Skip to content

Commit 3ec7c33

Browse files
Fix incorrect world <-> map coordinates conversions (#5049)
* Fix incorrect world <-> map coordinates conversions The conversion between world and map continuous (!) coordinates do not require a +/-0.5. This offset is only required when converting discrete map cell indexes to the coordinates of its center. Signed-off-by: Dylan De Coeyer <[email protected]> * nav2_smac_planner: fix smoother test when path is in collision The added pose was indeed invalid, but the it was ignored by the smoother, since considered as a cusp. Instead, let's make the end of the plan invalid as it won't be ignored. Also, let's duplicate the last pose to make the orientation estimation fail, rather than adding a new arbitrary pose. Signed-off-by: Dylan De Coeyer <[email protected]> --------- Signed-off-by: Dylan De Coeyer <[email protected]>
1 parent c673a4b commit 3ec7c33

File tree

3 files changed

+17
-10
lines changed

3 files changed

+17
-10
lines changed

nav2_costmap_2d/src/costmap_2d.cpp

Lines changed: 2 additions & 2 deletions
Original file line numberDiff line numberDiff line change
@@ -309,8 +309,8 @@ bool Costmap2D::worldToMapContinuous(double wx, double wy, float & mx, float & m
309309
return false;
310310
}
311311

312-
mx = static_cast<float>((wx - origin_x_) / resolution_) + 0.5f;
313-
my = static_cast<float>((wy - origin_y_) / resolution_) + 0.5f;
312+
mx = static_cast<float>((wx - origin_x_) / resolution_);
313+
my = static_cast<float>((wy - origin_y_) / resolution_);
314314

315315
if (mx < size_x_ && my < size_y_) {
316316
return true;

nav2_smac_planner/include/nav2_smac_planner/utils.hpp

Lines changed: 2 additions & 2 deletions
Original file line numberDiff line numberDiff line change
@@ -45,9 +45,9 @@ inline geometry_msgs::msg::Pose getWorldCoords(
4545
{
4646
geometry_msgs::msg::Pose msg;
4747
msg.position.x =
48-
static_cast<float>(costmap->getOriginX()) + (mx - 0.5) * costmap->getResolution();
48+
static_cast<float>(costmap->getOriginX()) + mx * costmap->getResolution();
4949
msg.position.y =
50-
static_cast<float>(costmap->getOriginY()) + (my - 0.5) * costmap->getResolution();
50+
static_cast<float>(costmap->getOriginY()) + my * costmap->getResolution();
5151
return msg;
5252
}
5353

nav2_smac_planner/test/test_smoother.cpp

Lines changed: 13 additions & 6 deletions
Original file line numberDiff line numberDiff line change
@@ -168,12 +168,19 @@ TEST(SmootherTest, test_full_smoother)
168168
double max_no_time = 0.0;
169169
EXPECT_FALSE(smoother->smooth(plan, costmap, max_no_time));
170170

171-
// Failure mode: Path is in collision, do 2x to exercise overlapping point
172-
// attempts to update orientation should also fail
173-
pose.pose.position.x = 1.25;
174-
pose.pose.position.y = 1.25;
175-
plan.poses.push_back(pose);
176-
plan.poses.push_back(pose);
171+
// Failure mode: invalid path and invalid orientation
172+
// make the end of the path invalid
173+
geometry_msgs::msg::PoseStamped lastPose = plan.poses.back();
174+
unsigned int mx, my;
175+
costmap->worldToMap(lastPose.pose.position.x, lastPose.pose.position.y, mx, my);
176+
for (unsigned int i = mx - 5; i <= mx + 5; ++i) {
177+
for (unsigned int j = my - 5; j <= my + 5; ++j) {
178+
costmap->setCost(i, j, 254);
179+
}
180+
}
181+
182+
// duplicate last pose to make the orientation update fail
183+
plan.poses.push_back(lastPose);
177184
EXPECT_FALSE(smoother->smooth(plan, costmap, maxtime));
178185
EXPECT_NEAR(plan.poses.end()[-2].pose.orientation.z, 1.0, 1e-3);
179186
EXPECT_NEAR(plan.poses.end()[-2].pose.orientation.x, 0.0, 1e-3);

0 commit comments

Comments
 (0)