22 #include "nav2_regulated_pure_pursuit_controller/collision_checker.hpp"
24 namespace nav2_regulated_pure_pursuit_controller
30 nav2::LifecycleNode::SharedPtr node,
31 std::shared_ptr<nav2_costmap_2d::Costmap2DROS> costmap_ros,
34 clock_ = node->get_clock();
35 costmap_ros_ = costmap_ros;
36 costmap_ = costmap_ros_->getCostmap();
40 footprint_collision_checker_ = std::make_unique<nav2_costmap_2d::
41 FootprintCollisionChecker<nav2_costmap_2d::Costmap2D *>>(costmap_);
42 footprint_collision_checker_->setCostmap(costmap_);
44 carrot_arc_pub_ = node->create_publisher<nav_msgs::msg::Path>(
"lookahead_collision_arc");
45 carrot_arc_pub_->on_activate();
49 const geometry_msgs::msg::PoseStamped & robot_pose,
50 const double & linear_vel,
const double & angular_vel,
51 const double & carrot_dist)
58 robot_pose.pose.position.x, robot_pose.pose.position.y,
59 tf2::getYaw(robot_pose.pose.orientation)))
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;
72 double projection_time = 0.0;
73 if (fabs(linear_vel) < 0.01 && fabs(angular_vel) > 0.01) {
80 double max_radius = costmap_ros_->getLayeredCostmap()->getCircumscribedRadius();
82 2.0 * sin((costmap_->getResolution() / 2) / max_radius) / fabs(angular_vel);
85 projection_time = costmap_->getResolution() / fabs(linear_vel);
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;
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)
102 while (i * projection_time < max_allowed_time_to_collision_check) {
105 double theta = tf2::getYaw(curr_pose.orientation);
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);
114 if (hypot(curr_pose.position.x - robot_xy.x, curr_pose.position.y - robot_xy.y) > carrot_dist) {
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);
125 if (inCollision(curr_pose.position.x, curr_pose.position.y, theta)) {
126 carrot_arc_pub_->publish(arc_pts_msg);
131 carrot_arc_pub_->publish(arc_pts_msg);
139 const double & theta)
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.");
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())
161 return footprint_cost >=
static_cast<double>(LETHAL_OBSTACLE);
169 if (!costmap_->worldToMap(x, y, mx, my)) {
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!");
179 unsigned char cost = costmap_->getCost(mx, my);
180 return static_cast<double>(cost);
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.