22 #include "nav2_regulated_pure_pursuit_controller/collision_checker.hpp"
24 namespace nav2_regulated_pure_pursuit_controller
30 rclcpp_lifecycle::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", 1);
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::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);
96 while (i * projection_time < params_->max_allowed_time_to_collision_up_to_carrot) {
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;
105 if (hypot(curr_pose.x - robot_xy.x, curr_pose.y - robot_xy.y) > carrot_dist) {
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);
116 if (inCollision(curr_pose.x, curr_pose.y, curr_pose.theta)) {
117 carrot_arc_pub_->publish(arc_pts_msg);
122 carrot_arc_pub_->publish(arc_pts_msg);
130 const double & theta)
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.");
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())
152 return footprint_cost >=
static_cast<double>(LETHAL_OBSTACLE);
160 if (!costmap_->worldToMap(x, y, mx, my)) {
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!");
170 unsigned char cost = costmap_->getCost(mx, my);
171 return static_cast<double>(cost);
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.