Skip to content

Commit

Permalink
Fix world to map coordinate conversion (#4506)
Browse files Browse the repository at this point in the history
Signed-off-by: HovorunBh <fipogh@gmail.com>
  • Loading branch information
HovorunBh authored Jul 1, 2024
1 parent 30f028d commit 137b93b
Show file tree
Hide file tree
Showing 2 changed files with 16 additions and 2 deletions.
4 changes: 2 additions & 2 deletions nav2_smac_planner/include/nav2_smac_planner/utils.hpp
Original file line number Diff line number Diff line change
Expand Up @@ -46,9 +46,9 @@ inline geometry_msgs::msg::Pose getWorldCoords(
{
geometry_msgs::msg::Pose msg;
msg.position.x =
static_cast<float>(costmap->getOriginX()) + (mx + 0.5) * costmap->getResolution();
static_cast<float>(costmap->getOriginX()) + (mx - 0.5) * costmap->getResolution();
msg.position.y =
static_cast<float>(costmap->getOriginY()) + (my + 0.5) * costmap->getResolution();
static_cast<float>(costmap->getOriginY()) + (my - 0.5) * costmap->getResolution();
return msg;
}

Expand Down
14 changes: 14 additions & 0 deletions nav2_smac_planner/test/test_utils.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -147,3 +147,17 @@ TEST(create_marker, test_createMarker)
EXPECT_EQ(marker2.id, 8u);
EXPECT_EQ(marker2.points.size(), 0u);
}

TEST(convert_map_to_world_to_map, test_convert_map_to_world_to_map)
{
auto costmap = nav2_costmap_2d::Costmap2D(10.0, 10.0, 0.05, 0.0, 0.0, 0);

float mx = 200.0;
float my = 100.0;
geometry_msgs::msg::Pose pose = getWorldCoords(mx, my, &costmap);

float mx1, my1;
costmap.worldToMapContinuous(pose.position.x, pose.position.y, mx1, my1);
EXPECT_NEAR(mx, mx1, 1e-3);
EXPECT_NEAR(my, my1, 1e-3);
}

0 comments on commit 137b93b

Please sign in to comment.