1+ // Copyright 2025 Kudan Ltd
2+
3+ // Licensed under the Apache License, Version 2.0 (the "License");
4+ // you may not use this file except in compliance with the License.
5+ // You may obtain a copy of the License at
6+ //
7+ // http://www.apache.org/licenses/LICENSE-2.0
8+ //
9+ // Unless required by applicable law or agreed to in writing, software
10+ // distributed under the License is distributed on an "AS IS" BASIS,
11+ // WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.
12+ // See the License for the specific language governing permissions and
13+ // limitations under the License.
14+
15+ #include < gtest/gtest.h>
16+
17+ #include < cstdio>
18+ #include < memory>
19+ #include < string>
20+
121#include " nav2_costmap_2d/cost_values.hpp"
222#include " nav2_costmap_2d/layered_costmap.hpp"
323#include " nav2_costmap_2d/obstacle_layer.hpp"
424#include " ../testing_helper.hpp"
525#include " tf2_ros/buffer.hpp"
626
7- #include < cstdio>
8- #include < memory>
9- #include < string>
10- #include < gtest/gtest.h>
11-
1227
1328class RclCppFixture
1429{
@@ -60,7 +75,7 @@ class TestLifecycleNode : public nav2::LifecycleNode
6075class ObstacleLayerTest : public ::testing::Test
6176{
6277public:
63- ObstacleLayerTest (double resolution = 0.1 )
78+ explicit ObstacleLayerTest (double resolution = 0.1 )
6479 : layers_(" frame" , false , false )
6580 {
6681 node_ = std::make_shared<TestLifecycleNode>(" obstacle_cell_distance_test_node" );
@@ -75,7 +90,8 @@ class ObstacleLayerTest : public ::testing::Test
7590 node_->declare_parameter (" transform_tolerance" , rclcpp::ParameterValue (0.3 ));
7691 node_->declare_parameter (" observation_sources" , rclcpp::ParameterValue (std::string (" " )));
7792
78- layers_.resizeMap (20 , 20 , resolution, 0 , 0 ); // 20x20 cells
93+ // 20x20 cells with origin at (0, 0)
94+ layers_.resizeMap (20 , 20 , resolution, 0 , 0 );
7995 tf2_ros::Buffer tf (node_->get_clock ());
8096 addObstacleLayer (layers_, tf, node_, obstacle_layer_);
8197 }
0 commit comments