Skip to content

Commit c3a421e

Browse files
ikhanncheriehu
authored andcommitted
Added parameter rotate_to_heading_once (ros-navigation#4721)
Signed-off-by: Daniil Khaninaev <khaninaev@yahoo.com>
1 parent 9db4781 commit c3a421e

File tree

3 files changed

+84
-3
lines changed

3 files changed

+84
-3
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
@@ -152,6 +152,13 @@ class RotationShimController : public nav2_core::Controller
152152
const double & angular_distance_to_heading,
153153
const geometry_msgs::msg::PoseStamped & pose);
154154

155+
/**
156+
* @brief Checks if the goal has changed based on the given path.
157+
* @param path The path to compare with the current goal.
158+
* @return True if the goal has changed, false otherwise.
159+
*/
160+
bool isGoalChanged(const nav_msgs::msg::Path & path);
161+
155162
/**
156163
* @brief Callback executed when a parameter change is detected
157164
* @param event ParameterEvent message
@@ -175,7 +182,7 @@ class RotationShimController : public nav2_core::Controller
175182
double forward_sampling_distance_, angular_dist_threshold_, angular_disengage_threshold_;
176183
double rotate_to_heading_angular_vel_, max_angular_accel_;
177184
double control_duration_, simulate_ahead_time_;
178-
bool rotate_to_goal_heading_, in_rotation_;
185+
bool rotate_to_goal_heading_, in_rotation_, rotate_to_heading_once_;
179186

180187
// Dynamic parameters handler
181188
std::mutex mutex_;

nav2_rotation_shim_controller/src/nav2_rotation_shim_controller.cpp

Lines changed: 17 additions & 1 deletion
Original file line numberDiff line numberDiff line change
@@ -67,6 +67,8 @@ void RotationShimController::configure(
6767
node, plugin_name_ + ".primary_controller", rclcpp::PARAMETER_STRING);
6868
nav2_util::declare_parameter_if_not_declared(
6969
node, plugin_name_ + ".rotate_to_goal_heading", rclcpp::ParameterValue(false));
70+
nav2_util::declare_parameter_if_not_declared(
71+
node, plugin_name_ + ".rotate_to_heading_once", rclcpp::ParameterValue(false));
7072

7173
node->get_parameter(plugin_name_ + ".angular_dist_threshold", angular_dist_threshold_);
7274
node->get_parameter(plugin_name_ + ".angular_disengage_threshold", angular_disengage_threshold_);
@@ -82,6 +84,7 @@ void RotationShimController::configure(
8284
control_duration_ = 1.0 / control_frequency;
8385

8486
node->get_parameter(plugin_name_ + ".rotate_to_goal_heading", rotate_to_goal_heading_);
87+
node->get_parameter(plugin_name_ + ".rotate_to_heading_once", rotate_to_heading_once_);
8588

8689
try {
8790
primary_controller_ = lp_loader_.createUniqueInstance(primary_controller);
@@ -333,9 +336,20 @@ void RotationShimController::isCollisionFree(
333336
}
334337
}
335338

339+
bool RotationShimController::isGoalChanged(const nav_msgs::msg::Path & path)
340+
{
341+
// Return true if rotating or if the current path is empty
342+
if (in_rotation_ || current_path_.poses.empty()) {
343+
return true;
344+
}
345+
346+
// Check if the last pose of the current and new paths differ
347+
return current_path_.poses.back().pose != path.poses.back().pose;
348+
}
349+
336350
void RotationShimController::setPlan(const nav_msgs::msg::Path & path)
337351
{
338-
path_updated_ = true;
352+
path_updated_ = rotate_to_heading_once_ ? isGoalChanged(path) : true;
339353
current_path_ = path;
340354
primary_controller_->setPlan(path);
341355
}
@@ -370,6 +384,8 @@ RotationShimController::dynamicParametersCallback(std::vector<rclcpp::Parameter>
370384
} else if (type == ParameterType::PARAMETER_BOOL) {
371385
if (name == plugin_name_ + ".rotate_to_goal_heading") {
372386
rotate_to_goal_heading_ = parameter.as_bool();
387+
} else if (name == plugin_name_ + ".rotate_to_heading_once") {
388+
rotate_to_heading_once_ = parameter.as_bool();
373389
}
374390
}
375391
}

nav2_rotation_shim_controller/test/test_shim_controller.cpp

Lines changed: 59 additions & 1 deletion
Original file line numberDiff line numberDiff line change
@@ -62,6 +62,11 @@ class RotationShimShim : public nav2_rotation_shim_controller::RotationShimContr
6262
return getSampledPathPt();
6363
}
6464

65+
bool isGoalChangedWrapper(const nav_msgs::msg::Path & path)
66+
{
67+
return isGoalChanged(path);
68+
}
69+
6570
geometry_msgs::msg::Pose transformPoseToBaseFrameWrapper(geometry_msgs::msg::PoseStamped pt)
6671
{
6772
return transformPoseToBaseFrame(pt);
@@ -382,6 +387,57 @@ TEST(RotationShimControllerTest, computeVelocityGoalRotationTests) {
382387
EXPECT_EQ(cmd_vel.twist.angular.z, 1.8);
383388
}
384389

390+
TEST(RotationShimControllerTest, isGoalChangedTest)
391+
{
392+
auto ctrl = std::make_shared<RotationShimShim>();
393+
auto node = std::make_shared<rclcpp_lifecycle::LifecycleNode>("ShimControllerTest");
394+
std::string name = "PathFollower";
395+
auto tf = std::make_shared<tf2_ros::Buffer>(node->get_clock());
396+
auto listener = std::make_shared<tf2_ros::TransformListener>(*tf, node, true);
397+
auto costmap = std::make_shared<nav2_costmap_2d::Costmap2DROS>("fake_costmap");
398+
rclcpp_lifecycle::State state;
399+
costmap->on_configure(state);
400+
auto tf_broadcaster = std::make_shared<tf2_ros::TransformBroadcaster>(node);
401+
402+
geometry_msgs::msg::TransformStamped transform;
403+
transform.header.frame_id = "base_link";
404+
transform.child_frame_id = "odom";
405+
transform.transform.rotation.x = 0.0;
406+
transform.transform.rotation.y = 0.0;
407+
transform.transform.rotation.z = 0.0;
408+
transform.transform.rotation.w = 1.0;
409+
tf_broadcaster->sendTransform(transform);
410+
411+
// set a valid primary controller so we can do lifecycle
412+
node->declare_parameter(
413+
"PathFollower.primary_controller",
414+
std::string("nav2_regulated_pure_pursuit_controller::RegulatedPurePursuitController"));
415+
node->declare_parameter(
416+
"PathFollower.rotate_to_heading_once",
417+
true);
418+
419+
auto controller = std::make_shared<RotationShimShim>();
420+
controller->configure(node, name, tf, costmap);
421+
controller->activate();
422+
423+
nav_msgs::msg::Path path;
424+
path.header.frame_id = "base_link";
425+
path.poses.resize(2);
426+
path.poses.back().pose.position.x = 2.0;
427+
path.poses.back().pose.position.y = 2.0;
428+
429+
// Test: Current path is empty, should return true
430+
EXPECT_EQ(controller->isGoalChangedWrapper(path), true);
431+
432+
// Test: Last pose of the current path is the same, should return false
433+
controller->setPlan(path);
434+
EXPECT_EQ(controller->isGoalChangedWrapper(path), false);
435+
436+
// Test: Last pose of the current path differs, should return true
437+
path.poses.back().pose.position.x = 3.0;
438+
EXPECT_EQ(controller->isGoalChangedWrapper(path), true);
439+
}
440+
385441
TEST(RotationShimControllerTest, testDynamicParameter)
386442
{
387443
auto node = std::make_shared<rclcpp_lifecycle::LifecycleNode>("ShimControllerTest");
@@ -412,7 +468,8 @@ TEST(RotationShimControllerTest, testDynamicParameter)
412468
rclcpp::Parameter("test.max_angular_accel", 7.0),
413469
rclcpp::Parameter("test.simulate_ahead_time", 7.0),
414470
rclcpp::Parameter("test.primary_controller", std::string("HI")),
415-
rclcpp::Parameter("test.rotate_to_goal_heading", true)});
471+
rclcpp::Parameter("test.rotate_to_goal_heading", true),
472+
rclcpp::Parameter("test.rotate_to_heading_once", true)});
416473

417474
rclcpp::spin_until_future_complete(
418475
node->get_node_base_interface(),
@@ -424,4 +481,5 @@ TEST(RotationShimControllerTest, testDynamicParameter)
424481
EXPECT_EQ(node->get_parameter("test.max_angular_accel").as_double(), 7.0);
425482
EXPECT_EQ(node->get_parameter("test.simulate_ahead_time").as_double(), 7.0);
426483
EXPECT_EQ(node->get_parameter("test.rotate_to_goal_heading").as_bool(), true);
484+
EXPECT_EQ(node->get_parameter("test.rotate_to_heading_once").as_bool(), true);
427485
}

0 commit comments

Comments
 (0)