@@ -148,7 +148,7 @@ class TestNode : public ::testing::Test
148
148
TEST_F (TestNode, testRaytracing) {
149
149
tf2_ros::Buffer tf (node_->get_clock ());
150
150
151
- nav2_costmap_2d::LayeredCostmap layers (" frame " , false , false );
151
+ nav2_costmap_2d::LayeredCostmap layers (" map " , false , false );
152
152
addStaticLayer (layers, tf, node_);
153
153
auto olayer = addObstacleLayer (layers, tf, node_);
154
154
@@ -170,7 +170,7 @@ TEST_F(TestNode, testRaytracing) {
170
170
*/
171
171
TEST_F (TestNode, testRaytracing2) {
172
172
tf2_ros::Buffer tf (node_->get_clock ());
173
- nav2_costmap_2d::LayeredCostmap layers (" frame " , false , false );
173
+ nav2_costmap_2d::LayeredCostmap layers (" map " , false , false );
174
174
addStaticLayer (layers, tf, node_);
175
175
auto olayer = addObstacleLayer (layers, tf, node_);
176
176
@@ -227,7 +227,7 @@ TEST_F(TestNode, testWaveInterference) {
227
227
tf2_ros::Buffer tf (node_->get_clock ());
228
228
node_->set_parameter (rclcpp::Parameter (" track_unknown_space" , true ));
229
229
// Start with an empty map, no rolling window, tracking unknown
230
- nav2_costmap_2d::LayeredCostmap layers (" frame " , false , true );
230
+ nav2_costmap_2d::LayeredCostmap layers (" map " , false , true );
231
231
layers.resizeMap (10 , 10 , 1 , 0 , 0 );
232
232
auto olayer = addObstacleLayer (layers, tf, node_);
233
233
@@ -255,7 +255,7 @@ TEST_F(TestNode, testWaveInterference) {
255
255
TEST_F (TestNode, testZThreshold) {
256
256
tf2_ros::Buffer tf (node_->get_clock ());
257
257
// Start with an empty map
258
- nav2_costmap_2d::LayeredCostmap layers (" frame " , false , true );
258
+ nav2_costmap_2d::LayeredCostmap layers (" map " , false , true );
259
259
layers.resizeMap (10 , 10 , 1 , 0 , 0 );
260
260
261
261
auto olayer = addObstacleLayer (layers, tf, node_);
@@ -275,7 +275,7 @@ TEST_F(TestNode, testZThreshold) {
275
275
*/
276
276
TEST_F (TestNode, testDynamicObstacles) {
277
277
tf2_ros::Buffer tf (node_->get_clock ());
278
- nav2_costmap_2d::LayeredCostmap layers (" frame " , false , false );
278
+ nav2_costmap_2d::LayeredCostmap layers (" map " , false , false );
279
279
addStaticLayer (layers, tf, node_);
280
280
281
281
auto olayer = addObstacleLayer (layers, tf, node_);
@@ -300,7 +300,7 @@ TEST_F(TestNode, testDynamicObstacles) {
300
300
*/
301
301
TEST_F (TestNode, testMultipleAdditions) {
302
302
tf2_ros::Buffer tf (node_->get_clock ());
303
- nav2_costmap_2d::LayeredCostmap layers (" frame " , false , false );
303
+ nav2_costmap_2d::LayeredCostmap layers (" map " , false , false );
304
304
addStaticLayer (layers, tf, node_);
305
305
306
306
auto olayer = addObstacleLayer (layers, tf, node_);
@@ -319,7 +319,7 @@ TEST_F(TestNode, testMultipleAdditions) {
319
319
*/
320
320
TEST_F (TestNode, testRepeatedResets) {
321
321
tf2_ros::Buffer tf (node_->get_clock ());
322
- nav2_costmap_2d::LayeredCostmap layers (" frame " , false , false );
322
+ nav2_costmap_2d::LayeredCostmap layers (" map " , false , false );
323
323
324
324
std::shared_ptr<nav2_costmap_2d::StaticLayer> slayer = nullptr ;
325
325
addStaticLayer (layers, tf, node_, slayer);
@@ -370,7 +370,7 @@ TEST_F(TestNode, testRepeatedResets) {
370
370
TEST_F (TestNode, testRaytracing) {
371
371
tf2_ros::Buffer tf (node_->get_clock ());
372
372
373
- nav2_costmap_2d::LayeredCostmap layers (" frame " , false , false );
373
+ nav2_costmap_2d::LayeredCostmap layers (" map " , false , false );
374
374
layers.resizeMap (10 , 10 , 1 , 0 , 0 );
375
375
376
376
std::shared_ptr<nav2_costmap_2d::StaticLayer> slayer = nullptr ;
@@ -555,7 +555,7 @@ TEST_F(TestNode, testMaxCombinationMethod) {
555
555
tf2_ros::Buffer tf (node_->get_clock ());
556
556
557
557
// Create a costmap with full unknown space
558
- nav2_costmap_2d::LayeredCostmap layers (" frame " , false , true );
558
+ nav2_costmap_2d::LayeredCostmap layers (" map " , false , true );
559
559
layers.resizeMap (10 , 10 , 1 , 0 , 0 );
560
560
561
561
std::shared_ptr<nav2_costmap_2d::ObstacleLayer> olayer = nullptr ;
@@ -600,7 +600,7 @@ TEST_F(TestNodeWithoutUnknownOverwrite, testMaxWithoutUnknownOverwriteCombinatio
600
600
tf2_ros::Buffer tf (node_->get_clock ());
601
601
602
602
// Create a costmap with full unknown space
603
- nav2_costmap_2d::LayeredCostmap layers (" frame " , false , true );
603
+ nav2_costmap_2d::LayeredCostmap layers (" map " , false , true );
604
604
layers.resizeMap (10 , 10 , 1 , 0 , 0 );
605
605
606
606
std::shared_ptr<nav2_costmap_2d::ObstacleLayer> olayer = nullptr ;
0 commit comments