Skip to content

fixing static layer update bounds with different fram #5194

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

Open
wants to merge 1 commit into
base: main
Choose a base branch
from
Open
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
52 changes: 45 additions & 7 deletions nav2_costmap_2d/plugins/static_layer.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -363,15 +363,53 @@

useExtraBounds(min_x, min_y, max_x, max_y);

double wx, wy;
// Might even be in a different frame
if (map_frame_ == global_frame_) {
double wx, wy;

mapToWorld(x_, y_, wx, wy);
*min_x = std::min(wx, *min_x);
*min_y = std::min(wy, *min_y);

mapToWorld(x_ + width_, y_ + height_, wx, wy);
*max_x = std::max(wx, *max_x);
*max_y = std::max(wy, *max_y);
} else {
geometry_msgs::msg::TransformStamped transform;

Check warning on line 378 in nav2_costmap_2d/plugins/static_layer.cpp

View check run for this annotation

Codecov / codecov/patch

nav2_costmap_2d/plugins/static_layer.cpp#L378

Added line #L378 was not covered by tests
try {
transform = tf_->lookupTransform(

Check warning on line 380 in nav2_costmap_2d/plugins/static_layer.cpp

View check run for this annotation

Codecov / codecov/patch

nav2_costmap_2d/plugins/static_layer.cpp#L380

Added line #L380 was not covered by tests
global_frame_, map_frame_, tf2::TimePointZero,
transform_tolerance_);
} catch (tf2::TransformException & ex) {
RCLCPP_ERROR(logger_, "StaticLayer: %s", ex.what());

Check warning on line 384 in nav2_costmap_2d/plugins/static_layer.cpp

View check run for this annotation

Codecov / codecov/patch

nav2_costmap_2d/plugins/static_layer.cpp#L382-L384

Added lines #L382 - L384 were not covered by tests
return;
}
tf2::Transform tf2_transform;
tf2::fromMsg(transform.transform, tf2_transform);

Check warning on line 388 in nav2_costmap_2d/plugins/static_layer.cpp

View check run for this annotation

Codecov / codecov/patch

nav2_costmap_2d/plugins/static_layer.cpp#L388

Added line #L388 was not covered by tests

double wx, wy;
mapToWorld(x_, y_, wx, wy);

Check warning on line 391 in nav2_costmap_2d/plugins/static_layer.cpp

View check run for this annotation

Codecov / codecov/patch

nav2_costmap_2d/plugins/static_layer.cpp#L391

Added line #L391 was not covered by tests
tf2::Vector3 down_left(wx, wy, 0);

mapToWorld(x_ + width_, y_, wx, wy);

Check warning on line 394 in nav2_costmap_2d/plugins/static_layer.cpp

View check run for this annotation

Codecov / codecov/patch

nav2_costmap_2d/plugins/static_layer.cpp#L394

Added line #L394 was not covered by tests
tf2::Vector3 down_right(wx, wy, 0);

mapToWorld(x_, y_ + height_, wx, wy);

Check warning on line 397 in nav2_costmap_2d/plugins/static_layer.cpp

View check run for this annotation

Codecov / codecov/patch

nav2_costmap_2d/plugins/static_layer.cpp#L397

Added line #L397 was not covered by tests
tf2::Vector3 up_left(wx, wy, 0);

mapToWorld(x_, y_, wx, wy);
*min_x = std::min(wx, *min_x);
*min_y = std::min(wy, *min_y);
mapToWorld(x_ + width_, y_ + height_, wx, wy);

Check warning on line 400 in nav2_costmap_2d/plugins/static_layer.cpp

View check run for this annotation

Codecov / codecov/patch

nav2_costmap_2d/plugins/static_layer.cpp#L400

Added line #L400 was not covered by tests
tf2::Vector3 up_right(wx, wy, 0);

mapToWorld(x_ + width_, y_ + height_, wx, wy);
*max_x = std::max(wx, *max_x);
*max_y = std::max(wy, *max_y);
down_left = tf2_transform * down_left;
down_right = tf2_transform * down_right;
up_left = tf2_transform * up_left;
up_right = tf2_transform * up_right;

Check warning on line 406 in nav2_costmap_2d/plugins/static_layer.cpp

View check run for this annotation

Codecov / codecov/patch

nav2_costmap_2d/plugins/static_layer.cpp#L403-L406

Added lines #L403 - L406 were not covered by tests

*min_x = std::min({*min_x, down_left.x(), down_right.x(), up_left.x(), up_right.x()});
*min_y = std::min({*min_y, down_left.y(), down_right.y(), up_left.y(), up_right.y()});
*max_x = std::max({*max_x, down_left.x(), down_right.x(), up_left.x(), up_right.x()});
*max_y = std::max({*max_y, down_left.y(), down_right.y(), up_left.y(), up_right.y()});

Check warning on line 411 in nav2_costmap_2d/plugins/static_layer.cpp

View check run for this annotation

Codecov / codecov/patch

nav2_costmap_2d/plugins/static_layer.cpp#L408-L411

Added lines #L408 - L411 were not covered by tests
}

has_updated_data_ = false;

Expand Down
18 changes: 9 additions & 9 deletions nav2_costmap_2d/test/integration/inflation_tests.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -201,7 +201,7 @@ TEST_F(TestNode, testAdjacentToObstacleCanStillMove)
{
initNode(4.1);
tf2_ros::Buffer tf(node_->get_clock());
nav2_costmap_2d::LayeredCostmap layers("frame", false, false);
nav2_costmap_2d::LayeredCostmap layers("map", false, false);
layers.resizeMap(10, 10, 1, 0, 0);

// Footprint with inscribed radius = 2.1
Expand Down Expand Up @@ -233,7 +233,7 @@ TEST_F(TestNode, testInflationShouldNotCreateUnknowns)
{
initNode(4.1);
tf2_ros::Buffer tf(node_->get_clock());
nav2_costmap_2d::LayeredCostmap layers("frame", false, false);
nav2_costmap_2d::LayeredCostmap layers("map", false, false);
layers.resizeMap(10, 10, 1, 0, 0);

// Footprint with inscribed radius = 2.1
Expand Down Expand Up @@ -269,7 +269,7 @@ TEST_F(TestNode, testInflationInUnknown)
node_->set_parameter(rclcpp::Parameter("track_unknown_space", true));

tf2_ros::Buffer tf(node_->get_clock());
nav2_costmap_2d::LayeredCostmap layers("frame", false, true);
nav2_costmap_2d::LayeredCostmap layers("map", false, true);
layers.resizeMap(9, 9, 1, 0, 0);

// Footprint with inscribed radius = 2.1
Expand Down Expand Up @@ -305,7 +305,7 @@ TEST_F(TestNode, testInflationAroundUnknown)
node_->set_parameter(rclcpp::Parameter("track_unknown_space", true));

tf2_ros::Buffer tf(node_->get_clock());
nav2_costmap_2d::LayeredCostmap layers("frame", false, false);
nav2_costmap_2d::LayeredCostmap layers("map", false, false);
layers.resizeMap(10, 10, 1, 0, 0);

// Footprint with inscribed radius = 2.1
Expand All @@ -330,7 +330,7 @@ TEST_F(TestNode, testCostFunctionCorrectness)
{
initNode(10.5);
tf2_ros::Buffer tf(node_->get_clock());
nav2_costmap_2d::LayeredCostmap layers("frame", false, false);
nav2_costmap_2d::LayeredCostmap layers("map", false, false);

layers.resizeMap(100, 100, 1, 0, 0);
// Footprint with inscribed radius = 5.0
Expand Down Expand Up @@ -405,7 +405,7 @@ TEST_F(TestNode, testInflationOrderCorrectness)
const double inflation_radius = 4.1;
initNode(inflation_radius);
tf2_ros::Buffer tf(node_->get_clock());
nav2_costmap_2d::LayeredCostmap layers("frame", false, false);
nav2_costmap_2d::LayeredCostmap layers("map", false, false);
layers.resizeMap(10, 10, 1, 0, 0);

// Footprint with inscribed radius = 2.1
Expand Down Expand Up @@ -438,7 +438,7 @@ TEST_F(TestNode, testInflation)
{
initNode(1);
tf2_ros::Buffer tf(node_->get_clock());
nav2_costmap_2d::LayeredCostmap layers("frame", false, false);
nav2_costmap_2d::LayeredCostmap layers("map", false, false);

// Footprint with inscribed radius = 2.1
// circumscribed radius = 3.1
Expand Down Expand Up @@ -516,7 +516,7 @@ TEST_F(TestNode, testInflation2)
{
initNode(1);
tf2_ros::Buffer tf(node_->get_clock());
nav2_costmap_2d::LayeredCostmap layers("frame", false, false);
nav2_costmap_2d::LayeredCostmap layers("map", false, false);

// Footprint with inscribed radius = 2.1
// circumscribed radius = 3.1
Expand Down Expand Up @@ -554,7 +554,7 @@ TEST_F(TestNode, testInflation3)
{
initNode(3);
tf2_ros::Buffer tf(node_->get_clock());
nav2_costmap_2d::LayeredCostmap layers("frame", false, false);
nav2_costmap_2d::LayeredCostmap layers("map", false, false);
layers.resizeMap(10, 10, 1, 0, 0);

// 1 2 3
Expand Down
20 changes: 10 additions & 10 deletions nav2_costmap_2d/test/integration/obstacle_tests.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -148,7 +148,7 @@ class TestNode : public ::testing::Test
TEST_F(TestNode, testRaytracing) {
tf2_ros::Buffer tf(node_->get_clock());

nav2_costmap_2d::LayeredCostmap layers("frame", false, false);
nav2_costmap_2d::LayeredCostmap layers("map", false, false);
addStaticLayer(layers, tf, node_);
auto olayer = addObstacleLayer(layers, tf, node_);

Expand All @@ -170,7 +170,7 @@ TEST_F(TestNode, testRaytracing) {
*/
TEST_F(TestNode, testRaytracing2) {
tf2_ros::Buffer tf(node_->get_clock());
nav2_costmap_2d::LayeredCostmap layers("frame", false, false);
nav2_costmap_2d::LayeredCostmap layers("map", false, false);
addStaticLayer(layers, tf, node_);
auto olayer = addObstacleLayer(layers, tf, node_);

Expand Down Expand Up @@ -227,7 +227,7 @@ TEST_F(TestNode, testWaveInterference) {
tf2_ros::Buffer tf(node_->get_clock());
node_->set_parameter(rclcpp::Parameter("track_unknown_space", true));
// Start with an empty map, no rolling window, tracking unknown
nav2_costmap_2d::LayeredCostmap layers("frame", false, true);
nav2_costmap_2d::LayeredCostmap layers("map", false, true);
layers.resizeMap(10, 10, 1, 0, 0);
auto olayer = addObstacleLayer(layers, tf, node_);

Expand Down Expand Up @@ -255,7 +255,7 @@ TEST_F(TestNode, testWaveInterference) {
TEST_F(TestNode, testZThreshold) {
tf2_ros::Buffer tf(node_->get_clock());
// Start with an empty map
nav2_costmap_2d::LayeredCostmap layers("frame", false, true);
nav2_costmap_2d::LayeredCostmap layers("map", false, true);
layers.resizeMap(10, 10, 1, 0, 0);

auto olayer = addObstacleLayer(layers, tf, node_);
Expand All @@ -275,7 +275,7 @@ TEST_F(TestNode, testZThreshold) {
*/
TEST_F(TestNode, testDynamicObstacles) {
tf2_ros::Buffer tf(node_->get_clock());
nav2_costmap_2d::LayeredCostmap layers("frame", false, false);
nav2_costmap_2d::LayeredCostmap layers("map", false, false);
addStaticLayer(layers, tf, node_);

auto olayer = addObstacleLayer(layers, tf, node_);
Expand All @@ -300,7 +300,7 @@ TEST_F(TestNode, testDynamicObstacles) {
*/
TEST_F(TestNode, testMultipleAdditions) {
tf2_ros::Buffer tf(node_->get_clock());
nav2_costmap_2d::LayeredCostmap layers("frame", false, false);
nav2_costmap_2d::LayeredCostmap layers("map", false, false);
addStaticLayer(layers, tf, node_);

auto olayer = addObstacleLayer(layers, tf, node_);
Expand All @@ -319,7 +319,7 @@ TEST_F(TestNode, testMultipleAdditions) {
*/
TEST_F(TestNode, testRepeatedResets) {
tf2_ros::Buffer tf(node_->get_clock());
nav2_costmap_2d::LayeredCostmap layers("frame", false, false);
nav2_costmap_2d::LayeredCostmap layers("map", false, false);

std::shared_ptr<nav2_costmap_2d::StaticLayer> slayer = nullptr;
addStaticLayer(layers, tf, node_, slayer);
Expand Down Expand Up @@ -370,7 +370,7 @@ TEST_F(TestNode, testRepeatedResets) {
TEST_F(TestNode, testRaytracing) {
tf2_ros::Buffer tf(node_->get_clock());

nav2_costmap_2d::LayeredCostmap layers("frame", false, false);
nav2_costmap_2d::LayeredCostmap layers("map", false, false);
layers.resizeMap(10, 10, 1, 0, 0);

std::shared_ptr<nav2_costmap_2d::StaticLayer> slayer = nullptr;
Expand Down Expand Up @@ -555,7 +555,7 @@ TEST_F(TestNode, testMaxCombinationMethod) {
tf2_ros::Buffer tf(node_->get_clock());

// Create a costmap with full unknown space
nav2_costmap_2d::LayeredCostmap layers("frame", false, true);
nav2_costmap_2d::LayeredCostmap layers("map", false, true);
layers.resizeMap(10, 10, 1, 0, 0);

std::shared_ptr<nav2_costmap_2d::ObstacleLayer> olayer = nullptr;
Expand Down Expand Up @@ -600,7 +600,7 @@ TEST_F(TestNodeWithoutUnknownOverwrite, testMaxWithoutUnknownOverwriteCombinatio
tf2_ros::Buffer tf(node_->get_clock());

// Create a costmap with full unknown space
nav2_costmap_2d::LayeredCostmap layers("frame", false, true);
nav2_costmap_2d::LayeredCostmap layers("map", false, true);
layers.resizeMap(10, 10, 1, 0, 0);

std::shared_ptr<nav2_costmap_2d::ObstacleLayer> olayer = nullptr;
Expand Down
18 changes: 9 additions & 9 deletions nav2_costmap_2d/test/integration/plugin_container_tests.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -158,7 +158,7 @@ class TestNode : public ::testing::Test
TEST_F(TestNode, testObstacleLayers) {
tf2_ros::Buffer tf(node_->get_clock());

nav2_costmap_2d::LayeredCostmap layers("frame", false, false);
nav2_costmap_2d::LayeredCostmap layers("map", false, false);
layers.resizeMap(10, 10, 1, 0, 0);

std::shared_ptr<nav2_costmap_2d::PluginContainerLayer> pclayer_a = nullptr;
Expand Down Expand Up @@ -191,7 +191,7 @@ TEST_F(TestNode, testObstacleAndStaticLayers) {
node_->declare_parameter("pclayer_a.static.map_topic",
rclcpp::ParameterValue(std::string("map")));

nav2_costmap_2d::LayeredCostmap layers("frame", false, false);
nav2_costmap_2d::LayeredCostmap layers("map", false, false);

layers.resizeMap(10, 10, 1, 0, 0);

Expand Down Expand Up @@ -232,7 +232,7 @@ TEST_F(TestNode, testDifferentInflationLayers) {
node_->declare_parameter("pclayer_b.inflation.inflation_radius",
rclcpp::ParameterValue(1.0));

nav2_costmap_2d::LayeredCostmap layers("frame", false, false);
nav2_costmap_2d::LayeredCostmap layers("map", false, false);

layers.resizeMap(10, 10, 1, 0, 0);

Expand Down Expand Up @@ -281,7 +281,7 @@ TEST_F(TestNode, testDifferentInflationLayers2) {
node_->declare_parameter("pclayer_a.inflation.inflation_radius",
rclcpp::ParameterValue(1.0));

nav2_costmap_2d::LayeredCostmap layers("frame", false, false);
nav2_costmap_2d::LayeredCostmap layers("map", false, false);

layers.resizeMap(10, 10, 1, 0, 0);

Expand Down Expand Up @@ -336,7 +336,7 @@ TEST_F(TestNode, testResetting) {
node_->declare_parameter("pclayer_b.inflation.inflation_radius",
rclcpp::ParameterValue(1.0));

nav2_costmap_2d::LayeredCostmap layers("frame", false, false);
nav2_costmap_2d::LayeredCostmap layers("map", false, false);

layers.resizeMap(10, 10, 1, 0, 0);

Expand Down Expand Up @@ -407,7 +407,7 @@ TEST_F(TestNode, testClearing) {
node_->declare_parameter("pclayer_b.inflation.inflation_radius",
rclcpp::ParameterValue(1.0));

nav2_costmap_2d::LayeredCostmap layers("frame", false, false);
nav2_costmap_2d::LayeredCostmap layers("map", false, false);

layers.resizeMap(10, 10, 1, 0, 0);

Expand Down Expand Up @@ -473,7 +473,7 @@ TEST_F(TestNode, testOverwriteCombinationMethods) {
node_->declare_parameter("pclayer_b.inflation.inflation_radius",
rclcpp::ParameterValue(1.0));

nav2_costmap_2d::LayeredCostmap layers("frame", false, false);
nav2_costmap_2d::LayeredCostmap layers("map", false, false);

layers.resizeMap(10, 10, 1, 0, 0);

Expand Down Expand Up @@ -534,7 +534,7 @@ TEST_F(TestNode, testWithoutUnknownOverwriteCombinationMethods) {
node_->declare_parameter("pclayer_b.inflation.inflation_radius",
rclcpp::ParameterValue(1.0));

nav2_costmap_2d::LayeredCostmap layers("frame", false, true);
nav2_costmap_2d::LayeredCostmap layers("map", false, true);

layers.resizeMap(10, 10, 1, 0, 0);

Expand Down Expand Up @@ -580,7 +580,7 @@ TEST_F(TestNode, testWithoutUnknownOverwriteCombinationMethods) {
TEST_F(TestNode, testClearable) {
tf2_ros::Buffer tf(node_->get_clock());

nav2_costmap_2d::LayeredCostmap layers("frame", false, false);
nav2_costmap_2d::LayeredCostmap layers("map", false, false);

std::shared_ptr<nav2_costmap_2d::PluginContainerLayer> pclayer_a = nullptr;
addPluginContainerLayer(layers, tf, node_, pclayer_a, "pclayer_a");
Expand Down
4 changes: 2 additions & 2 deletions nav2_costmap_2d/test/unit/declare_parameter_test.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -34,7 +34,7 @@ TEST(DeclareParameter, useValidParameter)
nav2_util::LifecycleNode::SharedPtr node =
std::make_shared<nav2_util::LifecycleNode>("test_node");
tf2_ros::Buffer tf(node->get_clock());
nav2_costmap_2d::LayeredCostmap layers("frame", false, false);
nav2_costmap_2d::LayeredCostmap layers("map", false, false);

layer.initialize(&layers, "test_layer", &tf, node, nullptr);

Expand All @@ -53,7 +53,7 @@ TEST(DeclareParameter, useInvalidParameter)
nav2_util::LifecycleNode::SharedPtr node =
std::make_shared<nav2_util::LifecycleNode>("test_node");
tf2_ros::Buffer tf(node->get_clock());
nav2_costmap_2d::LayeredCostmap layers("frame", false, false);
nav2_costmap_2d::LayeredCostmap layers("map", false, false);

layer.initialize(&layers, "test_layer", &tf, node, nullptr);

Expand Down
Loading