@@ -71,6 +71,8 @@ void RotationShimController::configure(
7171 node, plugin_name_ + " .primary_controller" , rclcpp::PARAMETER_STRING);
7272 nav2_util::declare_parameter_if_not_declared (
7373 node, plugin_name_ + " .rotate_to_goal_heading" , rclcpp::ParameterValue (false ));
74+ nav2_util::declare_parameter_if_not_declared (
75+ node, plugin_name_ + " .rotate_to_heading_once" , rclcpp::ParameterValue (false ));
7476
7577 node->get_parameter (plugin_name_ + " .angular_dist_threshold" , angular_dist_threshold_);
7678 node->get_parameter (plugin_name_ + " .angular_disengage_threshold" , angular_disengage_threshold_);
@@ -86,6 +88,7 @@ void RotationShimController::configure(
8688 control_duration_ = 1.0 / control_frequency;
8789
8890 node->get_parameter (plugin_name_ + " .rotate_to_goal_heading" , rotate_to_goal_heading_);
91+ node->get_parameter (plugin_name_ + " .rotate_to_heading_once" , rotate_to_heading_once_);
8992
9093 try {
9194 primary_controller_ = lp_loader_.createUniqueInstance (primary_controller);
@@ -340,9 +343,21 @@ void RotationShimController::isCollisionFree(
340343 }
341344}
342345
346+ bool RotationShimController::isGoalChanged (const nav_msgs::msg::Path & path)
347+ {
348+ // Return true if rotating or if the current path is empty
349+ if (in_rotation_ || current_path_.poses .empty ())
350+ {
351+ return true ;
352+ }
353+
354+ // Check if the last pose of the current and new paths differ
355+ return current_path_.poses .back ().pose != path.poses .back ().pose ;
356+ }
357+
343358void RotationShimController::setPlan (const nav_msgs::msg::Path & path)
344359{
345- path_updated_ = true ;
360+ path_updated_ = rotate_to_heading_once_ ? isGoalChanged (path) : true ;
346361 current_path_ = path;
347362 primary_controller_->setPlan (path);
348363}
@@ -377,6 +392,8 @@ RotationShimController::dynamicParametersCallback(std::vector<rclcpp::Parameter>
377392 } else if (type == ParameterType::PARAMETER_BOOL) {
378393 if (name == plugin_name_ + " .rotate_to_goal_heading" ) {
379394 rotate_to_goal_heading_ = parameter.as_bool ();
395+ } else if (name == plugin_name_ + " .rotate_to_heading_once" ) {
396+ rotate_to_heading_once_ = parameter.as_bool ();
380397 }
381398 }
382399 }
0 commit comments