Nav2 Navigation Stack - jazzy  jazzy
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  rclcpp_lifecycle::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", 1);
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::Pose2D curr_pose;
90  curr_pose.x = robot_pose.pose.position.x;
91  curr_pose.y = robot_pose.pose.position.y;
92  curr_pose.theta = tf2::getYaw(robot_pose.pose.orientation);
93 
94  // only forward simulate within time requested
95  int i = 1;
96  while (i * projection_time < params_->max_allowed_time_to_collision_up_to_carrot) {
97  i++;
98 
99  // apply velocity at curr_pose over distance
100  curr_pose.x += projection_time * (linear_vel * cos(curr_pose.theta));
101  curr_pose.y += projection_time * (linear_vel * sin(curr_pose.theta));
102  curr_pose.theta += projection_time * angular_vel;
103 
104  // check if past carrot pose, where no longer a thoughtfully valid command
105  if (hypot(curr_pose.x - robot_xy.x, curr_pose.y - robot_xy.y) > carrot_dist) {
106  break;
107  }
108 
109  // store it for visualization
110  pose_msg.pose.position.x = curr_pose.x;
111  pose_msg.pose.position.y = curr_pose.y;
112  pose_msg.pose.position.z = 0.01;
113  arc_pts_msg.poses.push_back(pose_msg);
114 
115  // check for collision at the projected pose
116  if (inCollision(curr_pose.x, curr_pose.y, curr_pose.theta)) {
117  carrot_arc_pub_->publish(arc_pts_msg);
118  return true;
119  }
120  }
121 
122  carrot_arc_pub_->publish(arc_pts_msg);
123 
124  return false;
125 }
126 
128  const double & x,
129  const double & y,
130  const double & theta)
131 {
132  unsigned int mx, my;
133 
134  if (!costmap_->worldToMap(x, y, mx, my)) {
135  RCLCPP_WARN_THROTTLE(
136  logger_, *(clock_), 30000,
137  "The dimensions of the costmap is too small to successfully check for "
138  "collisions as far ahead as requested. Proceed at your own risk, slow the robot, or "
139  "increase your costmap size.");
140  return false;
141  }
142 
143  double footprint_cost = footprint_collision_checker_->footprintCostAtPose(
144  x, y, theta, costmap_ros_->getRobotFootprint());
145  if (footprint_cost == static_cast<double>(NO_INFORMATION) &&
146  costmap_ros_->getLayeredCostmap()->isTrackingUnknown())
147  {
148  return false;
149  }
150 
151  // if occupied or unknown and not to traverse unknown space
152  return footprint_cost >= static_cast<double>(LETHAL_OBSTACLE);
153 }
154 
155 
156 double CollisionChecker::costAtPose(const double & x, const double & y)
157 {
158  unsigned int mx, my;
159 
160  if (!costmap_->worldToMap(x, y, mx, my)) {
161  RCLCPP_FATAL(
162  logger_,
163  "The dimensions of the costmap is too small to fully include your robot's footprint, "
164  "thusly the robot cannot proceed further");
166  "RegulatedPurePursuitController: Dimensions of the costmap are too small "
167  "to encapsulate the robot footprint at current speeds!");
168  }
169 
170  unsigned char cost = costmap_->getCost(mx, my);
171  return static_cast<double>(cost);
172 }
173 
174 } // namespace nav2_regulated_pure_pursuit_controller
CollisionChecker(rclcpp_lifecycle::LifecycleNode::SharedPtr node, std::shared_ptr< nav2_costmap_2d::Costmap2DROS > costmap_ros, Parameters *params)
Constructor for nav2_regulated_pure_pursuit_controller::CollisionChecker.
bool inCollision(const double &x, const double &y, const double &theta)
checks for collision at projected pose
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.