Skip to content

Commit fc7e086

Browse files
Adding disengagement threshold to rotation shim controller (ros-navigation#4699)
* adding disengagement threshold to rotation shim controller Signed-off-by: Steve Macenski <[email protected]> * change default to 22.5 deg Signed-off-by: Steve Macenski <[email protected]> --------- Signed-off-by: Steve Macenski <[email protected]>
1 parent 3233c84 commit fc7e086

2 files changed

Lines changed: 14 additions & 4 deletions

File tree

nav2_rotation_shim_controller/include/nav2_rotation_shim_controller/nav2_rotation_shim_controller.hpp

Lines changed: 2 additions & 2 deletions
Original file line numberDiff line numberDiff line change
@@ -168,10 +168,10 @@ class RotationShimController : public nav2_core::Controller
168168
nav2_core::Controller::Ptr primary_controller_;
169169
bool path_updated_;
170170
nav_msgs::msg::Path current_path_;
171-
double forward_sampling_distance_, angular_dist_threshold_;
171+
double forward_sampling_distance_, angular_dist_threshold_, angular_disengage_threshold_;
172172
double rotate_to_heading_angular_vel_, max_angular_accel_;
173173
double control_duration_, simulate_ahead_time_;
174-
bool rotate_to_goal_heading_;
174+
bool rotate_to_goal_heading_, in_rotation_;
175175

176176
// Dynamic parameters handler
177177
std::mutex mutex_;

nav2_rotation_shim_controller/src/nav2_rotation_shim_controller.cpp

Lines changed: 12 additions & 2 deletions
Original file line numberDiff line numberDiff line change
@@ -34,7 +34,8 @@ namespace nav2_rotation_shim_controller
3434
RotationShimController::RotationShimController()
3535
: lp_loader_("nav2_core", "nav2_core::Controller"),
3636
primary_controller_(nullptr),
37-
path_updated_(false)
37+
path_updated_(false),
38+
in_rotation_(false)
3839
{
3940
}
4041

@@ -56,6 +57,8 @@ void RotationShimController::configure(
5657
double control_frequency;
5758
nav2_util::declare_parameter_if_not_declared(
5859
node, plugin_name_ + ".angular_dist_threshold", rclcpp::ParameterValue(0.785)); // 45 deg
60+
nav2_util::declare_parameter_if_not_declared(
61+
node, plugin_name_ + ".angular_disengage_threshold", rclcpp::ParameterValue(0.785 / 2.0));
5962
nav2_util::declare_parameter_if_not_declared(
6063
node, plugin_name_ + ".forward_sampling_distance", rclcpp::ParameterValue(0.5));
6164
nav2_util::declare_parameter_if_not_declared(
@@ -70,6 +73,7 @@ void RotationShimController::configure(
7073
node, plugin_name_ + ".rotate_to_goal_heading", rclcpp::ParameterValue(false));
7174

7275
node->get_parameter(plugin_name_ + ".angular_dist_threshold", angular_dist_threshold_);
76+
node->get_parameter(plugin_name_ + ".angular_disengage_threshold", angular_disengage_threshold_);
7377
node->get_parameter(plugin_name_ + ".forward_sampling_distance", forward_sampling_distance_);
7478
node->get_parameter(
7579
plugin_name_ + ".rotate_to_heading_angular_vel",
@@ -111,6 +115,7 @@ void RotationShimController::activate()
111115
plugin_name_.c_str());
112116

113117
primary_controller_->activate();
118+
in_rotation_ = false;
114119

115120
auto node = node_.lock();
116121
dyn_params_handler_ = node->add_on_set_parameters_callback(
@@ -197,10 +202,14 @@ geometry_msgs::msg::TwistStamped RotationShimController::computeVelocityCommands
197202

198203
double angular_distance_to_heading =
199204
std::atan2(sampled_pt_base.position.y, sampled_pt_base.position.x);
200-
if (fabs(angular_distance_to_heading) > angular_dist_threshold_) {
205+
206+
double angular_thresh =
207+
in_rotation_ ? angular_disengage_threshold_ : angular_dist_threshold_;
208+
if (abs(angular_distance_to_heading) > angular_thresh) {
201209
RCLCPP_DEBUG(
202210
logger_,
203211
"Robot is not within the new path's rough heading, rotating to heading...");
212+
in_rotation_ = true;
204213
return computeRotateToHeadingCommand(angular_distance_to_heading, pose, velocity);
205214
} else {
206215
RCLCPP_DEBUG(
@@ -219,6 +228,7 @@ geometry_msgs::msg::TwistStamped RotationShimController::computeVelocityCommands
219228
}
220229

221230
// If at this point, use the primary controller to path track
231+
in_rotation_ = false;
222232
return primary_controller_->computeVelocityCommands(pose, velocity, goal_checker);
223233
}
224234

0 commit comments

Comments
 (0)