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_costmap_2d/costmap_filters/filter_values.hpp"
29 
30 using std::hypot;
31 using std::min;
32 using std::max;
33 using std::abs;
34 using namespace nav2_costmap_2d; // NOLINT
35 
36 namespace nav2_regulated_pure_pursuit_controller
37 {
38 
39 void RegulatedPurePursuitController::configure(
40  const nav2::LifecycleNode::WeakPtr & parent,
41  std::string name, std::shared_ptr<tf2_ros::Buffer> tf,
42  std::shared_ptr<nav2_costmap_2d::Costmap2DROS> costmap_ros)
43 {
44  auto node = parent.lock();
45  node_ = parent;
46  if (!node) {
47  throw nav2_core::ControllerException("Unable to lock node!");
48  }
49 
50  costmap_ros_ = costmap_ros;
51  costmap_ = costmap_ros_->getCostmap();
52  tf_ = tf;
53  plugin_name_ = name;
54  logger_ = node->get_logger();
55 
56  // Handles storage and dynamic configuration of parameters.
57  // Returns pointer to data current param settings.
58  param_handler_ = std::make_unique<ParameterHandler>(
59  node, plugin_name_, logger_, costmap_->getSizeInMetersX());
60  params_ = param_handler_->getParams();
61 
62  // Handles global path transformations
63  path_handler_ = std::make_unique<PathHandler>(
64  params_->transform_tolerance, tf_, costmap_ros_);
65 
66  // Checks for imminent collisions
67  collision_checker_ = std::make_unique<CollisionChecker>(node, costmap_ros_, params_);
68 
69  double control_frequency = 20.0;
70  goal_dist_tol_ = 0.25; // reasonable default before first update
71 
72  node->get_parameter("controller_frequency", control_frequency);
73  control_duration_ = 1.0 / control_frequency;
74 
75  global_path_pub_ = node->create_publisher<nav_msgs::msg::Path>("received_global_plan");
76  carrot_pub_ = node->create_publisher<geometry_msgs::msg::PointStamped>("lookahead_point");
77  curvature_carrot_pub_ = node->create_publisher<geometry_msgs::msg::PointStamped>(
78  "curvature_lookahead_point");
79  is_rotating_to_heading_pub_ = node->create_publisher<std_msgs::msg::Bool>(
80  "is_rotating_to_heading");
81 }
82 
83 void RegulatedPurePursuitController::cleanup()
84 {
85  RCLCPP_INFO(
86  logger_,
87  "Cleaning up controller: %s of type"
88  " regulated_pure_pursuit_controller::RegulatedPurePursuitController",
89  plugin_name_.c_str());
90  global_path_pub_.reset();
91  carrot_pub_.reset();
92  curvature_carrot_pub_.reset();
93  is_rotating_to_heading_pub_.reset();
94 }
95 
96 void RegulatedPurePursuitController::activate()
97 {
98  RCLCPP_INFO(
99  logger_,
100  "Activating controller: %s of type "
101  "regulated_pure_pursuit_controller::RegulatedPurePursuitController",
102  plugin_name_.c_str());
103  global_path_pub_->on_activate();
104  carrot_pub_->on_activate();
105  curvature_carrot_pub_->on_activate();
106  is_rotating_to_heading_pub_->on_activate();
107 }
108 
109 void RegulatedPurePursuitController::deactivate()
110 {
111  RCLCPP_INFO(
112  logger_,
113  "Deactivating controller: %s of type "
114  "regulated_pure_pursuit_controller::RegulatedPurePursuitController",
115  plugin_name_.c_str());
116  global_path_pub_->on_deactivate();
117  carrot_pub_->on_deactivate();
118  curvature_carrot_pub_->on_deactivate();
119  is_rotating_to_heading_pub_->on_deactivate();
120 }
121 
122 std::unique_ptr<geometry_msgs::msg::PointStamped> RegulatedPurePursuitController::createCarrotMsg(
123  const geometry_msgs::msg::PoseStamped & carrot_pose)
124 {
125  auto carrot_msg = std::make_unique<geometry_msgs::msg::PointStamped>();
126  carrot_msg->header = carrot_pose.header;
127  carrot_msg->point.x = carrot_pose.pose.position.x;
128  carrot_msg->point.y = carrot_pose.pose.position.y;
129  carrot_msg->point.z = 0.01; // publish right over map to stand out
130  return carrot_msg;
131 }
132 
133 double RegulatedPurePursuitController::getLookAheadDistance(
134  const geometry_msgs::msg::Twist & speed)
135 {
136  // If using velocity-scaled look ahead distances, find and clamp the dist
137  // Else, use the static look ahead distance
138  double lookahead_dist = params_->lookahead_dist;
139  if (params_->use_velocity_scaled_lookahead_dist) {
140  lookahead_dist = fabs(speed.linear.x) * params_->lookahead_time;
141  lookahead_dist = std::clamp(
142  lookahead_dist, params_->min_lookahead_dist, params_->max_lookahead_dist);
143  }
144 
145  return lookahead_dist;
146 }
147 
148 double calculateCurvature(geometry_msgs::msg::Point lookahead_point)
149 {
150  // Find distance^2 to look ahead point (carrot) in robot base frame
151  // This is the chord length of the circle
152  const double carrot_dist2 =
153  (lookahead_point.x * lookahead_point.x) +
154  (lookahead_point.y * lookahead_point.y);
155 
156  // Find curvature of circle (k = 1 / R)
157  if (carrot_dist2 > 0.001) {
158  return 2.0 * lookahead_point.y / carrot_dist2;
159  } else {
160  return 0.0;
161  }
162 }
163 
164 geometry_msgs::msg::TwistStamped RegulatedPurePursuitController::computeVelocityCommands(
165  const geometry_msgs::msg::PoseStamped & pose,
166  const geometry_msgs::msg::Twist & speed,
167  nav2_core::GoalChecker * goal_checker)
168 {
169  std::lock_guard<std::mutex> lock_reinit(param_handler_->getMutex());
170 
171  nav2_costmap_2d::Costmap2D * costmap = costmap_ros_->getCostmap();
172  std::unique_lock<nav2_costmap_2d::Costmap2D::mutex_t> lock(*(costmap->getMutex()));
173 
174  // Update for the current goal checker's state
175  geometry_msgs::msg::Pose pose_tolerance;
176  geometry_msgs::msg::Twist vel_tolerance;
177  if (!goal_checker->getTolerances(pose_tolerance, vel_tolerance)) {
178  RCLCPP_WARN(logger_, "Unable to retrieve goal checker's tolerances!");
179  } else {
180  goal_dist_tol_ = pose_tolerance.position.x;
181  }
182 
183  // Transform path to robot base frame
184  auto transformed_plan = path_handler_->transformGlobalPlan(
185  pose, params_->max_robot_pose_search_dist, params_->interpolate_curvature_after_goal);
186  global_path_pub_->publish(transformed_plan);
187 
188  // Find look ahead distance and point on path and publish
189  double lookahead_dist = getLookAheadDistance(speed);
190  double curv_lookahead_dist = params_->curvature_lookahead_dist;
191 
192  // Check for reverse driving
193  if (params_->allow_reversing) {
194  // Cusp check
195  const double dist_to_cusp = findVelocitySignChange(transformed_plan);
196 
197  // if the lookahead distance is further than the cusp, use the cusp distance instead
198  if (dist_to_cusp < lookahead_dist) {
199  lookahead_dist = dist_to_cusp;
200  }
201  if (dist_to_cusp < curv_lookahead_dist) {
202  curv_lookahead_dist = dist_to_cusp;
203  }
204  }
205 
206  // Get the particular point on the path at the lookahead distance
207  auto carrot_pose = getLookAheadPoint(lookahead_dist, transformed_plan);
208  auto rotate_to_path_carrot_pose = carrot_pose;
209  carrot_pub_->publish(createCarrotMsg(carrot_pose));
210 
211  double linear_vel, angular_vel;
212 
213  double lookahead_curvature = calculateCurvature(carrot_pose.pose.position);
214 
215  double regulation_curvature = lookahead_curvature;
216  if (params_->use_fixed_curvature_lookahead) {
217  auto curvature_lookahead_pose = getLookAheadPoint(
218  curv_lookahead_dist,
219  transformed_plan, params_->interpolate_curvature_after_goal);
220  rotate_to_path_carrot_pose = curvature_lookahead_pose;
221  regulation_curvature = calculateCurvature(curvature_lookahead_pose.pose.position);
222  curvature_carrot_pub_->publish(createCarrotMsg(curvature_lookahead_pose));
223  }
224 
225  // Setting the velocity direction
226  double x_vel_sign = 1.0;
227  if (params_->allow_reversing) {
228  x_vel_sign = carrot_pose.pose.position.x >= 0.0 ? 1.0 : -1.0;
229  }
230 
231  linear_vel = params_->desired_linear_vel;
232 
233  // Make sure we're in compliance with basic constraints
234  // For shouldRotateToPath, using x_vel_sign in order to support allow_reversing
235  // and rotate_to_path_carrot_pose for the direction carrot pose:
236  // - equal to "normal" carrot_pose when curvature_lookahead_pose = false
237  // - otherwise equal to curvature_lookahead_pose (which can be interpolated after goal)
238  double angle_to_heading;
239  if (shouldRotateToGoalHeading(carrot_pose)) {
240  is_rotating_to_heading_ = true;
241  double angle_to_goal = tf2::getYaw(transformed_plan.poses.back().pose.orientation);
242  rotateToHeading(linear_vel, angular_vel, angle_to_goal, speed);
243  } else if (shouldRotateToPath(rotate_to_path_carrot_pose, angle_to_heading, x_vel_sign)) {
244  is_rotating_to_heading_ = true;
245  rotateToHeading(linear_vel, angular_vel, angle_to_heading, speed);
246  } else {
247  is_rotating_to_heading_ = false;
248  applyConstraints(
249  regulation_curvature, speed,
250  collision_checker_->costAtPose(pose.pose.position.x, pose.pose.position.y), transformed_plan,
251  linear_vel, x_vel_sign);
252 
253  if (cancelling_) {
254  const double & dt = control_duration_;
255  linear_vel = speed.linear.x - x_vel_sign * dt * params_->cancel_deceleration;
256 
257  if (x_vel_sign > 0) {
258  if (linear_vel <= 0) {
259  linear_vel = 0;
260  finished_cancelling_ = true;
261  }
262  } else {
263  if (linear_vel >= 0) {
264  linear_vel = 0;
265  finished_cancelling_ = true;
266  }
267  }
268  }
269 
270  // Apply curvature to angular velocity after constraining linear velocity
271  angular_vel = linear_vel * regulation_curvature;
272  }
273 
274  // Collision checking on this velocity heading
275  const double & carrot_dist = hypot(carrot_pose.pose.position.x, carrot_pose.pose.position.y);
276  if (params_->use_collision_detection &&
277  collision_checker_->isCollisionImminent(pose, linear_vel, angular_vel, carrot_dist))
278  {
279  throw nav2_core::NoValidControl("RegulatedPurePursuitController detected collision ahead!");
280  }
281 
282  // Publish whether we are rotating to goal heading
283  std_msgs::msg::Bool is_rotating_to_heading_msg;
284  is_rotating_to_heading_msg.data = is_rotating_to_heading_;
285  is_rotating_to_heading_pub_->publish(is_rotating_to_heading_msg);
286 
287  // populate and return message
288  geometry_msgs::msg::TwistStamped cmd_vel;
289  cmd_vel.header = pose.header;
290  cmd_vel.twist.linear.x = linear_vel;
291  cmd_vel.twist.angular.z = angular_vel;
292  return cmd_vel;
293 }
294 
295 bool RegulatedPurePursuitController::cancel()
296 {
297  // if false then publish zero velocity
298  if (!params_->use_cancel_deceleration) {
299  return true;
300  }
301  cancelling_ = true;
302  return finished_cancelling_;
303 }
304 
305 bool RegulatedPurePursuitController::shouldRotateToPath(
306  const geometry_msgs::msg::PoseStamped & carrot_pose, double & angle_to_path,
307  double & x_vel_sign)
308 {
309  // Whether we should rotate robot to rough path heading
310  angle_to_path = atan2(carrot_pose.pose.position.y, carrot_pose.pose.position.x);
311  // In case we are reversing
312  if (x_vel_sign < 0.0) {
313  angle_to_path = angles::normalize_angle(angle_to_path + M_PI);
314  }
315  return params_->use_rotate_to_heading &&
316  fabs(angle_to_path) > params_->rotate_to_heading_min_angle;
317 }
318 
319 bool RegulatedPurePursuitController::shouldRotateToGoalHeading(
320  const geometry_msgs::msg::PoseStamped & carrot_pose)
321 {
322  // Whether we should rotate robot to goal heading
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_;
338 }
339 
340 void RegulatedPurePursuitController::rotateToHeading(
341  double & linear_vel, double & angular_vel,
342  const double & angle_to_path, const geometry_msgs::msg::Twist & curr_speed)
343 {
344  // Rotate in place using max angular velocity / acceleration possible
345  linear_vel = 0.0;
346  const double sign = angle_to_path > 0.0 ? 1.0 : -1.0;
347  angular_vel = sign * params_->rotate_to_heading_angular_vel;
348 
349  const double & dt = control_duration_;
350  const double min_feasible_angular_speed = curr_speed.angular.z - params_->max_angular_accel * dt;
351  const double max_feasible_angular_speed = curr_speed.angular.z + params_->max_angular_accel * dt;
352  angular_vel = std::clamp(angular_vel, min_feasible_angular_speed, max_feasible_angular_speed);
353 
354  // Check if we need to slow down to avoid overshooting
355  double max_vel_to_stop = std::sqrt(2 * params_->max_angular_accel * fabs(angle_to_path));
356  if (fabs(angular_vel) > max_vel_to_stop) {
357  angular_vel = sign * max_vel_to_stop;
358  }
359 }
360 
361 geometry_msgs::msg::Point RegulatedPurePursuitController::circleSegmentIntersection(
362  const geometry_msgs::msg::Point & p1,
363  const geometry_msgs::msg::Point & p2,
364  double r)
365 {
366  // Formula for intersection of a line with a circle centered at the origin,
367  // modified to always return the point that is on the segment between the two points.
368  // https://mathworld.wolfram.com/Circle-LineIntersection.html
369  // This works because the poses are transformed into the robot frame.
370  // This can be derived from solving the system of equations of a line and a circle
371  // which results in something that is just a reformulation of the quadratic formula.
372  // Interactive illustration in doc/circle-segment-intersection.ipynb as well as at
373  // https://www.desmos.com/calculator/td5cwbuocd
374  double x1 = p1.x;
375  double x2 = p2.x;
376  double y1 = p1.y;
377  double y2 = p2.y;
378 
379  double dx = x2 - x1;
380  double dy = y2 - y1;
381  double dr2 = dx * dx + dy * dy;
382  double D = x1 * y2 - x2 * y1;
383 
384  // Augmentation to only return point within segment
385  double d1 = x1 * x1 + y1 * y1;
386  double d2 = x2 * x2 + y2 * y2;
387  double dd = d2 - d1;
388 
389  geometry_msgs::msg::Point p;
390  double sqrt_term = std::sqrt(r * r * dr2 - D * D);
391  p.x = (D * dy + std::copysign(1.0, dd) * dx * sqrt_term) / dr2;
392  p.y = (-D * dx + std::copysign(1.0, dd) * dy * sqrt_term) / dr2;
393  return p;
394 }
395 
396 geometry_msgs::msg::PoseStamped RegulatedPurePursuitController::getLookAheadPoint(
397  const double & lookahead_dist,
398  const nav_msgs::msg::Path & transformed_plan,
399  bool interpolate_after_goal)
400 {
401  // Find the first pose which is at a distance greater than the lookahead distance
402  auto goal_pose_it = std::find_if(
403  transformed_plan.poses.begin(), transformed_plan.poses.end(), [&](const auto & ps) {
404  return hypot(ps.pose.position.x, ps.pose.position.y) >= lookahead_dist;
405  });
406 
407  // If the no pose is not far enough, take the last pose
408  if (goal_pose_it == transformed_plan.poses.end()) {
409  if (interpolate_after_goal) {
410  auto last_pose_it = std::prev(transformed_plan.poses.end());
411  auto prev_last_pose_it = std::prev(last_pose_it);
412 
413  double end_path_orientation = atan2(
414  last_pose_it->pose.position.y - prev_last_pose_it->pose.position.y,
415  last_pose_it->pose.position.x - prev_last_pose_it->pose.position.x);
416 
417  // Project the last segment out to guarantee it is beyond the look ahead
418  // distance
419  auto projected_position = last_pose_it->pose.position;
420  projected_position.x += cos(end_path_orientation) * lookahead_dist;
421  projected_position.y += sin(end_path_orientation) * lookahead_dist;
422 
423  // Use the circle intersection to find the position at the correct look
424  // ahead distance
425  const auto interpolated_position = circleSegmentIntersection(
426  last_pose_it->pose.position, projected_position, lookahead_dist);
427 
428  geometry_msgs::msg::PoseStamped interpolated_pose;
429  interpolated_pose.header = last_pose_it->header;
430  interpolated_pose.pose.position = interpolated_position;
431  return interpolated_pose;
432  } else {
433  goal_pose_it = std::prev(transformed_plan.poses.end());
434  }
435  } else if (goal_pose_it != transformed_plan.poses.begin()) {
436  // Find the point on the line segment between the two poses
437  // that is exactly the lookahead distance away from the robot pose (the origin)
438  // This can be found with a closed form for the intersection of a segment and a circle
439  // Because of the way we did the std::find_if, prev_pose is guaranteed to be inside the circle,
440  // and goal_pose is guaranteed to be outside the circle.
441  auto prev_pose_it = std::prev(goal_pose_it);
442  auto point = circleSegmentIntersection(
443  prev_pose_it->pose.position,
444  goal_pose_it->pose.position, lookahead_dist);
445  geometry_msgs::msg::PoseStamped pose;
446  pose.header.frame_id = prev_pose_it->header.frame_id;
447  pose.header.stamp = goal_pose_it->header.stamp;
448  pose.pose.position = point;
449  return pose;
450  }
451 
452  return *goal_pose_it;
453 }
454 
455 void RegulatedPurePursuitController::applyConstraints(
456  const double & curvature, const geometry_msgs::msg::Twist & /*curr_speed*/,
457  const double & pose_cost, const nav_msgs::msg::Path & path, double & linear_vel, double & sign)
458 {
459  double curvature_vel = linear_vel, cost_vel = linear_vel;
460 
461  // limit the linear velocity by curvature
462  if (params_->use_regulated_linear_velocity_scaling) {
463  curvature_vel = heuristics::curvatureConstraint(
464  linear_vel, curvature, params_->regulated_linear_scaling_min_radius);
465  }
466 
467  // limit the linear velocity by proximity to obstacles
468  if (params_->use_cost_regulated_linear_velocity_scaling) {
469  cost_vel = heuristics::costConstraint(linear_vel, pose_cost, costmap_ros_, params_);
470  }
471 
472  // Use the lowest of the 2 constraints, but above the minimum translational speed
473  linear_vel = std::min(cost_vel, curvature_vel);
474  linear_vel = std::max(linear_vel, params_->regulated_linear_scaling_min_speed);
475 
476  // Apply constraint to reduce speed on approach to the final goal pose
477  linear_vel = heuristics::approachVelocityConstraint(
478  linear_vel, path, params_->min_approach_linear_velocity,
479  params_->approach_velocity_scaling_dist);
480 
481  // Limit linear velocities to be valid
482  linear_vel = std::clamp(fabs(linear_vel), 0.0, params_->desired_linear_vel);
483  linear_vel = sign * linear_vel;
484 }
485 
486 void RegulatedPurePursuitController::setPlan(const nav_msgs::msg::Path & path)
487 {
488  has_reached_xy_tolerance_ = false;
489  path_handler_->setPlan(path);
490 }
491 
492 void RegulatedPurePursuitController::setSpeedLimit(
493  const double & speed_limit,
494  const bool & percentage)
495 {
496  std::lock_guard<std::mutex> lock_reinit(param_handler_->getMutex());
497 
498  if (speed_limit == nav2_costmap_2d::NO_SPEED_LIMIT) {
499  // Restore default value
500  params_->desired_linear_vel = params_->base_desired_linear_vel;
501  } else {
502  if (percentage) {
503  // Speed limit is expressed in % from maximum speed of robot
504  params_->desired_linear_vel = params_->base_desired_linear_vel * speed_limit / 100.0;
505  } else {
506  // Speed limit is expressed in absolute value
507  params_->desired_linear_vel = speed_limit;
508  }
509  }
510 }
511 
512 void RegulatedPurePursuitController::reset()
513 {
514  cancelling_ = false;
515  finished_cancelling_ = false;
516  has_reached_xy_tolerance_ = false;
517 }
518 
519 double RegulatedPurePursuitController::findVelocitySignChange(
520  const nav_msgs::msg::Path & transformed_plan)
521 {
522  // Iterating through the transformed global path to determine the position of the cusp
523  for (unsigned int pose_id = 1; pose_id < transformed_plan.poses.size() - 1; ++pose_id) {
524  // We have two vectors for the dot product OA and AB. Determining the vectors.
525  double oa_x = transformed_plan.poses[pose_id].pose.position.x -
526  transformed_plan.poses[pose_id - 1].pose.position.x;
527  double oa_y = transformed_plan.poses[pose_id].pose.position.y -
528  transformed_plan.poses[pose_id - 1].pose.position.y;
529  double ab_x = transformed_plan.poses[pose_id + 1].pose.position.x -
530  transformed_plan.poses[pose_id].pose.position.x;
531  double ab_y = transformed_plan.poses[pose_id + 1].pose.position.y -
532  transformed_plan.poses[pose_id].pose.position.y;
533 
534  /* Checking for the existence of cusp, in the path, using the dot product
535  and determine it's distance from the robot. If there is no cusp in the path,
536  then just determine the distance to the goal location. */
537  const double dot_prod = (oa_x * ab_x) + (oa_y * ab_y);
538  if (dot_prod < 0.0) {
539  // returning the distance if there is a cusp
540  // The transformed path is in the robots frame, so robot is at the origin
541  return hypot(
542  transformed_plan.poses[pose_id].pose.position.x,
543  transformed_plan.poses[pose_id].pose.position.y);
544  }
545 
546  if (
547  (hypot(oa_x, oa_y) == 0.0 &&
548  transformed_plan.poses[pose_id - 1].pose.orientation !=
549  transformed_plan.poses[pose_id].pose.orientation)
550  ||
551  (hypot(ab_x, ab_y) == 0.0 &&
552  transformed_plan.poses[pose_id].pose.orientation !=
553  transformed_plan.poses[pose_id + 1].pose.orientation))
554  {
555  // returning the distance since the points overlap
556  // but are not simply duplicate points (e.g. in place rotation)
557  return hypot(
558  transformed_plan.poses[pose_id].pose.position.x,
559  transformed_plan.poses[pose_id].pose.position.y);
560  }
561  }
562 
563  return std::numeric_limits<double>::max();
564 }
565 } // namespace nav2_regulated_pure_pursuit_controller
566 
567 // Register this controller as a nav2_core plugin
568 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