23 #include "nav2_regulated_pure_pursuit_controller/regulated_pure_pursuit_controller.hpp"
24 #include "nav2_core/exceptions.hpp"
25 #include "nav2_util/node_utils.hpp"
26 #include "nav2_util/geometry_utils.hpp"
27 #include "nav2_costmap_2d/costmap_filters/filter_values.hpp"
33 using nav2_util::declare_parameter_if_not_declared;
34 using nav2_util::geometry_utils::euclidean_distance;
36 using rcl_interfaces::msg::ParameterType;
38 namespace nav2_regulated_pure_pursuit_controller
41 void RegulatedPurePursuitController::configure(
42 const rclcpp_lifecycle::LifecycleNode::WeakPtr & parent,
43 std::string name, std::shared_ptr<tf2_ros::Buffer> tf,
44 std::shared_ptr<nav2_costmap_2d::Costmap2DROS> costmap_ros)
46 auto node = parent.lock();
52 costmap_ros_ = costmap_ros;
53 costmap_ = costmap_ros_->getCostmap();
56 logger_ = node->get_logger();
57 clock_ = node->get_clock();
59 double transform_tolerance = 0.1;
60 double control_frequency = 20.0;
61 goal_dist_tol_ = 0.25;
63 declare_parameter_if_not_declared(
64 node, plugin_name_ +
".desired_linear_vel", rclcpp::ParameterValue(0.5));
65 declare_parameter_if_not_declared(
66 node, plugin_name_ +
".lookahead_dist", rclcpp::ParameterValue(0.6));
67 declare_parameter_if_not_declared(
68 node, plugin_name_ +
".min_lookahead_dist", rclcpp::ParameterValue(0.3));
69 declare_parameter_if_not_declared(
70 node, plugin_name_ +
".max_lookahead_dist", rclcpp::ParameterValue(0.9));
71 declare_parameter_if_not_declared(
72 node, plugin_name_ +
".lookahead_time", rclcpp::ParameterValue(1.5));
73 declare_parameter_if_not_declared(
74 node, plugin_name_ +
".rotate_to_heading_angular_vel", rclcpp::ParameterValue(1.8));
75 declare_parameter_if_not_declared(
76 node, plugin_name_ +
".transform_tolerance", rclcpp::ParameterValue(0.1));
77 declare_parameter_if_not_declared(
78 node, plugin_name_ +
".use_velocity_scaled_lookahead_dist",
79 rclcpp::ParameterValue(
false));
80 declare_parameter_if_not_declared(
81 node, plugin_name_ +
".min_approach_linear_velocity", rclcpp::ParameterValue(0.05));
82 declare_parameter_if_not_declared(
83 node, plugin_name_ +
".approach_velocity_scaling_dist",
84 rclcpp::ParameterValue(0.6));
85 declare_parameter_if_not_declared(
86 node, plugin_name_ +
".max_allowed_time_to_collision_up_to_carrot",
87 rclcpp::ParameterValue(1.0));
88 declare_parameter_if_not_declared(
89 node, plugin_name_ +
".use_collision_detection",
90 rclcpp::ParameterValue(
true));
91 declare_parameter_if_not_declared(
92 node, plugin_name_ +
".use_regulated_linear_velocity_scaling", rclcpp::ParameterValue(
true));
93 declare_parameter_if_not_declared(
94 node, plugin_name_ +
".use_cost_regulated_linear_velocity_scaling",
95 rclcpp::ParameterValue(
true));
96 declare_parameter_if_not_declared(
97 node, plugin_name_ +
".cost_scaling_dist", rclcpp::ParameterValue(0.6));
98 declare_parameter_if_not_declared(
99 node, plugin_name_ +
".cost_scaling_gain", rclcpp::ParameterValue(1.0));
100 declare_parameter_if_not_declared(
101 node, plugin_name_ +
".inflation_cost_scaling_factor", rclcpp::ParameterValue(3.0));
102 declare_parameter_if_not_declared(
103 node, plugin_name_ +
".regulated_linear_scaling_min_radius", rclcpp::ParameterValue(0.90));
104 declare_parameter_if_not_declared(
105 node, plugin_name_ +
".regulated_linear_scaling_min_speed", rclcpp::ParameterValue(0.25));
106 declare_parameter_if_not_declared(
107 node, plugin_name_ +
".use_rotate_to_heading", rclcpp::ParameterValue(
true));
108 declare_parameter_if_not_declared(
109 node, plugin_name_ +
".rotate_to_heading_min_angle", rclcpp::ParameterValue(0.785));
110 declare_parameter_if_not_declared(
111 node, plugin_name_ +
".max_angular_accel", rclcpp::ParameterValue(3.2));
112 declare_parameter_if_not_declared(
113 node, plugin_name_ +
".allow_reversing", rclcpp::ParameterValue(
false));
114 declare_parameter_if_not_declared(
115 node, plugin_name_ +
".max_robot_pose_search_dist",
116 rclcpp::ParameterValue(getCostmapMaxExtent()));
117 declare_parameter_if_not_declared(
118 node, plugin_name_ +
".use_interpolation",
119 rclcpp::ParameterValue(
true));
121 node->get_parameter(plugin_name_ +
".desired_linear_vel", desired_linear_vel_);
122 base_desired_linear_vel_ = desired_linear_vel_;
123 node->get_parameter(plugin_name_ +
".lookahead_dist", lookahead_dist_);
124 node->get_parameter(plugin_name_ +
".min_lookahead_dist", min_lookahead_dist_);
125 node->get_parameter(plugin_name_ +
".max_lookahead_dist", max_lookahead_dist_);
126 node->get_parameter(plugin_name_ +
".lookahead_time", lookahead_time_);
128 plugin_name_ +
".rotate_to_heading_angular_vel",
129 rotate_to_heading_angular_vel_);
130 node->get_parameter(plugin_name_ +
".transform_tolerance", transform_tolerance);
132 plugin_name_ +
".use_velocity_scaled_lookahead_dist",
133 use_velocity_scaled_lookahead_dist_);
135 plugin_name_ +
".min_approach_linear_velocity",
136 min_approach_linear_velocity_);
138 plugin_name_ +
".approach_velocity_scaling_dist",
139 approach_velocity_scaling_dist_);
140 if (approach_velocity_scaling_dist_ > costmap_->getSizeInMetersX() / 2.0) {
142 logger_,
"approach_velocity_scaling_dist is larger than forward costmap extent, "
143 "leading to permanent slowdown");
146 plugin_name_ +
".max_allowed_time_to_collision_up_to_carrot",
147 max_allowed_time_to_collision_up_to_carrot_);
149 plugin_name_ +
".use_collision_detection",
150 use_collision_detection_);
152 plugin_name_ +
".use_regulated_linear_velocity_scaling",
153 use_regulated_linear_velocity_scaling_);
155 plugin_name_ +
".use_cost_regulated_linear_velocity_scaling",
156 use_cost_regulated_linear_velocity_scaling_);
157 node->get_parameter(plugin_name_ +
".cost_scaling_dist", cost_scaling_dist_);
158 node->get_parameter(plugin_name_ +
".cost_scaling_gain", cost_scaling_gain_);
160 plugin_name_ +
".inflation_cost_scaling_factor",
161 inflation_cost_scaling_factor_);
163 plugin_name_ +
".regulated_linear_scaling_min_radius",
164 regulated_linear_scaling_min_radius_);
166 plugin_name_ +
".regulated_linear_scaling_min_speed",
167 regulated_linear_scaling_min_speed_);
168 node->get_parameter(plugin_name_ +
".use_rotate_to_heading", use_rotate_to_heading_);
169 node->get_parameter(plugin_name_ +
".rotate_to_heading_min_angle", rotate_to_heading_min_angle_);
170 node->get_parameter(plugin_name_ +
".max_angular_accel", max_angular_accel_);
171 node->get_parameter(plugin_name_ +
".allow_reversing", allow_reversing_);
172 node->get_parameter(
"controller_frequency", control_frequency);
174 plugin_name_ +
".max_robot_pose_search_dist",
175 max_robot_pose_search_dist_);
177 plugin_name_ +
".use_interpolation",
180 transform_tolerance_ = tf2::durationFromSec(transform_tolerance);
181 control_duration_ = 1.0 / control_frequency;
183 if (inflation_cost_scaling_factor_ <= 0.0) {
185 logger_,
"The value inflation_cost_scaling_factor is incorrectly set, "
186 "it should be >0. Disabling cost regulated linear velocity scaling.");
187 use_cost_regulated_linear_velocity_scaling_ =
false;
193 if (use_rotate_to_heading_ && allow_reversing_) {
195 logger_,
"Disabling reversing. Both use_rotate_to_heading and allow_reversing "
196 "parameter cannot be set to true. By default setting use_rotate_to_heading true");
197 allow_reversing_ =
false;
200 global_path_pub_ = node->create_publisher<nav_msgs::msg::Path>(
"received_global_plan", 1);
201 carrot_pub_ = node->create_publisher<geometry_msgs::msg::PointStamped>(
"lookahead_point", 1);
202 carrot_arc_pub_ = node->create_publisher<nav_msgs::msg::Path>(
"lookahead_collision_arc", 1);
205 collision_checker_ = std::make_unique<nav2_costmap_2d::
206 FootprintCollisionChecker<nav2_costmap_2d::Costmap2D *>>(costmap_);
207 collision_checker_->setCostmap(costmap_);
210 void RegulatedPurePursuitController::cleanup()
214 "Cleaning up controller: %s of type"
215 " regulated_pure_pursuit_controller::RegulatedPurePursuitController",
216 plugin_name_.c_str());
217 global_path_pub_.reset();
219 carrot_arc_pub_.reset();
222 void RegulatedPurePursuitController::activate()
226 "Activating controller: %s of type "
227 "regulated_pure_pursuit_controller::RegulatedPurePursuitController",
228 plugin_name_.c_str());
229 global_path_pub_->on_activate();
230 carrot_pub_->on_activate();
231 carrot_arc_pub_->on_activate();
233 auto node = node_.lock();
234 dyn_params_handler_ = node->add_on_set_parameters_callback(
236 &RegulatedPurePursuitController::dynamicParametersCallback,
237 this, std::placeholders::_1));
240 void RegulatedPurePursuitController::deactivate()
244 "Deactivating controller: %s of type "
245 "regulated_pure_pursuit_controller::RegulatedPurePursuitController",
246 plugin_name_.c_str());
247 global_path_pub_->on_deactivate();
248 carrot_pub_->on_deactivate();
249 carrot_arc_pub_->on_deactivate();
250 dyn_params_handler_.reset();
253 std::unique_ptr<geometry_msgs::msg::PointStamped> RegulatedPurePursuitController::createCarrotMsg(
254 const geometry_msgs::msg::PoseStamped & carrot_pose)
256 auto carrot_msg = std::make_unique<geometry_msgs::msg::PointStamped>();
257 carrot_msg->header = carrot_pose.header;
258 carrot_msg->point.x = carrot_pose.pose.position.x;
259 carrot_msg->point.y = carrot_pose.pose.position.y;
260 carrot_msg->point.z = 0.01;
264 double RegulatedPurePursuitController::getLookAheadDistance(
265 const geometry_msgs::msg::Twist & speed)
269 double lookahead_dist = lookahead_dist_;
270 if (use_velocity_scaled_lookahead_dist_) {
271 lookahead_dist = fabs(speed.linear.x) * lookahead_time_;
272 lookahead_dist = std::clamp(lookahead_dist, min_lookahead_dist_, max_lookahead_dist_);
275 return lookahead_dist;
278 geometry_msgs::msg::TwistStamped RegulatedPurePursuitController::computeVelocityCommands(
279 const geometry_msgs::msg::PoseStamped & pose,
280 const geometry_msgs::msg::Twist & speed,
283 std::lock_guard<std::mutex> lock_reinit(mutex_);
286 std::unique_lock<nav2_costmap_2d::Costmap2D::mutex_t> lock(*(costmap->getMutex()));
289 geometry_msgs::msg::Pose pose_tolerance;
290 geometry_msgs::msg::Twist vel_tolerance;
291 if (!goal_checker->
getTolerances(pose_tolerance, vel_tolerance)) {
292 RCLCPP_WARN(logger_,
"Unable to retrieve goal checker's tolerances!");
294 goal_dist_tol_ = pose_tolerance.position.x;
298 auto transformed_plan = transformGlobalPlan(pose);
301 double lookahead_dist = getLookAheadDistance(speed);
304 if (allow_reversing_) {
306 double dist_to_cusp = findVelocitySignChange(transformed_plan);
309 if (dist_to_cusp < lookahead_dist) {
310 lookahead_dist = dist_to_cusp;
314 auto carrot_pose = getLookAheadPoint(lookahead_dist, transformed_plan);
315 carrot_pub_->publish(createCarrotMsg(carrot_pose));
317 double linear_vel, angular_vel;
321 const double carrot_dist2 =
322 (carrot_pose.pose.position.x * carrot_pose.pose.position.x) +
323 (carrot_pose.pose.position.y * carrot_pose.pose.position.y);
326 double curvature = 0.0;
327 if (carrot_dist2 > 0.001) {
328 curvature = 2.0 * carrot_pose.pose.position.y / carrot_dist2;
333 if (allow_reversing_) {
334 sign = carrot_pose.pose.position.x >= 0.0 ? 1.0 : -1.0;
337 linear_vel = desired_linear_vel_;
340 double angle_to_heading;
341 if (shouldRotateToGoalHeading(carrot_pose)) {
342 double angle_to_goal = tf2::getYaw(transformed_plan.poses.back().pose.orientation);
343 rotateToHeading(linear_vel, angular_vel, angle_to_goal, speed);
344 }
else if (shouldRotateToPath(carrot_pose, angle_to_heading)) {
345 rotateToHeading(linear_vel, angular_vel, angle_to_heading, speed);
349 costAtPose(pose.pose.position.x, pose.pose.position.y), transformed_plan,
353 angular_vel = linear_vel * curvature;
357 const double & carrot_dist = hypot(carrot_pose.pose.position.x, carrot_pose.pose.position.y);
358 if (use_collision_detection_ && isCollisionImminent(pose, linear_vel, angular_vel, carrot_dist)) {
363 geometry_msgs::msg::TwistStamped cmd_vel;
364 cmd_vel.header = pose.header;
365 cmd_vel.twist.linear.x = linear_vel;
366 cmd_vel.twist.angular.z = angular_vel;
370 bool RegulatedPurePursuitController::shouldRotateToPath(
371 const geometry_msgs::msg::PoseStamped & carrot_pose,
double & angle_to_path)
374 angle_to_path = atan2(carrot_pose.pose.position.y, carrot_pose.pose.position.x);
375 return use_rotate_to_heading_ && fabs(angle_to_path) > rotate_to_heading_min_angle_;
378 bool RegulatedPurePursuitController::shouldRotateToGoalHeading(
379 const geometry_msgs::msg::PoseStamped & carrot_pose)
382 double dist_to_goal = std::hypot(carrot_pose.pose.position.x, carrot_pose.pose.position.y);
383 return use_rotate_to_heading_ && dist_to_goal < goal_dist_tol_;
386 void RegulatedPurePursuitController::rotateToHeading(
387 double & linear_vel,
double & angular_vel,
388 const double & angle_to_path,
const geometry_msgs::msg::Twist & curr_speed)
392 const double sign = angle_to_path > 0.0 ? 1.0 : -1.0;
393 angular_vel = sign * rotate_to_heading_angular_vel_;
395 const double & dt = control_duration_;
396 const double min_feasible_angular_speed = curr_speed.angular.z - max_angular_accel_ * dt;
397 const double max_feasible_angular_speed = curr_speed.angular.z + max_angular_accel_ * dt;
398 angular_vel = std::clamp(angular_vel, min_feasible_angular_speed, max_feasible_angular_speed);
401 geometry_msgs::msg::Point RegulatedPurePursuitController::circleSegmentIntersection(
402 const geometry_msgs::msg::Point & p1,
403 const geometry_msgs::msg::Point & p2,
421 double dr2 = dx * dx + dy * dy;
422 double D = x1 * y2 - x2 * y1;
425 double d1 = x1 * x1 + y1 * y1;
426 double d2 = x2 * x2 + y2 * y2;
429 geometry_msgs::msg::Point p;
430 double sqrt_term = std::sqrt(r * r * dr2 - D * D);
431 p.x = (D * dy + std::copysign(1.0, dd) * dx * sqrt_term) / dr2;
432 p.y = (-D * dx + std::copysign(1.0, dd) * dy * sqrt_term) / dr2;
436 geometry_msgs::msg::PoseStamped RegulatedPurePursuitController::getLookAheadPoint(
437 const double & lookahead_dist,
438 const nav_msgs::msg::Path & transformed_plan)
441 auto goal_pose_it = std::find_if(
442 transformed_plan.poses.begin(), transformed_plan.poses.end(), [&](
const auto & ps) {
443 return hypot(ps.pose.position.x, ps.pose.position.y) >= lookahead_dist;
447 if (goal_pose_it == transformed_plan.poses.end()) {
448 goal_pose_it = std::prev(transformed_plan.poses.end());
449 }
else if (use_interpolation_ && goal_pose_it != transformed_plan.poses.begin()) {
455 auto prev_pose_it = std::prev(goal_pose_it);
456 auto point = circleSegmentIntersection(
457 prev_pose_it->pose.position,
458 goal_pose_it->pose.position, lookahead_dist);
459 geometry_msgs::msg::PoseStamped pose;
460 pose.header.frame_id = prev_pose_it->header.frame_id;
461 pose.header.stamp = goal_pose_it->header.stamp;
462 pose.pose.position = point;
466 return *goal_pose_it;
469 bool RegulatedPurePursuitController::isCollisionImminent(
470 const geometry_msgs::msg::PoseStamped & robot_pose,
471 const double & linear_vel,
const double & angular_vel,
472 const double & carrot_dist)
479 robot_pose.pose.position.x, robot_pose.pose.position.y,
480 tf2::getYaw(robot_pose.pose.orientation)))
486 nav_msgs::msg::Path arc_pts_msg;
487 arc_pts_msg.header.frame_id = costmap_ros_->getGlobalFrameID();
488 arc_pts_msg.header.stamp = robot_pose.header.stamp;
489 geometry_msgs::msg::PoseStamped pose_msg;
490 pose_msg.header.frame_id = arc_pts_msg.header.frame_id;
491 pose_msg.header.stamp = arc_pts_msg.header.stamp;
493 double projection_time = 0.0;
494 if (fabs(linear_vel) < 0.01 && fabs(angular_vel) > 0.01) {
501 double max_radius = costmap_ros_->getLayeredCostmap()->getCircumscribedRadius();
503 2.0 * sin((costmap_->getResolution() / 2) / max_radius) / fabs(angular_vel);
506 projection_time = costmap_->getResolution() / fabs(linear_vel);
509 const geometry_msgs::msg::Point & robot_xy = robot_pose.pose.position;
510 geometry_msgs::msg::Pose2D curr_pose;
511 curr_pose.x = robot_pose.pose.position.x;
512 curr_pose.y = robot_pose.pose.position.y;
513 curr_pose.theta = tf2::getYaw(robot_pose.pose.orientation);
517 while (i * projection_time < max_allowed_time_to_collision_up_to_carrot_) {
521 curr_pose.x += projection_time * (linear_vel * cos(curr_pose.theta));
522 curr_pose.y += projection_time * (linear_vel * sin(curr_pose.theta));
523 curr_pose.theta += projection_time * angular_vel;
526 if (hypot(curr_pose.x - robot_xy.x, curr_pose.y - robot_xy.y) > carrot_dist) {
531 pose_msg.pose.position.x = curr_pose.x;
532 pose_msg.pose.position.y = curr_pose.y;
533 pose_msg.pose.position.z = 0.01;
534 arc_pts_msg.poses.push_back(pose_msg);
537 if (inCollision(curr_pose.x, curr_pose.y, curr_pose.theta)) {
538 carrot_arc_pub_->publish(arc_pts_msg);
543 carrot_arc_pub_->publish(arc_pts_msg);
548 bool RegulatedPurePursuitController::inCollision(
551 const double & theta)
555 if (!costmap_->worldToMap(x, y, mx, my)) {
556 RCLCPP_WARN_THROTTLE(
557 logger_, *(clock_), 30000,
558 "The dimensions of the costmap is too small to successfully check for "
559 "collisions as far ahead as requested. Proceed at your own risk, slow the robot, or "
560 "increase your costmap size.");
564 double footprint_cost = collision_checker_->footprintCostAtPose(
565 x, y, theta, costmap_ros_->getRobotFootprint());
566 if (footprint_cost ==
static_cast<double>(NO_INFORMATION) &&
567 costmap_ros_->getLayeredCostmap()->isTrackingUnknown())
573 return footprint_cost >=
static_cast<double>(LETHAL_OBSTACLE);
576 double RegulatedPurePursuitController::costAtPose(
const double & x,
const double & y)
580 if (!costmap_->worldToMap(x, y, mx, my)) {
583 "The dimensions of the costmap is too small to fully include your robot's footprint, "
584 "thusly the robot cannot proceed further");
586 "RegulatedPurePursuitController: Dimensions of the costmap are too small "
587 "to encapsulate the robot footprint at current speeds!");
590 unsigned char cost = costmap_->getCost(mx, my);
591 return static_cast<double>(cost);
594 double RegulatedPurePursuitController::approachVelocityScalingFactor(
595 const nav_msgs::msg::Path & transformed_path
600 double remaining_distance = nav2_util::geometry_utils::calculate_path_length(transformed_path);
601 if (remaining_distance < approach_velocity_scaling_dist_) {
602 auto & last = transformed_path.poses.back();
605 double distance_to_last_pose = std::hypot(last.pose.position.x, last.pose.position.y);
606 return distance_to_last_pose / approach_velocity_scaling_dist_;
612 void RegulatedPurePursuitController::applyApproachVelocityScaling(
613 const nav_msgs::msg::Path & path,
617 double approach_vel = linear_vel;
618 double velocity_scaling = approachVelocityScalingFactor(path);
619 double unbounded_vel = approach_vel * velocity_scaling;
620 if (unbounded_vel < min_approach_linear_velocity_) {
621 approach_vel = min_approach_linear_velocity_;
623 approach_vel *= velocity_scaling;
627 linear_vel = std::min(linear_vel, approach_vel);
630 void RegulatedPurePursuitController::applyConstraints(
631 const double & curvature,
const geometry_msgs::msg::Twist & ,
632 const double & pose_cost,
const nav_msgs::msg::Path & path,
double & linear_vel,
double & sign)
634 double curvature_vel = linear_vel;
635 double cost_vel = linear_vel;
638 const double radius = fabs(1.0 / curvature);
639 const double & min_rad = regulated_linear_scaling_min_radius_;
640 if (use_regulated_linear_velocity_scaling_ && radius < min_rad) {
641 curvature_vel *= 1.0 - (fabs(radius - min_rad) / min_rad);
645 if (use_cost_regulated_linear_velocity_scaling_ &&
646 pose_cost !=
static_cast<double>(NO_INFORMATION) &&
647 pose_cost !=
static_cast<double>(FREE_SPACE))
649 const double inscribed_radius = costmap_ros_->getLayeredCostmap()->getInscribedRadius();
650 const double min_distance_to_obstacle = (-1.0 / inflation_cost_scaling_factor_) *
651 std::log(pose_cost / (INSCRIBED_INFLATED_OBSTACLE - 1)) + inscribed_radius;
653 if (min_distance_to_obstacle < cost_scaling_dist_) {
654 cost_vel *= cost_scaling_gain_ * min_distance_to_obstacle / cost_scaling_dist_;
659 linear_vel = std::min(cost_vel, curvature_vel);
660 linear_vel = std::max(linear_vel, regulated_linear_scaling_min_speed_);
662 applyApproachVelocityScaling(path, linear_vel);
665 linear_vel = std::clamp(fabs(linear_vel), 0.0, desired_linear_vel_);
666 linear_vel = sign * linear_vel;
669 void RegulatedPurePursuitController::setPlan(
const nav_msgs::msg::Path & path)
674 void RegulatedPurePursuitController::setSpeedLimit(
675 const double & speed_limit,
676 const bool & percentage)
678 if (speed_limit == nav2_costmap_2d::NO_SPEED_LIMIT) {
680 desired_linear_vel_ = base_desired_linear_vel_;
684 desired_linear_vel_ = base_desired_linear_vel_ * speed_limit / 100.0;
687 desired_linear_vel_ = speed_limit;
692 nav_msgs::msg::Path RegulatedPurePursuitController::transformGlobalPlan(
693 const geometry_msgs::msg::PoseStamped & pose)
695 if (global_plan_.poses.empty()) {
700 geometry_msgs::msg::PoseStamped robot_pose;
701 if (!transformPose(global_plan_.header.frame_id, pose, robot_pose)) {
706 double max_costmap_extent = getCostmapMaxExtent();
708 auto closest_pose_upper_bound =
709 nav2_util::geometry_utils::first_after_integrated_distance(
710 global_plan_.poses.begin(), global_plan_.poses.end(), max_robot_pose_search_dist_);
715 auto transformation_begin =
716 nav2_util::geometry_utils::min_by(
717 global_plan_.poses.begin(), closest_pose_upper_bound,
718 [&robot_pose](
const geometry_msgs::msg::PoseStamped & ps) {
719 return euclidean_distance(robot_pose, ps);
723 auto transformation_end = std::find_if(
724 transformation_begin, global_plan_.poses.end(),
725 [&](
const auto & pose) {
726 return euclidean_distance(pose, robot_pose) > max_costmap_extent;
730 auto transformGlobalPoseToLocal = [&](
const auto & global_plan_pose) {
731 geometry_msgs::msg::PoseStamped stamped_pose, transformed_pose;
732 stamped_pose.header.frame_id = global_plan_.header.frame_id;
733 stamped_pose.header.stamp = robot_pose.header.stamp;
734 stamped_pose.pose = global_plan_pose.pose;
735 transformPose(costmap_ros_->getBaseFrameID(), stamped_pose, transformed_pose);
736 transformed_pose.pose.position.z = 0.0;
737 return transformed_pose;
741 nav_msgs::msg::Path transformed_plan;
743 transformation_begin, transformation_end,
744 std::back_inserter(transformed_plan.poses),
745 transformGlobalPoseToLocal);
746 transformed_plan.header.frame_id = costmap_ros_->getBaseFrameID();
747 transformed_plan.header.stamp = robot_pose.header.stamp;
751 global_plan_.poses.erase(begin(global_plan_.poses), transformation_begin);
752 global_path_pub_->publish(transformed_plan);
754 if (transformed_plan.poses.empty()) {
758 return transformed_plan;
761 double RegulatedPurePursuitController::findVelocitySignChange(
762 const nav_msgs::msg::Path & transformed_plan)
765 for (
unsigned int pose_id = 1; pose_id < transformed_plan.poses.size() - 1; ++pose_id) {
767 double oa_x = transformed_plan.poses[pose_id].pose.position.x -
768 transformed_plan.poses[pose_id - 1].pose.position.x;
769 double oa_y = transformed_plan.poses[pose_id].pose.position.y -
770 transformed_plan.poses[pose_id - 1].pose.position.y;
771 double ab_x = transformed_plan.poses[pose_id + 1].pose.position.x -
772 transformed_plan.poses[pose_id].pose.position.x;
773 double ab_y = transformed_plan.poses[pose_id + 1].pose.position.y -
774 transformed_plan.poses[pose_id].pose.position.y;
779 if ( (oa_x * ab_x) + (oa_y * ab_y) < 0.0) {
783 transformed_plan.poses[pose_id].pose.position.x,
784 transformed_plan.poses[pose_id].pose.position.y);
788 return std::numeric_limits<double>::max();
791 bool RegulatedPurePursuitController::transformPose(
792 const std::string frame,
793 const geometry_msgs::msg::PoseStamped & in_pose,
794 geometry_msgs::msg::PoseStamped & out_pose)
const
796 if (in_pose.header.frame_id == frame) {
802 tf_->transform(in_pose, out_pose, frame, transform_tolerance_);
803 out_pose.header.frame_id = frame;
805 }
catch (tf2::TransformException & ex) {
806 RCLCPP_ERROR(logger_,
"Exception in transformPose: %s", ex.what());
811 double RegulatedPurePursuitController::getCostmapMaxExtent()
const
813 const double max_costmap_dim_meters = std::max(
814 costmap_->getSizeInMetersX(), costmap_->getSizeInMetersY());
815 return max_costmap_dim_meters / 2.0;
819 rcl_interfaces::msg::SetParametersResult
820 RegulatedPurePursuitController::dynamicParametersCallback(
821 std::vector<rclcpp::Parameter> parameters)
823 rcl_interfaces::msg::SetParametersResult result;
824 std::lock_guard<std::mutex> lock_reinit(mutex_);
826 for (
auto parameter : parameters) {
827 const auto & type = parameter.get_type();
828 const auto & name = parameter.get_name();
830 if (type == ParameterType::PARAMETER_DOUBLE) {
831 if (name == plugin_name_ +
".inflation_cost_scaling_factor") {
832 if (parameter.as_double() <= 0.0) {
834 logger_,
"The value inflation_cost_scaling_factor is incorrectly set, "
835 "it should be >0. Ignoring parameter update.");
838 inflation_cost_scaling_factor_ = parameter.as_double();
839 }
else if (name == plugin_name_ +
".desired_linear_vel") {
840 desired_linear_vel_ = parameter.as_double();
841 base_desired_linear_vel_ = parameter.as_double();
842 }
else if (name == plugin_name_ +
".lookahead_dist") {
843 lookahead_dist_ = parameter.as_double();
844 }
else if (name == plugin_name_ +
".max_lookahead_dist") {
845 max_lookahead_dist_ = parameter.as_double();
846 }
else if (name == plugin_name_ +
".min_lookahead_dist") {
847 min_lookahead_dist_ = parameter.as_double();
848 }
else if (name == plugin_name_ +
".lookahead_time") {
849 lookahead_time_ = parameter.as_double();
850 }
else if (name == plugin_name_ +
".rotate_to_heading_angular_vel") {
851 rotate_to_heading_angular_vel_ = parameter.as_double();
852 }
else if (name == plugin_name_ +
".min_approach_linear_velocity") {
853 min_approach_linear_velocity_ = parameter.as_double();
854 }
else if (name == plugin_name_ +
".max_allowed_time_to_collision_up_to_carrot") {
855 max_allowed_time_to_collision_up_to_carrot_ = parameter.as_double();
856 }
else if (name == plugin_name_ +
".cost_scaling_dist") {
857 cost_scaling_dist_ = parameter.as_double();
858 }
else if (name == plugin_name_ +
".cost_scaling_gain") {
859 cost_scaling_gain_ = parameter.as_double();
860 }
else if (name == plugin_name_ +
".regulated_linear_scaling_min_radius") {
861 regulated_linear_scaling_min_radius_ = parameter.as_double();
862 }
else if (name == plugin_name_ +
".transform_tolerance") {
863 double transform_tolerance = parameter.as_double();
864 transform_tolerance_ = tf2::durationFromSec(transform_tolerance);
865 }
else if (name == plugin_name_ +
".regulated_linear_scaling_min_speed") {
866 regulated_linear_scaling_min_speed_ = parameter.as_double();
867 }
else if (name == plugin_name_ +
".max_angular_accel") {
868 max_angular_accel_ = parameter.as_double();
869 }
else if (name == plugin_name_ +
".rotate_to_heading_min_angle") {
870 rotate_to_heading_min_angle_ = parameter.as_double();
872 }
else if (type == ParameterType::PARAMETER_BOOL) {
873 if (name == plugin_name_ +
".use_velocity_scaled_lookahead_dist") {
874 use_velocity_scaled_lookahead_dist_ = parameter.as_bool();
875 }
else if (name == plugin_name_ +
".use_regulated_linear_velocity_scaling") {
876 use_regulated_linear_velocity_scaling_ = parameter.as_bool();
877 }
else if (name == plugin_name_ +
".use_cost_regulated_linear_velocity_scaling") {
878 use_cost_regulated_linear_velocity_scaling_ = parameter.as_bool();
879 }
else if (name == plugin_name_ +
".use_rotate_to_heading") {
880 if (parameter.as_bool() && allow_reversing_) {
882 logger_,
"Both use_rotate_to_heading and allow_reversing "
883 "parameter cannot be set to true. Rejecting parameter update.");
886 use_rotate_to_heading_ = parameter.as_bool();
887 }
else if (name == plugin_name_ +
".allow_reversing") {
888 if (use_rotate_to_heading_ && parameter.as_bool()) {
890 logger_,
"Both use_rotate_to_heading and allow_reversing "
891 "parameter cannot be set to true. Rejecting parameter update.");
894 allow_reversing_ = parameter.as_bool();
899 result.successful =
true;
906 PLUGINLIB_EXPORT_CLASS(
controller interface that acts as a virtual base class for all controller plugins
Function-object for checking whether a goal has been reached.
virtual bool getTolerances(geometry_msgs::msg::Pose &pose_tolerance, geometry_msgs::msg::Twist &vel_tolerance)=0
Get the maximum possible tolerances used for goal checking in the major types. Any field without a va...
A 2D costmap provides a mapping between points in the world and their associated "costs".
Regulated pure pursuit controller plugin.