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 }
109 
110 void RegulatedPurePursuitController::deactivate()
111 {
112  RCLCPP_INFO(
113  logger_,
114  "Deactivating controller: %s of type "
115  "regulated_pure_pursuit_controller::RegulatedPurePursuitController",
116  plugin_name_.c_str());
117  global_path_pub_->on_deactivate();
118  carrot_pub_->on_deactivate();
119  curvature_carrot_pub_->on_deactivate();
120  is_rotating_to_heading_pub_->on_deactivate();
121 }
122 
123 std::unique_ptr<geometry_msgs::msg::PointStamped> RegulatedPurePursuitController::createCarrotMsg(
124  const geometry_msgs::msg::PoseStamped & carrot_pose)
125 {
126  auto carrot_msg = std::make_unique<geometry_msgs::msg::PointStamped>();
127  carrot_msg->header = carrot_pose.header;
128  carrot_msg->point.x = carrot_pose.pose.position.x;
129  carrot_msg->point.y = carrot_pose.pose.position.y;
130  carrot_msg->point.z = 0.01; // publish right over map to stand out
131  return carrot_msg;
132 }
133 
134 double RegulatedPurePursuitController::getLookAheadDistance(
135  const geometry_msgs::msg::Twist & speed)
136 {
137  // If using velocity-scaled look ahead distances, find and clamp the dist
138  // Else, use the static look ahead distance
139  double lookahead_dist = params_->lookahead_dist;
140  if (params_->use_velocity_scaled_lookahead_dist) {
141  lookahead_dist = fabs(speed.linear.x) * params_->lookahead_time;
142  lookahead_dist = std::clamp(
143  lookahead_dist, params_->min_lookahead_dist, params_->max_lookahead_dist);
144  }
145 
146  return lookahead_dist;
147 }
148 
149 double calculateCurvature(geometry_msgs::msg::Point lookahead_point)
150 {
151  // Find distance^2 to look ahead point (carrot) in robot base frame
152  // This is the chord length of the circle
153  const double carrot_dist2 =
154  (lookahead_point.x * lookahead_point.x) +
155  (lookahead_point.y * lookahead_point.y);
156 
157  // Find curvature of circle (k = 1 / R)
158  if (carrot_dist2 > 0.001) {
159  return 2.0 * lookahead_point.y / carrot_dist2;
160  } else {
161  return 0.0;
162  }
163 }
164 
165 geometry_msgs::msg::TwistStamped RegulatedPurePursuitController::computeVelocityCommands(
166  const geometry_msgs::msg::PoseStamped & pose,
167  const geometry_msgs::msg::Twist & speed,
168  nav2_core::GoalChecker * goal_checker)
169 {
170  std::lock_guard<std::mutex> lock_reinit(param_handler_->getMutex());
171 
172  nav2_costmap_2d::Costmap2D * costmap = costmap_ros_->getCostmap();
173  std::unique_lock<nav2_costmap_2d::Costmap2D::mutex_t> lock(*(costmap->getMutex()));
174 
175  // Update for the current goal checker's state
176  geometry_msgs::msg::Pose pose_tolerance;
177  geometry_msgs::msg::Twist vel_tolerance;
178  if (!goal_checker->getTolerances(pose_tolerance, vel_tolerance)) {
179  RCLCPP_WARN(logger_, "Unable to retrieve goal checker's tolerances!");
180  } else {
181  goal_dist_tol_ = pose_tolerance.position.x;
182  }
183 
184  // Transform path to robot base frame
185  auto transformed_plan = path_handler_->transformGlobalPlan(
186  pose, params_->max_robot_pose_search_dist, params_->interpolate_curvature_after_goal);
187  global_path_pub_->publish(transformed_plan);
188 
189  // Find look ahead distance and point on path and publish
190  double lookahead_dist = getLookAheadDistance(speed);
191  double curv_lookahead_dist = params_->curvature_lookahead_dist;
192 
193  // Check for reverse driving
194  if (params_->allow_reversing) {
195  // Cusp check
196  const double dist_to_cusp = findVelocitySignChange(transformed_plan);
197 
198  // if the lookahead distance is further than the cusp, use the cusp distance instead
199  if (dist_to_cusp < lookahead_dist) {
200  lookahead_dist = dist_to_cusp;
201  }
202  if (dist_to_cusp < curv_lookahead_dist) {
203  curv_lookahead_dist = dist_to_cusp;
204  }
205  }
206 
207  // Get the particular point on the path at the lookahead distance
208  auto carrot_pose = nav2_util::getLookAheadPoint(lookahead_dist, transformed_plan);
209  auto rotate_to_path_carrot_pose = carrot_pose;
210  carrot_pub_->publish(createCarrotMsg(carrot_pose));
211 
212  double linear_vel, angular_vel;
213 
214  double lookahead_curvature = calculateCurvature(carrot_pose.pose.position);
215 
216  double regulation_curvature = lookahead_curvature;
217  if (params_->use_fixed_curvature_lookahead) {
218  auto curvature_lookahead_pose = nav2_util::getLookAheadPoint(
219  curv_lookahead_dist,
220  transformed_plan, params_->interpolate_curvature_after_goal);
221  rotate_to_path_carrot_pose = curvature_lookahead_pose;
222  regulation_curvature = calculateCurvature(curvature_lookahead_pose.pose.position);
223  curvature_carrot_pub_->publish(createCarrotMsg(curvature_lookahead_pose));
224  }
225 
226  // Setting the velocity direction
227  double x_vel_sign = 1.0;
228  if (params_->allow_reversing) {
229  x_vel_sign = carrot_pose.pose.position.x >= 0.0 ? 1.0 : -1.0;
230  }
231 
232  linear_vel = params_->desired_linear_vel;
233 
234  // Make sure we're in compliance with basic constraints
235  // For shouldRotateToPath, using x_vel_sign in order to support allow_reversing
236  // and rotate_to_path_carrot_pose for the direction carrot pose:
237  // - equal to "normal" carrot_pose when curvature_lookahead_pose = false
238  // - otherwise equal to curvature_lookahead_pose (which can be interpolated after goal)
239  double angle_to_heading;
240  if (shouldRotateToGoalHeading(carrot_pose)) {
241  is_rotating_to_heading_ = true;
242  double angle_to_goal = tf2::getYaw(transformed_plan.poses.back().pose.orientation);
243  rotateToHeading(linear_vel, angular_vel, angle_to_goal, speed);
244  } else if (shouldRotateToPath(rotate_to_path_carrot_pose, angle_to_heading, x_vel_sign)) {
245  is_rotating_to_heading_ = true;
246  rotateToHeading(linear_vel, angular_vel, angle_to_heading, speed);
247  } else {
248  is_rotating_to_heading_ = false;
249  applyConstraints(
250  regulation_curvature, speed,
251  collision_checker_->costAtPose(pose.pose.position.x, pose.pose.position.y), transformed_plan,
252  linear_vel, x_vel_sign);
253 
254  if (cancelling_) {
255  const double & dt = control_duration_;
256  linear_vel = speed.linear.x - x_vel_sign * dt * params_->cancel_deceleration;
257 
258  if (x_vel_sign > 0) {
259  if (linear_vel <= 0) {
260  linear_vel = 0;
261  finished_cancelling_ = true;
262  }
263  } else {
264  if (linear_vel >= 0) {
265  linear_vel = 0;
266  finished_cancelling_ = true;
267  }
268  }
269  }
270 
271  // Apply curvature to angular velocity after constraining linear velocity
272  angular_vel = linear_vel * regulation_curvature;
273  }
274 
275  // Collision checking on this velocity heading
276  const double & carrot_dist = hypot(carrot_pose.pose.position.x, carrot_pose.pose.position.y);
277  if (params_->use_collision_detection &&
278  collision_checker_->isCollisionImminent(pose, linear_vel, angular_vel, carrot_dist))
279  {
280  throw nav2_core::NoValidControl("RegulatedPurePursuitController detected collision ahead!");
281  }
282 
283  // Publish whether we are rotating to goal heading
284  std_msgs::msg::Bool is_rotating_to_heading_msg;
285  is_rotating_to_heading_msg.data = is_rotating_to_heading_;
286  is_rotating_to_heading_pub_->publish(is_rotating_to_heading_msg);
287 
288  // populate and return message
289  geometry_msgs::msg::TwistStamped cmd_vel;
290  cmd_vel.header = pose.header;
291  cmd_vel.twist.linear.x = linear_vel;
292  cmd_vel.twist.angular.z = angular_vel;
293  return cmd_vel;
294 }
295 
296 bool RegulatedPurePursuitController::cancel()
297 {
298  // if false then publish zero velocity
299  if (!params_->use_cancel_deceleration) {
300  return true;
301  }
302  cancelling_ = true;
303  return finished_cancelling_;
304 }
305 
306 bool RegulatedPurePursuitController::shouldRotateToPath(
307  const geometry_msgs::msg::PoseStamped & carrot_pose, double & angle_to_path,
308  double & x_vel_sign)
309 {
310  // Whether we should rotate robot to rough path heading
311  angle_to_path = atan2(carrot_pose.pose.position.y, carrot_pose.pose.position.x);
312  // In case we are reversing
313  if (x_vel_sign < 0.0) {
314  angle_to_path = angles::normalize_angle(angle_to_path + M_PI);
315  }
316  return params_->use_rotate_to_heading &&
317  fabs(angle_to_path) > params_->rotate_to_heading_min_angle;
318 }
319 
320 bool RegulatedPurePursuitController::shouldRotateToGoalHeading(
321  const geometry_msgs::msg::PoseStamped & carrot_pose)
322 {
323  // Whether we should rotate robot to goal heading
324  if (!params_->use_rotate_to_heading) {
325  return false;
326  }
327 
328  double dist_to_goal = std::hypot(
329  carrot_pose.pose.position.x, carrot_pose.pose.position.y);
330 
331  if (params_->stateful) {
332  if (!has_reached_xy_tolerance_ && dist_to_goal < goal_dist_tol_) {
333  has_reached_xy_tolerance_ = true;
334  }
335  return has_reached_xy_tolerance_;
336  }
337 
338  return dist_to_goal < goal_dist_tol_;
339 }
340 
341 void RegulatedPurePursuitController::rotateToHeading(
342  double & linear_vel, double & angular_vel,
343  const double & angle_to_path, const geometry_msgs::msg::Twist & curr_speed)
344 {
345  // Rotate in place using max angular velocity / acceleration possible
346  linear_vel = 0.0;
347  const double sign = angle_to_path > 0.0 ? 1.0 : -1.0;
348  angular_vel = sign * params_->rotate_to_heading_angular_vel;
349 
350  const double & dt = control_duration_;
351  const double min_feasible_angular_speed = curr_speed.angular.z - params_->max_angular_accel * dt;
352  const double max_feasible_angular_speed = curr_speed.angular.z + params_->max_angular_accel * dt;
353  angular_vel = std::clamp(angular_vel, min_feasible_angular_speed, max_feasible_angular_speed);
354 
355  // Check if we need to slow down to avoid overshooting
356  double max_vel_to_stop = std::sqrt(2 * params_->max_angular_accel * fabs(angle_to_path));
357  if (fabs(angular_vel) > max_vel_to_stop) {
358  angular_vel = sign * max_vel_to_stop;
359  }
360 }
361 
362 void RegulatedPurePursuitController::applyConstraints(
363  const double & curvature, const geometry_msgs::msg::Twist & /*curr_speed*/,
364  const double & pose_cost, const nav_msgs::msg::Path & path, double & linear_vel, double & sign)
365 {
366  double curvature_vel = linear_vel, cost_vel = linear_vel;
367 
368  // limit the linear velocity by curvature
369  if (params_->use_regulated_linear_velocity_scaling) {
370  curvature_vel = heuristics::curvatureConstraint(
371  linear_vel, curvature, params_->regulated_linear_scaling_min_radius);
372  }
373 
374  // limit the linear velocity by proximity to obstacles
375  if (params_->use_cost_regulated_linear_velocity_scaling) {
376  cost_vel = heuristics::costConstraint(linear_vel, pose_cost, costmap_ros_, params_);
377  }
378 
379  // Use the lowest of the 2 constraints, but above the minimum translational speed
380  linear_vel = std::min(cost_vel, curvature_vel);
381  linear_vel = std::max(linear_vel, params_->regulated_linear_scaling_min_speed);
382 
383  // Apply constraint to reduce speed on approach to the final goal pose
384  linear_vel = heuristics::approachVelocityConstraint(
385  linear_vel, path, params_->min_approach_linear_velocity,
386  params_->approach_velocity_scaling_dist);
387 
388  // Limit linear velocities to be valid
389  linear_vel = std::clamp(fabs(linear_vel), 0.0, params_->desired_linear_vel);
390  linear_vel = sign * linear_vel;
391 }
392 
393 void RegulatedPurePursuitController::setPlan(const nav_msgs::msg::Path & path)
394 {
395  has_reached_xy_tolerance_ = false;
396  path_handler_->setPlan(path);
397 }
398 
399 void RegulatedPurePursuitController::setSpeedLimit(
400  const double & speed_limit,
401  const bool & percentage)
402 {
403  std::lock_guard<std::mutex> lock_reinit(param_handler_->getMutex());
404 
405  if (speed_limit == nav2_costmap_2d::NO_SPEED_LIMIT) {
406  // Restore default value
407  params_->desired_linear_vel = params_->base_desired_linear_vel;
408  } else {
409  if (percentage) {
410  // Speed limit is expressed in % from maximum speed of robot
411  params_->desired_linear_vel = params_->base_desired_linear_vel * speed_limit / 100.0;
412  } else {
413  // Speed limit is expressed in absolute value
414  params_->desired_linear_vel = speed_limit;
415  }
416  }
417 }
418 
419 void RegulatedPurePursuitController::reset()
420 {
421  cancelling_ = false;
422  finished_cancelling_ = false;
423  has_reached_xy_tolerance_ = false;
424 }
425 
426 double RegulatedPurePursuitController::findVelocitySignChange(
427  const nav_msgs::msg::Path & transformed_plan)
428 {
429  // Iterating through the transformed global path to determine the position of the cusp
430  for (unsigned int pose_id = 1; pose_id < transformed_plan.poses.size() - 1; ++pose_id) {
431  // We have two vectors for the dot product OA and AB. Determining the vectors.
432  double oa_x = transformed_plan.poses[pose_id].pose.position.x -
433  transformed_plan.poses[pose_id - 1].pose.position.x;
434  double oa_y = transformed_plan.poses[pose_id].pose.position.y -
435  transformed_plan.poses[pose_id - 1].pose.position.y;
436  double ab_x = transformed_plan.poses[pose_id + 1].pose.position.x -
437  transformed_plan.poses[pose_id].pose.position.x;
438  double ab_y = transformed_plan.poses[pose_id + 1].pose.position.y -
439  transformed_plan.poses[pose_id].pose.position.y;
440 
441  /* Checking for the existence of cusp, in the path, using the dot product
442  and determine it's distance from the robot. If there is no cusp in the path,
443  then just determine the distance to the goal location. */
444  const double dot_prod = (oa_x * ab_x) + (oa_y * ab_y);
445  if (dot_prod < 0.0) {
446  // returning the distance if there is a cusp
447  // The transformed path is in the robots frame, so robot is at the origin
448  return hypot(
449  transformed_plan.poses[pose_id].pose.position.x,
450  transformed_plan.poses[pose_id].pose.position.y);
451  }
452 
453  if (
454  (hypot(oa_x, oa_y) == 0.0 &&
455  transformed_plan.poses[pose_id - 1].pose.orientation !=
456  transformed_plan.poses[pose_id].pose.orientation)
457  ||
458  (hypot(ab_x, ab_y) == 0.0 &&
459  transformed_plan.poses[pose_id].pose.orientation !=
460  transformed_plan.poses[pose_id + 1].pose.orientation))
461  {
462  // returning the distance since the points overlap
463  // but are not simply duplicate points (e.g. in place rotation)
464  return hypot(
465  transformed_plan.poses[pose_id].pose.position.x,
466  transformed_plan.poses[pose_id].pose.position.y);
467  }
468  }
469 
470  return std::numeric_limits<double>::max();
471 }
472 } // namespace nav2_regulated_pure_pursuit_controller
473 
474 // Register this controller as a nav2_core plugin
475 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