Skip to content

Commit

Permalink
footprint checks
Browse files Browse the repository at this point in the history
  • Loading branch information
jwallace42 committed Jan 3, 2024
1 parent ef0d773 commit cfe14b6
Show file tree
Hide file tree
Showing 2 changed files with 35 additions and 7 deletions.
3 changes: 3 additions & 0 deletions nav2_planner/include/nav2_planner/planner_server.hpp
Original file line number Diff line number Diff line change
Expand Up @@ -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
Expand Down Expand Up @@ -248,6 +249,8 @@ class PlannerServer : public nav2_util::LifecycleNode
std::shared_ptr<nav2_costmap_2d::Costmap2DROS> costmap_ros_;
std::unique_ptr<nav2_util::NodeThread> costmap_thread_;
nav2_costmap_2d::Costmap2D * costmap_;
std::unique_ptr<nav2_costmap_2d::FootprintCollisionChecker<nav2_costmap_2d::Costmap2D *>>
collision_checker_;

// Publishers for the path
rclcpp_lifecycle::LifecyclePublisher<nav_msgs::msg::Path>::SharedPtr plan_publisher_;
Expand Down
39 changes: 32 additions & 7 deletions nav2_planner/src/planner_server.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -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_);
Expand Down Expand Up @@ -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<nav2_costmap_2d::FootprintCollisionChecker<nav2_costmap_2d::Costmap2D *>>(
costmap_);
}

// Launch a thread to run the costmap node
costmap_thread_ = std::make_unique<nav2_util::NodeThread>(costmap_ros_);

Expand Down Expand Up @@ -644,16 +649,35 @@ void PlannerServer::isPathValid(
std::unique_lock<nav2_costmap_2d::Costmap2D::mutex_t> lock(*(costmap_->getMutex()));
unsigned int mx = 0;
unsigned int my = 0;

bool use_radius = costmap_ros_->getUseRadius();

// Visualize the first polygon on the path
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<unsigned int>(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;
}
}
}
Expand Down Expand Up @@ -709,3 +733,4 @@ void PlannerServer::exceptionWarning(
// This acts as a sort of entry point, allowing the component to be discoverable when its library
// is being loaded into a running process.
RCLCPP_COMPONENTS_REGISTER_NODE(nav2_planner::PlannerServer)

0 comments on commit cfe14b6

Please sign in to comment.