@@ -30,7 +30,8 @@ namespace nav2_rotation_shim_controller
3030RotationShimController::RotationShimController ()
3131: lp_loader_(" nav2_core" , " nav2_core::Controller" ),
3232 primary_controller_ (nullptr ),
33- path_updated_(false )
33+ path_updated_(false ),
34+ in_rotation_(false )
3435{
3536}
3637
@@ -52,6 +53,8 @@ void RotationShimController::configure(
5253 double control_frequency;
5354 nav2_util::declare_parameter_if_not_declared (
5455 node, plugin_name_ + " .angular_dist_threshold" , rclcpp::ParameterValue (0.785 )); // 45 deg
56+ nav2_util::declare_parameter_if_not_declared (
57+ node, plugin_name_ + " .angular_disengage_threshold" , rclcpp::ParameterValue (0.785 ));
5558 nav2_util::declare_parameter_if_not_declared (
5659 node, plugin_name_ + " .forward_sampling_distance" , rclcpp::ParameterValue (0.5 ));
5760 nav2_util::declare_parameter_if_not_declared (
@@ -66,6 +69,7 @@ void RotationShimController::configure(
6669 node, plugin_name_ + " .rotate_to_goal_heading" , rclcpp::ParameterValue (false ));
6770
6871 node->get_parameter (plugin_name_ + " .angular_dist_threshold" , angular_dist_threshold_);
72+ node->get_parameter (plugin_name_ + " .angular_disengage_threshold" , angular_disengage_threshold_);
6973 node->get_parameter (plugin_name_ + " .forward_sampling_distance" , forward_sampling_distance_);
7074 node->get_parameter (
7175 plugin_name_ + " .rotate_to_heading_angular_vel" ,
@@ -107,6 +111,7 @@ void RotationShimController::activate()
107111 plugin_name_.c_str ());
108112
109113 primary_controller_->activate ();
114+ in_rotation_ = false ;
110115
111116 auto node = node_.lock ();
112117 dyn_params_handler_ = node->add_on_set_parameters_callback (
@@ -190,10 +195,14 @@ geometry_msgs::msg::TwistStamped RotationShimController::computeVelocityCommands
190195
191196 double angular_distance_to_heading =
192197 std::atan2 (sampled_pt_base.position .y , sampled_pt_base.position .x );
193- if (fabs (angular_distance_to_heading) > angular_dist_threshold_) {
198+
199+ double angular_thresh =
200+ in_rotation_ ? angular_disengage_threshold_ : angular_dist_threshold_;
201+ if (abs (angular_distance_to_heading) > angular_thresh) {
194202 RCLCPP_DEBUG (
195203 logger_,
196204 " Robot is not within the new path's rough heading, rotating to heading..." );
205+ in_rotation_ = true ;
197206 return computeRotateToHeadingCommand (angular_distance_to_heading, pose, velocity);
198207 } else {
199208 RCLCPP_DEBUG (
@@ -212,6 +221,7 @@ geometry_msgs::msg::TwistStamped RotationShimController::computeVelocityCommands
212221 }
213222
214223 // If at this point, use the primary controller to path track
224+ in_rotation_ = false ;
215225 return primary_controller_->computeVelocityCommands (pose, velocity, goal_checker);
216226}
217227
0 commit comments