diff --git a/nav2_regulated_pure_pursuit_controller/include/nav2_regulated_pure_pursuit_controller/regulated_pure_pursuit_controller.hpp b/nav2_regulated_pure_pursuit_controller/include/nav2_regulated_pure_pursuit_controller/regulated_pure_pursuit_controller.hpp index a9ba01682c8..456d077baed 100644 --- a/nav2_regulated_pure_pursuit_controller/include/nav2_regulated_pure_pursuit_controller/regulated_pure_pursuit_controller.hpp +++ b/nav2_regulated_pure_pursuit_controller/include/nav2_regulated_pure_pursuit_controller/regulated_pure_pursuit_controller.hpp @@ -22,6 +22,7 @@ #include #include +#include "nav2_costmap_2d/footprint_collision_checker.hpp" #include "nav2_core/controller.hpp" #include "rclcpp/rclcpp.hpp" #include "pluginlib/class_loader.hpp" @@ -184,13 +185,16 @@ class RegulatedPurePursuitController : public nav2_core::Controller const double &, const double &); /** - * @brief Whether point is in collision + * @brief checks for collision at projected pose * @param x Pose of pose x * @param y Pose of pose y + * @param theta orientation of Yaw * @return Whether in collision */ - bool inCollision(const double & x, const double & y); - + bool inCollision( + const double & x, + const double & y, + const double & theta); /** * @brief Cost at a point * @param x Pose of pose x @@ -273,6 +277,8 @@ class RegulatedPurePursuitController : public nav2_core::Controller std::shared_ptr> carrot_pub_; std::shared_ptr> carrot_arc_pub_; + std::unique_ptr> + collision_checker_; // Dynamic parameters handler std::mutex mutex_; diff --git a/nav2_regulated_pure_pursuit_controller/src/regulated_pure_pursuit_controller.cpp b/nav2_regulated_pure_pursuit_controller/src/regulated_pure_pursuit_controller.cpp index a04388d7fc4..bbd2a44632b 100644 --- a/nav2_regulated_pure_pursuit_controller/src/regulated_pure_pursuit_controller.cpp +++ b/nav2_regulated_pure_pursuit_controller/src/regulated_pure_pursuit_controller.cpp @@ -175,6 +175,11 @@ void RegulatedPurePursuitController::configure( global_path_pub_ = node->create_publisher("received_global_plan", 1); carrot_pub_ = node->create_publisher("lookahead_point", 1); carrot_arc_pub_ = node->create_publisher("lookahead_collision_arc", 1); + + // initialize collision checker and set costmap + collision_checker_ = std::make_unique>(costmap_); + collision_checker_->setCostmap(costmap_); } void RegulatedPurePursuitController::cleanup() @@ -389,7 +394,10 @@ bool RegulatedPurePursuitController::isCollisionImminent( // odom frame and the carrot_pose is in robot base frame. // check current point is OK - if (inCollision(robot_pose.pose.position.x, robot_pose.pose.position.y)) { + if (inCollision( + robot_pose.pose.position.x, robot_pose.pose.position.y, + tf2::getYaw(robot_pose.pose.orientation))) + { return true; } @@ -408,13 +416,9 @@ bool RegulatedPurePursuitController::isCollisionImminent( curr_pose.y = robot_pose.pose.position.y; curr_pose.theta = tf2::getYaw(robot_pose.pose.orientation); + // only forward simulate within time requested int i = 1; - while (true) { - // only forward simulate within time requested - if (i * projection_time > max_allowed_time_to_collision_) { - break; - } - + while (i * projection_time < max_allowed_time_to_collision_) { i++; // apply velocity at curr_pose over distance @@ -428,8 +432,8 @@ bool RegulatedPurePursuitController::isCollisionImminent( pose_msg.pose.position.z = 0.01; arc_pts_msg.poses.push_back(pose_msg); - // check for collision at this point - if (inCollision(curr_pose.x, curr_pose.y)) { + // check for collision at the projected pose + if (inCollision(curr_pose.x, curr_pose.y, curr_pose.theta)) { carrot_arc_pub_->publish(arc_pts_msg); return true; } @@ -440,7 +444,10 @@ bool RegulatedPurePursuitController::isCollisionImminent( return false; } -bool RegulatedPurePursuitController::inCollision(const double & x, const double & y) +bool RegulatedPurePursuitController::inCollision( + const double & x, + const double & y, + const double & theta) { unsigned int mx, my; @@ -453,13 +460,16 @@ bool RegulatedPurePursuitController::inCollision(const double & x, const double return false; } - unsigned char cost = costmap_->getCost(mx, my); - - if (costmap_ros_->getLayeredCostmap()->isTrackingUnknown()) { - return cost >= INSCRIBED_INFLATED_OBSTACLE && cost != NO_INFORMATION; - } else { - return cost >= INSCRIBED_INFLATED_OBSTACLE; + double footprint_cost = collision_checker_->footprintCostAtPose( + x, y, theta, costmap_ros_->getRobotFootprint()); + if (footprint_cost == static_cast(NO_INFORMATION) && + costmap_ros_->getLayeredCostmap()->isTrackingUnknown()) + { + return false; } + + // if occupied or unknown and not to traverse unknown space + return footprint_cost >= static_cast(LETHAL_OBSTACLE); } double RegulatedPurePursuitController::costAtPose(const double & x, const double & y)