Skip to content

Commit d1ec130

Browse files
committed
Added parameter rotate_to_heading_once
Signed-off-by: Daniil Khaninaev <[email protected]>
1 parent 682e089 commit d1ec130

File tree

2 files changed

+26
-2
lines changed

2 files changed

+26
-2
lines changed

nav2_rotation_shim_controller/include/nav2_rotation_shim_controller/nav2_rotation_shim_controller.hpp

Lines changed: 8 additions & 1 deletion
Original file line numberDiff line numberDiff line change
@@ -148,6 +148,13 @@ class RotationShimController : public nav2_core::Controller
148148
const double & angular_distance_to_heading,
149149
const geometry_msgs::msg::PoseStamped & pose);
150150

151+
/**
152+
* @brief Checks if the goal has changed based on the given path.
153+
* @param path The path to compare with the current goal.
154+
* @return True if the goal has changed, false otherwise.
155+
*/
156+
bool isGoalChanged(const nav_msgs::msg::Path & path);
157+
151158
/**
152159
* @brief Callback executed when a parameter change is detected
153160
* @param event ParameterEvent message
@@ -171,7 +178,7 @@ class RotationShimController : public nav2_core::Controller
171178
double forward_sampling_distance_, angular_dist_threshold_, angular_disengage_threshold_;
172179
double rotate_to_heading_angular_vel_, max_angular_accel_;
173180
double control_duration_, simulate_ahead_time_;
174-
bool rotate_to_goal_heading_, in_rotation_;
181+
bool rotate_to_goal_heading_, in_rotation_, rotate_to_heading_once_;
175182

176183
// Dynamic parameters handler
177184
std::mutex mutex_;

nav2_rotation_shim_controller/src/nav2_rotation_shim_controller.cpp

Lines changed: 18 additions & 1 deletion
Original file line numberDiff line numberDiff line change
@@ -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+
343358
void 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

Comments
 (0)