Skip to content

Commit 997d7c8

Browse files
mergify[bot]jadhm
andauthored
Add stateful to regulated pure pursuit controller (#5167) (#5181)
* add_stateful_to_regulated_pure_pursuit_controller * fix naming * fix naming left over * resolve comments * typo * add unit test for both cases stateful and not stateful --------- (cherry picked from commit fda475c) Signed-off-by: Jad haj mustafa <[email protected]> Co-authored-by: Jad Haj Mustafa <[email protected]>
1 parent c37ba58 commit 997d7c8

File tree

5 files changed

+54
-3
lines changed

5 files changed

+54
-3
lines changed

nav2_regulated_pure_pursuit_controller/include/nav2_regulated_pure_pursuit_controller/parameter_handler.hpp

Lines changed: 1 addition & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -61,6 +61,7 @@ struct Parameters
6161
bool interpolate_curvature_after_goal;
6262
bool use_collision_detection;
6363
double transform_tolerance;
64+
bool stateful;
6465
};
6566

6667
/**

nav2_regulated_pure_pursuit_controller/include/nav2_regulated_pure_pursuit_controller/regulated_pure_pursuit_controller.hpp

Lines changed: 1 addition & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -220,6 +220,7 @@ class RegulatedPurePursuitController : public nav2_core::Controller
220220
bool cancelling_ = false;
221221
bool finished_cancelling_ = false;
222222
bool is_rotating_to_heading_ = false;
223+
bool has_reached_xy_tolerance_ = false;
223224

224225
std::shared_ptr<rclcpp_lifecycle::LifecyclePublisher<nav_msgs::msg::Path>> global_path_pub_;
225226
std::shared_ptr<rclcpp_lifecycle::LifecyclePublisher<geometry_msgs::msg::PointStamped>>

nav2_regulated_pure_pursuit_controller/src/parameter_handler.cpp

Lines changed: 5 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -101,6 +101,8 @@ ParameterHandler::ParameterHandler(
101101
declare_parameter_if_not_declared(
102102
node, plugin_name_ + ".use_collision_detection",
103103
rclcpp::ParameterValue(true));
104+
declare_parameter_if_not_declared(
105+
node, plugin_name_ + ".stateful", rclcpp::ParameterValue(true));
104106

105107
node->get_parameter(plugin_name_ + ".desired_linear_vel", params_.desired_linear_vel);
106108
params_.base_desired_linear_vel = params_.desired_linear_vel;
@@ -181,6 +183,7 @@ ParameterHandler::ParameterHandler(
181183
node->get_parameter(
182184
plugin_name_ + ".use_collision_detection",
183185
params_.use_collision_detection);
186+
node->get_parameter(plugin_name_ + ".stateful", params_.stateful);
184187

185188
if (params_.inflation_cost_scaling_factor <= 0.0) {
186189
RCLCPP_WARN(
@@ -269,6 +272,8 @@ ParameterHandler::dynamicParametersCallback(
269272
params_.use_cost_regulated_linear_velocity_scaling = parameter.as_bool();
270273
} else if (name == plugin_name_ + ".use_collision_detection") {
271274
params_.use_collision_detection = parameter.as_bool();
275+
} else if (name == plugin_name_ + ".stateful") {
276+
params_.stateful = parameter.as_bool();
272277
} else if (name == plugin_name_ + ".use_rotate_to_heading") {
273278
params_.use_rotate_to_heading = parameter.as_bool();
274279
} else if (name == plugin_name_ + ".use_cancel_deceleration") {

nav2_regulated_pure_pursuit_controller/src/regulated_pure_pursuit_controller.cpp

Lines changed: 17 additions & 2 deletions
Original file line numberDiff line numberDiff line change
@@ -320,8 +320,21 @@ bool RegulatedPurePursuitController::shouldRotateToGoalHeading(
320320
const geometry_msgs::msg::PoseStamped & carrot_pose)
321321
{
322322
// Whether we should rotate robot to goal heading
323-
double dist_to_goal = std::hypot(carrot_pose.pose.position.x, carrot_pose.pose.position.y);
324-
return params_->use_rotate_to_heading && dist_to_goal < goal_dist_tol_;
323+
if (!params_->use_rotate_to_heading) {
324+
return false;
325+
}
326+
327+
double dist_to_goal = std::hypot(
328+
carrot_pose.pose.position.x, carrot_pose.pose.position.y);
329+
330+
if (params_->stateful) {
331+
if (!has_reached_xy_tolerance_ && dist_to_goal < goal_dist_tol_) {
332+
has_reached_xy_tolerance_ = true;
333+
}
334+
return has_reached_xy_tolerance_;
335+
}
336+
337+
return dist_to_goal < goal_dist_tol_;
325338
}
326339

327340
void RegulatedPurePursuitController::rotateToHeading(
@@ -466,6 +479,7 @@ void RegulatedPurePursuitController::applyConstraints(
466479

467480
void RegulatedPurePursuitController::setPlan(const nav_msgs::msg::Path & path)
468481
{
482+
has_reached_xy_tolerance_ = false;
469483
path_handler_->setPlan(path);
470484
}
471485

@@ -493,6 +507,7 @@ void RegulatedPurePursuitController::reset()
493507
{
494508
cancelling_ = false;
495509
finished_cancelling_ = false;
510+
has_reached_xy_tolerance_ = false;
496511
}
497512

498513
double RegulatedPurePursuitController::findVelocitySignChange(

nav2_regulated_pure_pursuit_controller/test/test_regulated_pp.cpp

Lines changed: 30 additions & 1 deletion
Original file line numberDiff line numberDiff line change
@@ -506,8 +506,14 @@ TEST(RegulatedPurePursuitTest, lookaheadAPI)
506506

507507
TEST(RegulatedPurePursuitTest, rotateTests)
508508
{
509+
// --------------------------
510+
// Non-Stateful Configuration
511+
// --------------------------
509512
auto ctrl = std::make_shared<BasicAPIRPP>();
510513
auto node = std::make_shared<rclcpp_lifecycle::LifecycleNode>("testRPP");
514+
nav2_util::declare_parameter_if_not_declared(
515+
node, "PathFollower.stateful", rclcpp::ParameterValue(false));
516+
511517
std::string name = "PathFollower";
512518
auto tf = std::make_shared<tf2_ros::Buffer>(node->get_clock());
513519
auto costmap = std::make_shared<nav2_costmap_2d::Costmap2DROS>("fake_costmap");
@@ -573,6 +579,27 @@ TEST(RegulatedPurePursuitTest, rotateTests)
573579
curr_speed.angular.z = 1.0;
574580
ctrl->rotateToHeadingWrapper(lin_v, ang_v, angle_to_path, curr_speed);
575581
EXPECT_NEAR(ang_v, 0.84, 0.01);
582+
583+
// -----------------------
584+
// Stateful Configuration
585+
// -----------------------
586+
node->set_parameter(
587+
rclcpp::Parameter("PathFollower.stateful", true));
588+
589+
ctrl->configure(node, name, tf, costmap);
590+
591+
// Start just outside tolerance
592+
carrot.pose.position.x = 0.0;
593+
carrot.pose.position.y = 0.26;
594+
EXPECT_EQ(ctrl->shouldRotateToGoalHeadingWrapper(carrot), false);
595+
596+
// Enter tolerance (should set internal flag)
597+
carrot.pose.position.y = 0.24;
598+
EXPECT_EQ(ctrl->shouldRotateToGoalHeadingWrapper(carrot), true);
599+
600+
// Move outside tolerance again - still expect true (due to persistent state)
601+
carrot.pose.position.y = 0.26;
602+
EXPECT_EQ(ctrl->shouldRotateToGoalHeadingWrapper(carrot), true);
576603
}
577604

578605
TEST(RegulatedPurePursuitTest, applyConstraints)
@@ -713,7 +740,8 @@ TEST(RegulatedPurePursuitTest, testDynamicParameter)
713740
rclcpp::Parameter("test.use_cost_regulated_linear_velocity_scaling", false),
714741
rclcpp::Parameter("test.inflation_cost_scaling_factor", 1.0),
715742
rclcpp::Parameter("test.allow_reversing", false),
716-
rclcpp::Parameter("test.use_rotate_to_heading", false)});
743+
rclcpp::Parameter("test.use_rotate_to_heading", false),
744+
rclcpp::Parameter("test.stateful", false)});
717745

718746
rclcpp::spin_until_future_complete(
719747
node->get_node_base_interface(),
@@ -744,6 +772,7 @@ TEST(RegulatedPurePursuitTest, testDynamicParameter)
744772
"test.use_cost_regulated_linear_velocity_scaling").as_bool(), false);
745773
EXPECT_EQ(node->get_parameter("test.allow_reversing").as_bool(), false);
746774
EXPECT_EQ(node->get_parameter("test.use_rotate_to_heading").as_bool(), false);
775+
EXPECT_EQ(node->get_parameter("test.stateful").as_bool(), false);
747776

748777
// Should fail
749778
auto results2 = rec_param->set_parameters_atomically(

0 commit comments

Comments
 (0)