15 #include "nav2_smac_planner/collision_checker.hpp"
17 namespace nav2_smac_planner
22 unsigned int num_quantizations,
23 rclcpp_lifecycle::LifecycleNode::SharedPtr node)
24 : FootprintCollisionChecker(costmap)
27 clock_ = node->get_clock();
28 logger_ = node->get_logger();
32 float bin_size = 2 * M_PI /
static_cast<float>(num_quantizations);
33 angles_.reserve(num_quantizations);
34 for (
unsigned int i = 0; i != num_quantizations; i++) {
35 angles_.push_back(bin_size * i);
48 const nav2_costmap_2d::Footprint & footprint,
50 const double & possible_inscribed_cost)
52 possible_inscribed_cost_ = possible_inscribed_cost;
53 footprint_is_radius_ = radius;
61 if (footprint == unoriented_footprint_) {
65 oriented_footprints_.clear();
66 oriented_footprints_.reserve(angles_.size());
67 double sin_th, cos_th;
68 geometry_msgs::msg::Point new_pt;
69 const unsigned int footprint_size = footprint.size();
72 for (
unsigned int i = 0; i != angles_.size(); i++) {
73 sin_th = sin(angles_[i]);
74 cos_th = cos(angles_[i]);
75 nav2_costmap_2d::Footprint oriented_footprint;
76 oriented_footprint.reserve(footprint_size);
78 for (
unsigned int j = 0; j < footprint_size; j++) {
79 new_pt.x = footprint[j].x * cos_th - footprint[j].y * sin_th;
80 new_pt.y = footprint[j].x * sin_th + footprint[j].y * cos_th;
81 oriented_footprint.push_back(new_pt);
84 oriented_footprints_.push_back(oriented_footprint);
87 unoriented_footprint_ = footprint;
93 const float & angle_bin,
94 const bool & traverse_unknown)
105 costmap_->
mapToWorld(
static_cast<double>(x),
static_cast<double>(y), wx, wy);
107 if (!footprint_is_radius_) {
110 footprint_cost_ = costmap_->
getCost(
111 static_cast<unsigned int>(x),
static_cast<unsigned int>(y));
113 if (footprint_cost_ < possible_inscribed_cost_) {
114 if (possible_inscribed_cost_ > 0) {
117 RCLCPP_ERROR_THROTTLE(
118 logger_, *clock_, 1000,
119 "Inflation layer either not found or inflation is not set sufficiently for "
120 "optimized non-circular collision checking capabilities. It is HIGHLY recommended to set"
121 " the inflation radius to be at MINIMUM half of the robot's largest cross-section. See "
122 "github.com/ros-planning/navigation2/tree/main/nav2_smac_planner#potential-fields"
123 " for full instructions. This will substantially impact run-time performance.");
129 if (footprint_cost_ == UNKNOWN && !traverse_unknown) {
133 if (footprint_cost_ == INSCRIBED || footprint_cost_ == OCCUPIED) {
140 geometry_msgs::msg::Point new_pt;
141 const nav2_costmap_2d::Footprint & oriented_footprint = oriented_footprints_[angle_bin];
142 nav2_costmap_2d::Footprint current_footprint;
143 current_footprint.reserve(oriented_footprint.size());
144 for (
unsigned int i = 0; i < oriented_footprint.size(); ++i) {
145 new_pt.x = wx + oriented_footprint[i].x;
146 new_pt.y = wy + oriented_footprint[i].y;
147 current_footprint.push_back(new_pt);
152 if (footprint_cost_ == UNKNOWN && traverse_unknown) {
157 return footprint_cost_ >= OCCUPIED;
160 footprint_cost_ = costmap_->
getCost(
161 static_cast<unsigned int>(x),
static_cast<unsigned int>(y));
163 if (footprint_cost_ == UNKNOWN && traverse_unknown) {
168 return static_cast<double>(footprint_cost_) >= INSCRIBED;
173 const unsigned int & i,
174 const bool & traverse_unknown)
176 footprint_cost_ = costmap_->
getCost(i);
177 if (footprint_cost_ == UNKNOWN && traverse_unknown) {
182 return footprint_cost_ >= INSCRIBED;
188 return static_cast<float>(footprint_cost_);
191 bool GridCollisionChecker::outsideRange(
const unsigned int & max,
const float & value)
193 return value < 0.0f || value > max;
A 2D costmap provides a mapping between points in the world and their associated "costs".
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.
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.
void setFootprint(const nav2_costmap_2d::Footprint &footprint, const bool &radius, const double &possible_inscribed_cost)
A constructor for nav2_smac_planner::GridCollisionChecker for use when irregular bin intervals are ap...
GridCollisionChecker(nav2_costmap_2d::Costmap2D *costmap, unsigned int num_quantizations, rclcpp_lifecycle::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.