Nav2 Navigation Stack - rolling  main
ROS 2 Navigation Stack
regulated_pure_pursuit_controller.cpp
1 // Copyright (c) 2020 Shrijit Singh
2 // Copyright (c) 2020 Samsung Research America
3 //
4 // Licensed under the Apache License, Version 2.0 (the "License");
5 // you may not use this file except in compliance with the License.
6 // You may obtain a copy of the License at
7 //
8 // http://www.apache.org/licenses/LICENSE-2.0
9 //
10 // Unless required by applicable law or agreed to in writing, software
11 // distributed under the License is distributed on an "AS IS" BASIS,
12 // WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.
13 // See the License for the specific language governing permissions and
14 // limitations under the License.
15 
16 #include <algorithm>
17 #include <string>
18 #include <limits>
19 #include <memory>
20 #include <vector>
21 #include <utility>
22 
23 #include "angles/angles.h"
24 #include "nav2_regulated_pure_pursuit_controller/regulated_pure_pursuit_controller.hpp"
25 #include "nav2_core/controller_exceptions.hpp"
26 #include "nav2_ros_common/node_utils.hpp"
27 #include "nav2_util/geometry_utils.hpp"
28 #include "nav2_util/controller_utils.hpp"
29 #include "nav2_costmap_2d/costmap_filters/filter_values.hpp"
30 
31 using std::hypot;
32 using std::min;
33 using std::max;
34 using std::abs;
35 using namespace nav2_costmap_2d; // NOLINT
36 
37 namespace nav2_regulated_pure_pursuit_controller
38 {
39 
40 void RegulatedPurePursuitController::configure(
41  const nav2::LifecycleNode::WeakPtr & parent,
42  std::string name, std::shared_ptr<tf2_ros::Buffer> tf,
43  std::shared_ptr<nav2_costmap_2d::Costmap2DROS> costmap_ros)
44 {
45  auto node = parent.lock();
46  node_ = parent;
47  if (!node) {
48  throw nav2_core::ControllerException("Unable to lock node!");
49  }
50 
51  costmap_ros_ = costmap_ros;
52  costmap_ = costmap_ros_->getCostmap();
53  tf_ = tf;
54  plugin_name_ = name;
55  logger_ = node->get_logger();
56 
57  // Handles storage and dynamic configuration of parameters.
58  // Returns pointer to data current param settings.
59  param_handler_ = std::make_unique<ParameterHandler>(
60  node, plugin_name_, logger_, costmap_->getSizeInMetersX());
61  params_ = param_handler_->getParams();
62 
63  // Handles global path transformations
64  path_handler_ = std::make_unique<PathHandler>(
65  params_->transform_tolerance, tf_, costmap_ros_);
66 
67  // Checks for imminent collisions
68  collision_checker_ = std::make_unique<CollisionChecker>(node, costmap_ros_, params_);
69 
70  double control_frequency = 20.0;
71  goal_dist_tol_ = 0.25; // reasonable default before first update
72 
73  node->get_parameter("controller_frequency", control_frequency);
74  control_duration_ = 1.0 / control_frequency;
75 
76  global_path_pub_ = node->create_publisher<nav_msgs::msg::Path>("received_global_plan");
77  carrot_pub_ = node->create_publisher<geometry_msgs::msg::PointStamped>("lookahead_point");
78  curvature_carrot_pub_ = node->create_publisher<geometry_msgs::msg::PointStamped>(
79  "curvature_lookahead_point");
80  is_rotating_to_heading_pub_ = node->create_publisher<std_msgs::msg::Bool>(
81  "is_rotating_to_heading");
82 }
83 
84 void RegulatedPurePursuitController::cleanup()
85 {
86  RCLCPP_INFO(
87  logger_,
88  "Cleaning up controller: %s of type"
89  " regulated_pure_pursuit_controller::RegulatedPurePursuitController",
90  plugin_name_.c_str());
91  global_path_pub_.reset();
92  carrot_pub_.reset();
93  curvature_carrot_pub_.reset();
94  is_rotating_to_heading_pub_.reset();
95 }
96 
97 void RegulatedPurePursuitController::activate()
98 {
99  RCLCPP_INFO(
100  logger_,
101  "Activating controller: %s of type "
102  "regulated_pure_pursuit_controller::RegulatedPurePursuitController",
103  plugin_name_.c_str());
104  global_path_pub_->on_activate();
105  carrot_pub_->on_activate();
106  curvature_carrot_pub_->on_activate();
107  is_rotating_to_heading_pub_->on_activate();
108  param_handler_->activate();
109 }
110 
111 void RegulatedPurePursuitController::deactivate()
112 {
113  RCLCPP_INFO(
114  logger_,
115  "Deactivating controller: %s of type "
116  "regulated_pure_pursuit_controller::RegulatedPurePursuitController",
117  plugin_name_.c_str());
118  global_path_pub_->on_deactivate();
119  carrot_pub_->on_deactivate();
120  curvature_carrot_pub_->on_deactivate();
121  is_rotating_to_heading_pub_->on_deactivate();
122  param_handler_->deactivate();
123 }
124 
125 std::unique_ptr<geometry_msgs::msg::PointStamped> RegulatedPurePursuitController::createCarrotMsg(
126  const geometry_msgs::msg::PoseStamped & carrot_pose)
127 {
128  auto carrot_msg = std::make_unique<geometry_msgs::msg::PointStamped>();
129  carrot_msg->header = carrot_pose.header;
130  carrot_msg->point.x = carrot_pose.pose.position.x;
131  carrot_msg->point.y = carrot_pose.pose.position.y;
132  carrot_msg->point.z = 0.01; // publish right over map to stand out
133  return carrot_msg;
134 }
135 
136 double RegulatedPurePursuitController::getLookAheadDistance(
137  const geometry_msgs::msg::Twist & speed)
138 {
139  // If using velocity-scaled look ahead distances, find and clamp the dist
140  // Else, use the static look ahead distance
141  double lookahead_dist = params_->lookahead_dist;
142  if (params_->use_velocity_scaled_lookahead_dist) {
143  lookahead_dist = fabs(speed.linear.x) * params_->lookahead_time;
144  lookahead_dist = std::clamp(
145  lookahead_dist, params_->min_lookahead_dist, params_->max_lookahead_dist);
146  }
147 
148  return lookahead_dist;
149 }
150 
151 double calculateCurvature(geometry_msgs::msg::Point lookahead_point)
152 {
153  // Find distance^2 to look ahead point (carrot) in robot base frame
154  // This is the chord length of the circle
155  const double carrot_dist2 =
156  (lookahead_point.x * lookahead_point.x) +
157  (lookahead_point.y * lookahead_point.y);
158 
159  // Find curvature of circle (k = 1 / R)
160  if (carrot_dist2 > 0.001) {
161  return 2.0 * lookahead_point.y / carrot_dist2;
162  } else {
163  return 0.0;
164  }
165 }
166 
167 geometry_msgs::msg::TwistStamped RegulatedPurePursuitController::computeVelocityCommands(
168  const geometry_msgs::msg::PoseStamped & pose,
169  const geometry_msgs::msg::Twist & speed,
170  nav2_core::GoalChecker * goal_checker)
171 {
172  std::lock_guard<std::mutex> lock_reinit(param_handler_->getMutex());
173 
174  nav2_costmap_2d::Costmap2D * costmap = costmap_ros_->getCostmap();
175  std::unique_lock<nav2_costmap_2d::Costmap2D::mutex_t> lock(*(costmap->getMutex()));
176 
177  // Update for the current goal checker's state
178  geometry_msgs::msg::Pose pose_tolerance;
179  geometry_msgs::msg::Twist vel_tolerance;
180  if (!goal_checker->getTolerances(pose_tolerance, vel_tolerance)) {
181  RCLCPP_WARN(logger_, "Unable to retrieve goal checker's tolerances!");
182  } else {
183  goal_dist_tol_ = pose_tolerance.position.x;
184  }
185 
186  // Transform path to robot base frame
187  auto transformed_plan = path_handler_->transformGlobalPlan(
188  pose, params_->max_robot_pose_search_dist, params_->interpolate_curvature_after_goal);
189  global_path_pub_->publish(transformed_plan);
190 
191  // Find look ahead distance and point on path and publish
192  double lookahead_dist = getLookAheadDistance(speed);
193  double curv_lookahead_dist = params_->curvature_lookahead_dist;
194 
195  // Check for reverse driving
196  if (params_->allow_reversing) {
197  // Cusp check
198  const double dist_to_cusp = findVelocitySignChange(transformed_plan);
199 
200  // if the lookahead distance is further than the cusp, use the cusp distance instead
201  if (dist_to_cusp < lookahead_dist) {
202  lookahead_dist = dist_to_cusp;
203  }
204  if (dist_to_cusp < curv_lookahead_dist) {
205  curv_lookahead_dist = dist_to_cusp;
206  }
207  }
208 
209  // Get the particular point on the path at the lookahead distance
210  auto carrot_pose = nav2_util::getLookAheadPoint(lookahead_dist, transformed_plan);
211  auto rotate_to_path_carrot_pose = carrot_pose;
212  carrot_pub_->publish(createCarrotMsg(carrot_pose));
213 
214  double linear_vel, angular_vel;
215 
216  double lookahead_curvature = calculateCurvature(carrot_pose.pose.position);
217 
218  double regulation_curvature = lookahead_curvature;
219  if (params_->use_fixed_curvature_lookahead) {
220  auto curvature_lookahead_pose = nav2_util::getLookAheadPoint(
221  curv_lookahead_dist,
222  transformed_plan, params_->interpolate_curvature_after_goal);
223  rotate_to_path_carrot_pose = curvature_lookahead_pose;
224  regulation_curvature = calculateCurvature(curvature_lookahead_pose.pose.position);
225  curvature_carrot_pub_->publish(createCarrotMsg(curvature_lookahead_pose));
226  }
227 
228  // Setting the velocity direction
229  double x_vel_sign = 1.0;
230  if (params_->allow_reversing) {
231  x_vel_sign = carrot_pose.pose.position.x >= 0.0 ? 1.0 : -1.0;
232  }
233 
234  linear_vel = params_->desired_linear_vel;
235 
236  // Make sure we're in compliance with basic constraints
237  // For shouldRotateToPath, using x_vel_sign in order to support allow_reversing
238  // and rotate_to_path_carrot_pose for the direction carrot pose:
239  // - equal to "normal" carrot_pose when curvature_lookahead_pose = false
240  // - otherwise equal to curvature_lookahead_pose (which can be interpolated after goal)
241  double angle_to_heading;
242  if (shouldRotateToGoalHeading(carrot_pose)) {
243  is_rotating_to_heading_ = true;
244  double angle_to_goal = tf2::getYaw(transformed_plan.poses.back().pose.orientation);
245  rotateToHeading(linear_vel, angular_vel, angle_to_goal, speed);
246  } else if (shouldRotateToPath(rotate_to_path_carrot_pose, angle_to_heading, x_vel_sign)) {
247  is_rotating_to_heading_ = true;
248  rotateToHeading(linear_vel, angular_vel, angle_to_heading, speed);
249  } else {
250  is_rotating_to_heading_ = false;
251  applyConstraints(
252  regulation_curvature, speed,
253  collision_checker_->costAtPose(pose.pose.position.x, pose.pose.position.y), transformed_plan,
254  linear_vel, x_vel_sign);
255 
256  if (cancelling_) {
257  const double & dt = control_duration_;
258  linear_vel = speed.linear.x - x_vel_sign * dt * params_->cancel_deceleration;
259 
260  if (x_vel_sign > 0) {
261  if (linear_vel <= 0) {
262  linear_vel = 0;
263  finished_cancelling_ = true;
264  }
265  } else {
266  if (linear_vel >= 0) {
267  linear_vel = 0;
268  finished_cancelling_ = true;
269  }
270  }
271  }
272 
273  // Apply curvature to angular velocity after constraining linear velocity
274  angular_vel = linear_vel * regulation_curvature;
275  }
276 
277  // Collision checking on this velocity heading
278  const double & carrot_dist = hypot(carrot_pose.pose.position.x, carrot_pose.pose.position.y);
279  if (params_->use_collision_detection &&
280  collision_checker_->isCollisionImminent(pose, linear_vel, angular_vel, carrot_dist))
281  {
282  throw nav2_core::NoValidControl("RegulatedPurePursuitController detected collision ahead!");
283  }
284 
285  // Publish whether we are rotating to goal heading
286  std_msgs::msg::Bool is_rotating_to_heading_msg;
287  is_rotating_to_heading_msg.data = is_rotating_to_heading_;
288  is_rotating_to_heading_pub_->publish(is_rotating_to_heading_msg);
289 
290  // populate and return message
291  geometry_msgs::msg::TwistStamped cmd_vel;
292  cmd_vel.header = pose.header;
293  cmd_vel.twist.linear.x = linear_vel;
294  cmd_vel.twist.angular.z = angular_vel;
295  return cmd_vel;
296 }
297 
298 bool RegulatedPurePursuitController::cancel()
299 {
300  // if false then publish zero velocity
301  if (!params_->use_cancel_deceleration) {
302  return true;
303  }
304  cancelling_ = true;
305  return finished_cancelling_;
306 }
307 
308 bool RegulatedPurePursuitController::shouldRotateToPath(
309  const geometry_msgs::msg::PoseStamped & carrot_pose, double & angle_to_path,
310  double & x_vel_sign)
311 {
312  // Whether we should rotate robot to rough path heading
313  angle_to_path = atan2(carrot_pose.pose.position.y, carrot_pose.pose.position.x);
314  // In case we are reversing
315  if (x_vel_sign < 0.0) {
316  angle_to_path = angles::normalize_angle(angle_to_path + M_PI);
317  }
318  return params_->use_rotate_to_heading &&
319  fabs(angle_to_path) > params_->rotate_to_heading_min_angle;
320 }
321 
322 bool RegulatedPurePursuitController::shouldRotateToGoalHeading(
323  const geometry_msgs::msg::PoseStamped & carrot_pose)
324 {
325  // Whether we should rotate robot to goal heading
326  if (!params_->use_rotate_to_heading) {
327  return false;
328  }
329 
330  double dist_to_goal = std::hypot(
331  carrot_pose.pose.position.x, carrot_pose.pose.position.y);
332 
333  if (params_->stateful) {
334  if (!has_reached_xy_tolerance_ && dist_to_goal < goal_dist_tol_) {
335  has_reached_xy_tolerance_ = true;
336  }
337  return has_reached_xy_tolerance_;
338  }
339 
340  return dist_to_goal < goal_dist_tol_;
341 }
342 
343 void RegulatedPurePursuitController::rotateToHeading(
344  double & linear_vel, double & angular_vel,
345  const double & angle_to_path, const geometry_msgs::msg::Twist & curr_speed)
346 {
347  // Rotate in place using max angular velocity / acceleration possible
348  linear_vel = 0.0;
349  const double sign = angle_to_path > 0.0 ? 1.0 : -1.0;
350  angular_vel = sign * params_->rotate_to_heading_angular_vel;
351 
352  const double & dt = control_duration_;
353  const double min_feasible_angular_speed = curr_speed.angular.z - params_->max_angular_accel * dt;
354  const double max_feasible_angular_speed = curr_speed.angular.z + params_->max_angular_accel * dt;
355  angular_vel = std::clamp(angular_vel, min_feasible_angular_speed, max_feasible_angular_speed);
356 
357  // Check if we need to slow down to avoid overshooting
358  double max_vel_to_stop = std::sqrt(2 * params_->max_angular_accel * fabs(angle_to_path));
359  if (fabs(angular_vel) > max_vel_to_stop) {
360  angular_vel = sign * max_vel_to_stop;
361  }
362 }
363 
364 void RegulatedPurePursuitController::applyConstraints(
365  const double & curvature, const geometry_msgs::msg::Twist & /*curr_speed*/,
366  const double & pose_cost, const nav_msgs::msg::Path & path, double & linear_vel, double & sign)
367 {
368  double curvature_vel = linear_vel, cost_vel = linear_vel;
369 
370  // limit the linear velocity by curvature
371  if (params_->use_regulated_linear_velocity_scaling) {
372  curvature_vel = heuristics::curvatureConstraint(
373  linear_vel, curvature, params_->regulated_linear_scaling_min_radius);
374  }
375 
376  // limit the linear velocity by proximity to obstacles
377  if (params_->use_cost_regulated_linear_velocity_scaling) {
378  cost_vel = heuristics::costConstraint(linear_vel, pose_cost, costmap_ros_, params_);
379  }
380 
381  // Use the lowest of the 2 constraints, but above the minimum translational speed
382  linear_vel = std::min(cost_vel, curvature_vel);
383  linear_vel = std::max(linear_vel, params_->regulated_linear_scaling_min_speed);
384 
385  // Apply constraint to reduce speed on approach to the final goal pose
386  linear_vel = heuristics::approachVelocityConstraint(
387  linear_vel, path, params_->min_approach_linear_velocity,
388  params_->approach_velocity_scaling_dist);
389 
390  // Limit linear velocities to be valid
391  linear_vel = std::clamp(fabs(linear_vel), 0.0, params_->desired_linear_vel);
392  linear_vel = sign * linear_vel;
393 }
394 
395 void RegulatedPurePursuitController::setPlan(const nav_msgs::msg::Path & path)
396 {
397  has_reached_xy_tolerance_ = false;
398  path_handler_->setPlan(path);
399 }
400 
401 void RegulatedPurePursuitController::setSpeedLimit(
402  const double & speed_limit,
403  const bool & percentage)
404 {
405  std::lock_guard<std::mutex> lock_reinit(param_handler_->getMutex());
406 
407  if (speed_limit == nav2_costmap_2d::NO_SPEED_LIMIT) {
408  // Restore default value
409  params_->desired_linear_vel = params_->base_desired_linear_vel;
410  } else {
411  if (percentage) {
412  // Speed limit is expressed in % from maximum speed of robot
413  params_->desired_linear_vel = params_->base_desired_linear_vel * speed_limit / 100.0;
414  } else {
415  // Speed limit is expressed in absolute value
416  params_->desired_linear_vel = speed_limit;
417  }
418  }
419 }
420 
421 void RegulatedPurePursuitController::reset()
422 {
423  cancelling_ = false;
424  finished_cancelling_ = false;
425  has_reached_xy_tolerance_ = false;
426 }
427 
428 double RegulatedPurePursuitController::findVelocitySignChange(
429  const nav_msgs::msg::Path & transformed_plan)
430 {
431  // Iterating through the transformed global path to determine the position of the cusp
432  for (unsigned int pose_id = 1; pose_id < transformed_plan.poses.size() - 1; ++pose_id) {
433  // We have two vectors for the dot product OA and AB. Determining the vectors.
434  double oa_x = transformed_plan.poses[pose_id].pose.position.x -
435  transformed_plan.poses[pose_id - 1].pose.position.x;
436  double oa_y = transformed_plan.poses[pose_id].pose.position.y -
437  transformed_plan.poses[pose_id - 1].pose.position.y;
438  double ab_x = transformed_plan.poses[pose_id + 1].pose.position.x -
439  transformed_plan.poses[pose_id].pose.position.x;
440  double ab_y = transformed_plan.poses[pose_id + 1].pose.position.y -
441  transformed_plan.poses[pose_id].pose.position.y;
442 
443  /* Checking for the existence of cusp, in the path, using the dot product
444  and determine it's distance from the robot. If there is no cusp in the path,
445  then just determine the distance to the goal location. */
446  const double dot_prod = (oa_x * ab_x) + (oa_y * ab_y);
447  if (dot_prod < 0.0) {
448  // returning the distance if there is a cusp
449  // The transformed path is in the robots frame, so robot is at the origin
450  return hypot(
451  transformed_plan.poses[pose_id].pose.position.x,
452  transformed_plan.poses[pose_id].pose.position.y);
453  }
454 
455  if (
456  (hypot(oa_x, oa_y) == 0.0 &&
457  transformed_plan.poses[pose_id - 1].pose.orientation !=
458  transformed_plan.poses[pose_id].pose.orientation)
459  ||
460  (hypot(ab_x, ab_y) == 0.0 &&
461  transformed_plan.poses[pose_id].pose.orientation !=
462  transformed_plan.poses[pose_id + 1].pose.orientation))
463  {
464  // returning the distance since the points overlap
465  // but are not simply duplicate points (e.g. in place rotation)
466  return hypot(
467  transformed_plan.poses[pose_id].pose.position.x,
468  transformed_plan.poses[pose_id].pose.position.y);
469  }
470  }
471 
472  return std::numeric_limits<double>::max();
473 }
474 } // namespace nav2_regulated_pure_pursuit_controller
475 
476 // Register this controller as a nav2_core plugin
477 PLUGINLIB_EXPORT_CLASS(
controller interface that acts as a virtual base class for all controller plugins
Definition: controller.hpp:60
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".
Definition: costmap_2d.hpp:69