15 #include "nav2_smac_planner/collision_checker.hpp"
17 namespace nav2_smac_planner
21 std::shared_ptr<nav2_costmap_2d::Costmap2DROS> costmap_ros,
22 unsigned int num_quantizations,
23 nav2::LifecycleNode::SharedPtr node)
24 : FootprintCollisionChecker(costmap_ros ? costmap_ros->getCostmap() : nullptr)
27 clock_ = node->get_clock();
28 logger_ = node->get_logger();
32 costmap_ros_ = costmap_ros;
36 float bin_size = 2 * M_PI /
static_cast<float>(num_quantizations);
37 angles_.reserve(num_quantizations);
38 for (
unsigned int i = 0; i != num_quantizations; i++) {
39 angles_.push_back(bin_size * i);
52 const nav2_costmap_2d::Footprint & footprint,
54 const double & possible_collision_cost)
56 possible_collision_cost_ =
static_cast<float>(possible_collision_cost);
57 if (possible_collision_cost_ <= 0.0f) {
58 RCLCPP_ERROR_THROTTLE(
59 logger_, *clock_, 1000,
60 "Inflation layer either not found or inflation is not set sufficiently for "
61 "optimized non-circular collision checking capabilities. It is HIGHLY recommended to set"
62 " the inflation radius to be at MINIMUM half of the robot's largest cross-section. See "
63 "github.com/ros-planning/navigation2/tree/main/nav2_smac_planner#potential-fields"
64 " for full instructions. This will substantially impact run-time performance.");
67 footprint_is_radius_ = radius;
75 if (footprint == unoriented_footprint_) {
79 oriented_footprints_.clear();
80 oriented_footprints_.reserve(angles_.size());
81 double sin_th, cos_th;
82 geometry_msgs::msg::Point new_pt;
83 const unsigned int footprint_size = footprint.size();
86 for (
unsigned int i = 0; i != angles_.size(); i++) {
87 sin_th = sin(angles_[i]);
88 cos_th = cos(angles_[i]);
89 nav2_costmap_2d::Footprint oriented_footprint;
90 oriented_footprint.reserve(footprint_size);
92 for (
unsigned int j = 0; j < footprint_size; j++) {
93 new_pt.x = footprint[j].x * cos_th - footprint[j].y * sin_th;
94 new_pt.y = footprint[j].x * sin_th + footprint[j].y * cos_th;
95 oriented_footprint.push_back(new_pt);
98 oriented_footprints_.push_back(oriented_footprint);
101 unoriented_footprint_ = footprint;
107 const float & angle_bin,
108 const bool & traverse_unknown)
118 center_cost_ =
static_cast<float>(costmap_->
getCost(
119 static_cast<unsigned int>(x + 0.5f),
static_cast<unsigned int>(y + 0.5f)));
121 if (!footprint_is_radius_) {
124 if (center_cost_ < possible_collision_cost_ && possible_collision_cost_ > 0.0f) {
130 if (center_cost_ == UNKNOWN_COST && !traverse_unknown) {
134 if (center_cost_ == INSCRIBED_COST || center_cost_ == OCCUPIED_COST) {
142 costmap_->
mapToWorld(
static_cast<double>(x),
static_cast<double>(y), wx, wy);
143 geometry_msgs::msg::Point new_pt;
144 const nav2_costmap_2d::Footprint & oriented_footprint = oriented_footprints_[angle_bin];
145 nav2_costmap_2d::Footprint current_footprint;
146 current_footprint.reserve(oriented_footprint.size());
147 for (
unsigned int i = 0; i < oriented_footprint.size(); ++i) {
148 new_pt.x = wx + oriented_footprint[i].x;
149 new_pt.y = wy + oriented_footprint[i].y;
150 current_footprint.push_back(new_pt);
153 float footprint_cost =
static_cast<float>(
footprintCost(current_footprint));
155 if (footprint_cost == UNKNOWN_COST && traverse_unknown) {
160 return footprint_cost >= OCCUPIED_COST;
163 if (center_cost_ == UNKNOWN_COST && traverse_unknown) {
168 return center_cost_ >= INSCRIBED_COST;
173 const unsigned int & i,
174 const bool & traverse_unknown)
176 center_cost_ = costmap_->
getCost(i);
177 if (center_cost_ == UNKNOWN_COST && traverse_unknown) {
182 return center_cost_ >= INSCRIBED_COST;
188 return static_cast<float>(center_cost_);
193 return value < 0.0f || value > max;
void mapToWorld(unsigned int mx, unsigned int my, double &wx, double &wy) const
Convert from map coordinates to world coordinates.
unsigned char getCost(unsigned int mx, unsigned int my) const
Get the cost of a cell in the costmap.
unsigned int getSizeInCellsX() const
Accessor for the x size of the costmap in cells.
unsigned int getSizeInCellsY() const
Accessor for the y size of the costmap in cells.
void setFootprint(const nav2_costmap_2d::Footprint &footprint, const bool &radius, const double &possible_collision_cost)
A constructor for nav2_smac_planner::GridCollisionChecker for use when irregular bin intervals are ap...
bool inCollision(const float &x, const float &y, const float &theta, const bool &traverse_unknown)
Check if in collision with costmap and footprint at pose.
bool outsideRange(const unsigned int &max, const float &value)
Check if value outside the range.
GridCollisionChecker(std::shared_ptr< nav2_costmap_2d::Costmap2DROS > costmap, unsigned int num_quantizations, nav2::LifecycleNode::SharedPtr node)
A constructor for nav2_smac_planner::GridCollisionChecker for use when regular bin intervals are appr...
float getCost()
Get cost at footprint pose in costmap.