Skip to content

Add footprintAreaCost #5250

New issue

Have a question about this project? Sign up for a free GitHub account to open an issue and contact its maintainers and the community.

By clicking “Sign up for GitHub”, you agree to our terms of service and privacy statement. We’ll occasionally send you account related emails.

Already on GitHub? Sign in to your account

Closed
Closed
Show file tree
Hide file tree
Changes from all commits
Commits
File filter

Filter by extension

Filter by extension

Conversations
Failed to load comments.
Loading
Jump to
Jump to file
Failed to load files.
Loading
Diff view
Diff view
Original file line number Diff line number Diff line change
Expand Up @@ -52,6 +52,10 @@ class FootprintCollisionChecker
* @brief Find the footprint cost in oriented footprint
*/
double footprintCost(const Footprint & footprint);
/**
* @brief Find the footprint cost for entire footprint area using full coverage
*/
double footprintAreaCost(const Footprint & footprint);
/**
* @brief Find the footprint cost a a post with an unoriented footprint
*/
Expand Down Expand Up @@ -81,6 +85,17 @@ class FootprintCollisionChecker
}

protected:
/**
* @brief Check if a point is inside the footprint polygon
* @param x X coordinate in world frame
* @param y Y coordinate in world frame
* @param footprint Footprint polygon
* @return True if point is inside footprint
*/
bool isPointInFootprint(
double x, double y,
const Footprint & footprint);

CostmapT costmap_;
};

Expand Down
2 changes: 1 addition & 1 deletion nav2_costmap_2d/src/costmap_topic_collision_checker.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -94,7 +94,7 @@ double CostmapTopicCollisionChecker::scorePose(
throw IllegalPoseException(name_, "Pose Goes Off Grid.");
}

return collision_checker_.footprintCost(getFootprint(pose, fetch_costmap_and_footprint));
return collision_checker_.footprintAreaCost(getFootprint(pose, fetch_costmap_and_footprint));
}

Footprint CostmapTopicCollisionChecker::getFootprint(
Expand Down
84 changes: 84 additions & 0 deletions nav2_costmap_2d/src/footprint_collision_checker.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -84,6 +84,55 @@ double FootprintCollisionChecker<CostmapT>::footprintCost(const Footprint & foot
return std::max(lineCost(xstart, x1, ystart, y1), footprint_cost);
}

template<typename CostmapT>
double FootprintCollisionChecker<CostmapT>::footprintAreaCost(const Footprint & footprint)
{
// Find bounding box of footprint
double min_x = std::numeric_limits<double>::max();
double max_x = std::numeric_limits<double>::lowest();
double min_y = std::numeric_limits<double>::max();
double max_y = std::numeric_limits<double>::lowest();

for (const auto & point : footprint) {
min_x = std::min(min_x, point.x);
max_x = std::max(max_x, point.x);
min_y = std::min(min_y, point.y);
max_y = std::max(max_y, point.y);
}

// Convert to grid coordinates
unsigned int min_mx, min_my, max_mx, max_my;
if (!worldToMap(min_x, min_y, min_mx, min_my) ||
!worldToMap(max_x, max_y, max_mx, max_my))
{
return static_cast<double>(LETHAL_OBSTACLE);
}

double max_cost = 0.0;

// Check all cells within bounding box
for (unsigned int my = min_my; my <= max_my; ++my) {
for (unsigned int mx = min_mx; mx <= max_mx; ++mx) {
double wx, wy;
costmap_->mapToWorld(mx, my, wx, wy);

if (isPointInFootprint(wx, wy, footprint)) {
double cost = pointCost(mx, my);

if (cost == static_cast<double>(LETHAL_OBSTACLE)) {
return cost;
} else if (cost == static_cast<double>(NO_INFORMATION)) {
// Return NO_INFORMATION for unknown cells, let caller decide how to handle
return cost;
}
max_cost = std::max(max_cost, cost);
}
}
}

return max_cost;
}

template<typename CostmapT>
double FootprintCollisionChecker<CostmapT>::lineCost(int x0, int x1, int y0, int y1) const
{
Expand Down Expand Up @@ -143,6 +192,41 @@ double FootprintCollisionChecker<CostmapT>::footprintCostAtPose(
return footprintCost(oriented_footprint);
}

template<typename CostmapT>
bool FootprintCollisionChecker<CostmapT>::isPointInFootprint(
Copy link
Contributor Author

@tonynajjar tonynajjar Jun 10, 2025

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

taken from collision_monitor. Libraries also exist for this e.g boost

double x, double y,
const Footprint & footprint)
{
// Adaptation of Shimrat, Moshe. "Algorithm 112: position of point relative to polygon."
// Communications of the ACM 5.8 (1962): 434.
// Implementation of ray crossings algorithm for point in polygon task solving.
// Y coordinate is fixed. Moving the ray on X+ axis starting from given point.
// Odd number of intersections with polygon boundaries means the point is inside polygon.
const int poly_size = footprint.size();
int i, j; // Polygon vertex iterators
bool res = false; // Final result, initialized with already inverted value

// Starting from the edge where the last point of polygon is connected to the first
i = poly_size - 1;
for (j = 0; j < poly_size; j++) {
// Checking the edge only if given point is between edge boundaries by Y coordinates.
// One of the condition should contain equality in order to exclude the edges
// parallel to X+ ray.
if ((y <= footprint[i].y) == (y > footprint[j].y)) {
// Calculating the intersection coordinate of X+ ray
const double x_inter = footprint[i].x +
(y - footprint[i].y) * (footprint[j].x - footprint[i].x) /
(footprint[j].y - footprint[i].y);
// If intersection with checked edge is greater than point.x coordinate, inverting the result
if (x_inter > x) {
res = !res;
}
}
i = j;
}
return res;
}

// declare our valid template parameters
template class FootprintCollisionChecker<std::shared_ptr<nav2_costmap_2d::Costmap2D>>;
template class FootprintCollisionChecker<nav2_costmap_2d::Costmap2D *>;
Expand Down
7 changes: 3 additions & 4 deletions nav2_smac_planner/src/collision_checker.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -135,9 +135,7 @@ bool GridCollisionChecker::inCollision(
return true;
}

// if possible inscribed, need to check actual footprint pose.
// Use precomputed oriented footprints are done on initialization,
// offset by translation value to collision check
// Use full area checking instead of edge-only checking
double wx, wy;
costmap_->mapToWorld(static_cast<double>(x), static_cast<double>(y), wx, wy);
geometry_msgs::msg::Point new_pt;
Expand All @@ -150,7 +148,8 @@ bool GridCollisionChecker::inCollision(
current_footprint.push_back(new_pt);
}

float footprint_cost = static_cast<float>(footprintCost(current_footprint));
// Check full area covered by footprint
float footprint_cost = static_cast<float>(footprintAreaCost(current_footprint));
Copy link
Contributor Author

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

can be parametrized to allow user to tune for speed vs accuracy


if (footprint_cost == UNKNOWN_COST && traverse_unknown) {
return false;
Expand Down
Loading