Nav2 Navigation Stack - rolling  main
ROS 2 Navigation Stack
collision_checker.cpp
1 // Copyright (c) 2022 Samsung Research America
2 //
3 // Licensed under the Apache License, Version 2.0 (the "License");
4 // you may not use this file except in compliance with the License.
5 // You may obtain a copy of the License at
6 //
7 // http://www.apache.org/licenses/LICENSE-2.0
8 //
9 // Unless required by applicable law or agreed to in writing, software
10 // distributed under the License is distributed on an "AS IS" BASIS,
11 // WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.
12 // See the License for the specific language governing permissions and
13 // limitations under the License.
14 
15 #include <algorithm>
16 #include <string>
17 #include <limits>
18 #include <memory>
19 #include <vector>
20 #include <utility>
21 
22 #include "nav2_regulated_pure_pursuit_controller/collision_checker.hpp"
23 
24 namespace nav2_regulated_pure_pursuit_controller
25 {
26 
27 using namespace nav2_costmap_2d; // NOLINT
28 
30  nav2::LifecycleNode::SharedPtr node,
31  std::shared_ptr<nav2_costmap_2d::Costmap2DROS> costmap_ros,
32  Parameters * params)
33 {
34  clock_ = node->get_clock();
35  costmap_ros_ = costmap_ros;
36  costmap_ = costmap_ros_->getCostmap();
37  params_ = params;
38 
39  // initialize collision checker and set costmap
40  footprint_collision_checker_ = std::make_unique<nav2_costmap_2d::
41  FootprintCollisionChecker<nav2_costmap_2d::Costmap2D *>>(costmap_);
42  footprint_collision_checker_->setCostmap(costmap_);
43 
44  carrot_arc_pub_ = node->create_publisher<nav_msgs::msg::Path>("lookahead_collision_arc");
45  carrot_arc_pub_->on_activate();
46 }
47 
49  const geometry_msgs::msg::PoseStamped & robot_pose,
50  const double & linear_vel, const double & angular_vel,
51  const double & carrot_dist)
52 {
53  // Note(stevemacenski): This may be a bit unusual, but the robot_pose is in
54  // odom frame and the carrot_pose is in robot base frame. Just how the data comes to us
55 
56  // check current point is OK
57  if (inCollision(
58  robot_pose.pose.position.x, robot_pose.pose.position.y,
59  tf2::getYaw(robot_pose.pose.orientation)))
60  {
61  return true;
62  }
63 
64  // visualization messages
65  nav_msgs::msg::Path arc_pts_msg;
66  arc_pts_msg.header.frame_id = costmap_ros_->getGlobalFrameID();
67  arc_pts_msg.header.stamp = robot_pose.header.stamp;
68  geometry_msgs::msg::PoseStamped pose_msg;
69  pose_msg.header.frame_id = arc_pts_msg.header.frame_id;
70  pose_msg.header.stamp = arc_pts_msg.header.stamp;
71 
72  double projection_time = 0.0;
73  if (fabs(linear_vel) < 0.01 && fabs(angular_vel) > 0.01) {
74  // rotating to heading at goal or toward path
75  // Equation finds the angular distance required for the largest
76  // part of the robot radius to move to another costmap cell:
77  // theta_min = 2.0 * sin ((res/2) / r_max)
78  // via isosceles triangle r_max-r_max-resolution,
79  // dividing by angular_velocity gives us a timestep.
80  double max_radius = costmap_ros_->getLayeredCostmap()->getCircumscribedRadius();
81  projection_time =
82  2.0 * sin((costmap_->getResolution() / 2) / max_radius) / fabs(angular_vel);
83  } else {
84  // Normal path tracking
85  projection_time = costmap_->getResolution() / fabs(linear_vel);
86  }
87 
88  const geometry_msgs::msg::Point & robot_xy = robot_pose.pose.position;
89  geometry_msgs::msg::Pose curr_pose;
90  curr_pose = robot_pose.pose;
91 
92  // only forward simulate within time requested
93  double max_allowed_time_to_collision_check = params_->max_allowed_time_to_collision_up_to_carrot;
94  if (params_->min_distance_to_obstacle > 0.0) {
95  max_allowed_time_to_collision_check = std::max(
96  params_->max_allowed_time_to_collision_up_to_carrot,
97  params_->min_distance_to_obstacle / std::max(std::abs(linear_vel),
98  params_->min_approach_linear_velocity)
99  );
100  }
101  int i = 1;
102  while (i * projection_time < max_allowed_time_to_collision_check) {
103  i++;
104 
105  double theta = tf2::getYaw(curr_pose.orientation);
106 
107  // apply velocity at curr_pose over distance
108  curr_pose.position.x += projection_time * (linear_vel * cos(theta));
109  curr_pose.position.y += projection_time * (linear_vel * sin(theta));
110  theta += projection_time * angular_vel;
111  curr_pose.orientation = nav2_util::geometry_utils::orientationAroundZAxis(theta);
112 
113  // check if past carrot pose, where no longer a thoughtfully valid command
114  if (hypot(curr_pose.position.x - robot_xy.x, curr_pose.position.y - robot_xy.y) > carrot_dist) {
115  break;
116  }
117 
118  // store it for visualization
119  pose_msg.pose.position.x = curr_pose.position.x;
120  pose_msg.pose.position.y = curr_pose.position.y;
121  pose_msg.pose.position.z = 0.01;
122  arc_pts_msg.poses.push_back(pose_msg);
123 
124  // check for collision at the projected pose
125  if (inCollision(curr_pose.position.x, curr_pose.position.y, theta)) {
126  carrot_arc_pub_->publish(arc_pts_msg);
127  return true;
128  }
129  }
130 
131  carrot_arc_pub_->publish(arc_pts_msg);
132 
133  return false;
134 }
135 
137  const double & x,
138  const double & y,
139  const double & theta)
140 {
141  unsigned int mx, my;
142 
143  if (!costmap_->worldToMap(x, y, mx, my)) {
144  RCLCPP_WARN_THROTTLE(
145  logger_, *(clock_), 30000,
146  "The dimensions of the costmap is too small to successfully check for "
147  "collisions as far ahead as requested. Proceed at your own risk, slow the robot, or "
148  "increase your costmap size.");
149  return false;
150  }
151 
152  double footprint_cost = footprint_collision_checker_->footprintCostAtPose(
153  x, y, theta, costmap_ros_->getRobotFootprint());
154  if (footprint_cost == static_cast<double>(NO_INFORMATION) &&
155  costmap_ros_->getLayeredCostmap()->isTrackingUnknown())
156  {
157  return false;
158  }
159 
160  // if occupied or unknown and not to traverse unknown space
161  return footprint_cost >= static_cast<double>(LETHAL_OBSTACLE);
162 }
163 
164 
165 double CollisionChecker::costAtPose(const double & x, const double & y)
166 {
167  unsigned int mx, my;
168 
169  if (!costmap_->worldToMap(x, y, mx, my)) {
170  RCLCPP_FATAL(
171  logger_,
172  "The dimensions of the costmap is too small to fully include your robot's footprint, "
173  "thusly the robot cannot proceed further");
175  "RegulatedPurePursuitController: Dimensions of the costmap are too small "
176  "to encapsulate the robot footprint at current speeds!");
177  }
178 
179  unsigned char cost = costmap_->getCost(mx, my);
180  return static_cast<double>(cost);
181 }
182 
183 } // namespace nav2_regulated_pure_pursuit_controller
bool inCollision(const double &x, const double &y, const double &theta)
checks for collision at projected pose
CollisionChecker(nav2::LifecycleNode::SharedPtr node, std::shared_ptr< nav2_costmap_2d::Costmap2DROS > costmap_ros, Parameters *params)
Constructor for nav2_regulated_pure_pursuit_controller::CollisionChecker.
bool isCollisionImminent(const geometry_msgs::msg::PoseStamped &, const double &, const double &, const double &)
Whether collision is imminent.
double costAtPose(const double &x, const double &y)
Cost at a point.