Skip to content

Commit

Permalink
Update collision_checker.cpp
Browse files Browse the repository at this point in the history
Signed-off-by: Steve Macenski <[email protected]>
  • Loading branch information
SteveMacenski authored Jan 17, 2024
1 parent a8a0c3a commit 8891a53
Showing 1 changed file with 2 additions and 2 deletions.
4 changes: 2 additions & 2 deletions nav2_smac_planner/src/collision_checker.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -107,7 +107,7 @@ bool GridCollisionChecker::inCollision(
// if footprint, then we check for the footprint's points, but first see
// if the robot is even potentially in an inscribed collision
footprint_cost_ = costmap_->getCost(
static_cast<unsigned int>(x), static_cast<unsigned int>(y));
static_cast<unsigned int>(x + 0.5), static_cast<unsigned int>(y + 0.5));

if (footprint_cost_ < possible_inscribed_cost_) {
if (possible_inscribed_cost_ > 0) {
Expand Down Expand Up @@ -157,7 +157,7 @@ bool GridCollisionChecker::inCollision(
} else {
// if radius, then we can check the center of the cost assuming inflation is used
footprint_cost_ = costmap_->getCost(
static_cast<unsigned int>(x), static_cast<unsigned int>(y));
static_cast<unsigned int>(x + 0.5), static_cast<unsigned int>(y + 0.5));

if (footprint_cost_ == UNKNOWN && traverse_unknown) {
return false;
Expand Down

0 comments on commit 8891a53

Please sign in to comment.