diff --git a/nav2_planner/include/nav2_planner/planner_server.hpp b/nav2_planner/include/nav2_planner/planner_server.hpp index 2413e2eb3f0..7d2c9d03f00 100644 --- a/nav2_planner/include/nav2_planner/planner_server.hpp +++ b/nav2_planner/include/nav2_planner/planner_server.hpp @@ -39,6 +39,7 @@ #include "pluginlib/class_list_macros.hpp" #include "nav2_core/global_planner.hpp" #include "nav2_msgs/srv/is_path_valid.hpp" +#include "nav2_costmap_2d/footprint_collision_checker.hpp" #include "nav2_core/planner_exceptions.hpp" namespace nav2_planner @@ -248,6 +249,8 @@ class PlannerServer : public nav2_util::LifecycleNode std::shared_ptr costmap_ros_; std::unique_ptr costmap_thread_; nav2_costmap_2d::Costmap2D * costmap_; + std::unique_ptr> + collision_checker_; // Publishers for the path rclcpp_lifecycle::LifecyclePublisher::SharedPtr plan_publisher_; diff --git a/nav2_planner/src/planner_server.cpp b/nav2_planner/src/planner_server.cpp index d087cbef758..cb2e87b7463 100644 --- a/nav2_planner/src/planner_server.cpp +++ b/nav2_planner/src/planner_server.cpp @@ -52,7 +52,6 @@ PlannerServer::PlannerServer(const rclcpp::NodeOptions & options) // Declare this node's parameters declare_parameter("planner_plugins", default_ids_); declare_parameter("expected_planner_frequency", 1.0); - declare_parameter("action_server_result_timeout", 10.0); get_parameter("planner_plugins", planner_ids_); @@ -86,6 +85,12 @@ PlannerServer::on_configure(const rclcpp_lifecycle::State & /*state*/) costmap_ros_->configure(); costmap_ = costmap_ros_->getCostmap(); + if (!costmap_ros_->getUseRadius()) { + collision_checker_ = + std::make_unique>( + costmap_); + } + // Launch a thread to run the costmap node costmap_thread_ = std::make_unique(costmap_ros_); @@ -644,16 +649,34 @@ void PlannerServer::isPathValid( std::unique_lock lock(*(costmap_->getMutex())); unsigned int mx = 0; unsigned int my = 0; + + bool use_radius = costmap_ros_->getUseRadius(); + + unsigned int cost = nav2_costmap_2d::FREE_SPACE; for (unsigned int i = closest_point_index; i < request->path.poses.size(); ++i) { - costmap_->worldToMap( - request->path.poses[i].pose.position.x, - request->path.poses[i].pose.position.y, mx, my); - unsigned int cost = costmap_->getCost(mx, my); + auto & position = request->path.poses[i].pose.position; + if (use_radius) { + if (costmap_->worldToMap(position.x, position.y, mx, my)) { + cost = costmap_->getCost(mx, my); + } else { + cost = nav2_costmap_2d::LETHAL_OBSTACLE; + } + } else { + nav2_costmap_2d::Footprint footprint = costmap_ros_->getRobotFootprint(); + auto theta = tf2::getYaw(request->path.poses[i].pose.orientation); + cost = static_cast(collision_checker_->footprintCostAtPose( + position.x, position.y, theta, footprint)); + } - if (cost == nav2_costmap_2d::LETHAL_OBSTACLE || - cost == nav2_costmap_2d::INSCRIBED_INFLATED_OBSTACLE) + if (use_radius && + (cost == nav2_costmap_2d::LETHAL_OBSTACLE || + cost == nav2_costmap_2d::INSCRIBED_INFLATED_OBSTACLE)) { response->is_valid = false; + break; + } else if (cost == nav2_costmap_2d::LETHAL_OBSTACLE) { + response->is_valid = false; + break; } } }