Skip to content

Commit 536ed1f

Browse files
authored
Fix cppcheck errors (#1718)
* Fix cppcheck errors Signed-off-by: Sarthak Mittal <sarthakmittal2608@gmail.com> * Fix test name generator * Fix returning after it is deallocated / released error * Increase sleep to 10 seconds to allow map server node to start up * Fix infinite wait for service in nav2_map_server tests
1 parent 7addcb7 commit 536ed1f

File tree

8 files changed

+145
-89
lines changed

8 files changed

+145
-89
lines changed

‎nav2_costmap_2d/include/nav2_costmap_2d/testing_helper.hpp‎

Lines changed: 13 additions & 13 deletions
Original file line numberDiff line numberDiff line change
@@ -77,28 +77,28 @@ unsigned int countValues(
7777
return count;
7878
}
7979

80-
nav2_costmap_2d::StaticLayer * addStaticLayer(
80+
void addStaticLayer(
8181
nav2_costmap_2d::LayeredCostmap & layers,
82-
tf2_ros::Buffer & tf, nav2_util::LifecycleNode::SharedPtr node)
82+
tf2_ros::Buffer & tf, nav2_util::LifecycleNode::SharedPtr node,
83+
std::shared_ptr<nav2_costmap_2d::StaticLayer> & slayer)
8384
{
84-
nav2_costmap_2d::StaticLayer * slayer = new nav2_costmap_2d::StaticLayer();
85+
slayer = std::make_shared<nav2_costmap_2d::StaticLayer>();
8586
layers.addPlugin(std::shared_ptr<nav2_costmap_2d::Layer>(slayer));
8687
slayer->initialize(&layers, "static", &tf, node, nullptr, nullptr /*TODO*/);
87-
return slayer;
8888
}
8989

90-
nav2_costmap_2d::ObstacleLayer * addObstacleLayer(
90+
void addObstacleLayer(
9191
nav2_costmap_2d::LayeredCostmap & layers,
92-
tf2_ros::Buffer & tf, nav2_util::LifecycleNode::SharedPtr node)
92+
tf2_ros::Buffer & tf, nav2_util::LifecycleNode::SharedPtr node,
93+
std::shared_ptr<nav2_costmap_2d::ObstacleLayer> & olayer)
9394
{
94-
nav2_costmap_2d::ObstacleLayer * olayer = new nav2_costmap_2d::ObstacleLayer();
95+
olayer = std::make_shared<nav2_costmap_2d::ObstacleLayer>();
9596
olayer->initialize(&layers, "obstacles", &tf, node, nullptr, nullptr /*TODO*/);
9697
layers.addPlugin(std::shared_ptr<nav2_costmap_2d::Layer>(olayer));
97-
return olayer;
9898
}
9999

100100
void addObservation(
101-
nav2_costmap_2d::ObstacleLayer * olayer, double x, double y, double z = 0.0,
101+
std::shared_ptr<nav2_costmap_2d::ObstacleLayer> & olayer, double x, double y, double z = 0.0,
102102
double ox = 0.0, double oy = 0.0, double oz = MAX_Z)
103103
{
104104
sensor_msgs::msg::PointCloud2 cloud;
@@ -122,15 +122,15 @@ void addObservation(
122122
olayer->addStaticObservation(obs, true, true);
123123
}
124124

125-
nav2_costmap_2d::InflationLayer * addInflationLayer(
125+
void addInflationLayer(
126126
nav2_costmap_2d::LayeredCostmap & layers,
127-
tf2_ros::Buffer & tf, nav2_util::LifecycleNode::SharedPtr node)
127+
tf2_ros::Buffer & tf, nav2_util::LifecycleNode::SharedPtr node,
128+
std::shared_ptr<nav2_costmap_2d::InflationLayer> & ilayer)
128129
{
129-
nav2_costmap_2d::InflationLayer * ilayer = new nav2_costmap_2d::InflationLayer();
130+
ilayer = std::make_shared<nav2_costmap_2d::InflationLayer>();
130131
ilayer->initialize(&layers, "inflation", &tf, node, nullptr, nullptr /*TODO*/);
131132
std::shared_ptr<nav2_costmap_2d::Layer> ipointer(ilayer);
132133
layers.addPlugin(ipointer);
133-
return ilayer;
134134
}
135135

136136

‎nav2_costmap_2d/test/integration/inflation_tests.cpp‎

Lines changed: 51 additions & 20 deletions
Original file line numberDiff line numberDiff line change
@@ -72,12 +72,12 @@ class TestNode : public ::testing::Test
7272
void validatePointInflation(
7373
unsigned int mx, unsigned int my,
7474
nav2_costmap_2d::Costmap2D * costmap,
75-
nav2_costmap_2d::InflationLayer * ilayer,
75+
std::shared_ptr<nav2_costmap_2d::InflationLayer> & ilayer,
7676
double inflation_radius);
7777

7878
void initNode(double inflation_radius);
7979

80-
void waitForMap(nav2_costmap_2d::StaticLayer * slayer);
80+
void waitForMap(std::shared_ptr<nav2_costmap_2d::StaticLayer> & slayer);
8181

8282
protected:
8383
nav2_util::LifecycleNode::SharedPtr node_;
@@ -106,7 +106,7 @@ std::vector<Point> TestNode::setRadii(
106106
return polygon;
107107
}
108108

109-
void TestNode::waitForMap(nav2_costmap_2d::StaticLayer * slayer)
109+
void TestNode::waitForMap(std::shared_ptr<nav2_costmap_2d::StaticLayer> & slayer)
110110
{
111111
while (!slayer->isCurrent()) {
112112
rclcpp::spin_some(node_->get_node_base_interface());
@@ -117,7 +117,7 @@ void TestNode::waitForMap(nav2_costmap_2d::StaticLayer * slayer)
117117
void TestNode::validatePointInflation(
118118
unsigned int mx, unsigned int my,
119119
nav2_costmap_2d::Costmap2D * costmap,
120-
nav2_costmap_2d::InflationLayer * ilayer,
120+
std::shared_ptr<nav2_costmap_2d::InflationLayer> & ilayer,
121121
double inflation_radius)
122122
{
123123
bool * seen = new bool[costmap->getSizeInCellsX() * costmap->getSizeInCellsY()];
@@ -206,8 +206,12 @@ TEST_F(TestNode, testAdjacentToObstacleCanStillMove)
206206
// circumscribed radius = 3.1
207207
std::vector<Point> polygon = setRadii(layers, 2.1, 2.3);
208208

209-
nav2_costmap_2d::ObstacleLayer * olayer = addObstacleLayer(layers, tf, node_);
210-
addInflationLayer(layers, tf, node_);
209+
std::shared_ptr<nav2_costmap_2d::ObstacleLayer> olayer = nullptr;
210+
addObstacleLayer(layers, tf, node_, olayer);
211+
212+
std::shared_ptr<nav2_costmap_2d::InflationLayer> ilayer = nullptr;
213+
addInflationLayer(layers, tf, node_, ilayer);
214+
211215
layers.setFootprint(polygon);
212216

213217
addObservation(olayer, 0, 0, MAX_Z);
@@ -234,8 +238,12 @@ TEST_F(TestNode, testInflationShouldNotCreateUnknowns)
234238
// circumscribed radius = 3.1
235239
std::vector<Point> polygon = setRadii(layers, 2.1, 2.3);
236240

237-
nav2_costmap_2d::ObstacleLayer * olayer = addObstacleLayer(layers, tf, node_);
238-
addInflationLayer(layers, tf, node_);
241+
std::shared_ptr<nav2_costmap_2d::ObstacleLayer> olayer = nullptr;
242+
addObstacleLayer(layers, tf, node_, olayer);
243+
244+
std::shared_ptr<nav2_costmap_2d::InflationLayer> ilayer = nullptr;
245+
addInflationLayer(layers, tf, node_, ilayer);
246+
239247
layers.setFootprint(polygon);
240248

241249
addObservation(olayer, 0, 0, MAX_Z);
@@ -260,8 +268,12 @@ TEST_F(TestNode, testCostFunctionCorrectness)
260268
// circumscribed radius = 8.0
261269
std::vector<Point> polygon = setRadii(layers, 5.0, 6.25);
262270

263-
nav2_costmap_2d::ObstacleLayer * olayer = addObstacleLayer(layers, tf, node_);
264-
nav2_costmap_2d::InflationLayer * ilayer = addInflationLayer(layers, tf, node_);
271+
std::shared_ptr<nav2_costmap_2d::ObstacleLayer> olayer = nullptr;
272+
addObstacleLayer(layers, tf, node_, olayer);
273+
274+
std::shared_ptr<nav2_costmap_2d::InflationLayer> ilayer = nullptr;
275+
addInflationLayer(layers, tf, node_, ilayer);
276+
265277
layers.setFootprint(polygon);
266278

267279
addObservation(olayer, 50, 50, MAX_Z);
@@ -331,8 +343,12 @@ TEST_F(TestNode, testInflationOrderCorrectness)
331343
// circumscribed radius = 3.1
332344
std::vector<Point> polygon = setRadii(layers, 2.1, 2.3);
333345

334-
nav2_costmap_2d::ObstacleLayer * olayer = addObstacleLayer(layers, tf, node_);
335-
nav2_costmap_2d::InflationLayer * ilayer = addInflationLayer(layers, tf, node_);
346+
std::shared_ptr<nav2_costmap_2d::ObstacleLayer> olayer = nullptr;
347+
addObstacleLayer(layers, tf, node_, olayer);
348+
349+
std::shared_ptr<nav2_costmap_2d::InflationLayer> ilayer = nullptr;
350+
addInflationLayer(layers, tf, node_, ilayer);
351+
336352
layers.setFootprint(polygon);
337353

338354
// Add two diagonal cells, they would induce problems under the
@@ -359,9 +375,14 @@ TEST_F(TestNode, testInflation)
359375
// circumscribed radius = 3.1
360376
std::vector<Point> polygon = setRadii(layers, 1, 1);
361377

362-
auto slayer = addStaticLayer(layers, tf, node_);
363-
nav2_costmap_2d::ObstacleLayer * olayer = addObstacleLayer(layers, tf, node_);
364-
addInflationLayer(layers, tf, node_);
378+
std::shared_ptr<nav2_costmap_2d::StaticLayer> slayer = nullptr;
379+
addStaticLayer(layers, tf, node_, slayer);
380+
381+
std::shared_ptr<nav2_costmap_2d::ObstacleLayer> olayer = nullptr;
382+
addObstacleLayer(layers, tf, node_, olayer);
383+
384+
std::shared_ptr<nav2_costmap_2d::InflationLayer> ilayer = nullptr;
385+
addInflationLayer(layers, tf, node_, ilayer);
365386
layers.setFootprint(polygon);
366387

367388
nav2_costmap_2d::Costmap2D * costmap = layers.getCostmap();
@@ -432,9 +453,15 @@ TEST_F(TestNode, testInflation2)
432453
// circumscribed radius = 3.1
433454
std::vector<Point> polygon = setRadii(layers, 1, 1);
434455

435-
auto slayer = addStaticLayer(layers, tf, node_);
436-
nav2_costmap_2d::ObstacleLayer * olayer = addObstacleLayer(layers, tf, node_);
437-
addInflationLayer(layers, tf, node_);
456+
std::shared_ptr<nav2_costmap_2d::StaticLayer> slayer = nullptr;
457+
addStaticLayer(layers, tf, node_, slayer);
458+
459+
std::shared_ptr<nav2_costmap_2d::ObstacleLayer> olayer = nullptr;
460+
addObstacleLayer(layers, tf, node_, olayer);
461+
462+
std::shared_ptr<nav2_costmap_2d::InflationLayer> ilayer = nullptr;
463+
addInflationLayer(layers, tf, node_, ilayer);
464+
438465
layers.setFootprint(polygon);
439466

440467
waitForMap(slayer);
@@ -464,8 +491,12 @@ TEST_F(TestNode, testInflation3)
464491
// 1 2 3
465492
std::vector<Point> polygon = setRadii(layers, 1, 1.75);
466493

467-
nav2_costmap_2d::ObstacleLayer * olayer = addObstacleLayer(layers, tf, node_);
468-
addInflationLayer(layers, tf, node_);
494+
std::shared_ptr<nav2_costmap_2d::ObstacleLayer> olayer = nullptr;
495+
addObstacleLayer(layers, tf, node_, olayer);
496+
497+
std::shared_ptr<nav2_costmap_2d::InflationLayer> ilayer = nullptr;
498+
addInflationLayer(layers, tf, node_, ilayer);
499+
469500
layers.setFootprint(polygon);
470501

471502
// There should be no occupied cells

‎nav2_costmap_2d/test/integration/obstacle_tests.cpp‎

Lines changed: 9 additions & 7 deletions
Original file line numberDiff line numberDiff line change
@@ -157,7 +157,7 @@ TEST_F(TestNode, testRaytracing) {
157157

158158
nav2_costmap_2d::LayeredCostmap layers("frame", false, false);
159159
addStaticLayer(layers, tf, node_);
160-
nav2_costmap_2d::ObstacleLayer * olayer = addObstacleLayer(layers, tf, node_);
160+
auto olayer = addObstacleLayer(layers, tf, node_);
161161

162162
// Add a point at 0, 0, 0
163163
addObservation(olayer, 0.0, 0.0, MAX_Z / 2, 0, 0, MAX_Z / 2);
@@ -179,7 +179,7 @@ TEST_F(TestNode, testRaytracing2) {
179179
tf2_ros::Buffer tf(node_->get_clock());
180180
nav2_costmap_2d::LayeredCostmap layers("frame", false, false);
181181
addStaticLayer(layers, tf, node_);
182-
nav2_costmap_2d::ObstacleLayer * olayer = addObstacleLayer(layers, tf, node_);
182+
auto olayer = addObstacleLayer(layers, tf, node_);
183183

184184
// If we print map now, it is 10x10 all value 0
185185
// printMap(*(layers.getCostmap()));
@@ -236,7 +236,7 @@ TEST_F(TestNode, testWaveInterference) {
236236
// Start with an empty map, no rolling window, tracking unknown
237237
nav2_costmap_2d::LayeredCostmap layers("frame", false, true);
238238
layers.resizeMap(10, 10, 1, 0, 0);
239-
nav2_costmap_2d::ObstacleLayer * olayer = addObstacleLayer(layers, tf, node_);
239+
auto olayer = addObstacleLayer(layers, tf, node_);
240240

241241
// If we print map now, it is 10x10, all cells are 255 (NO_INFORMATION)
242242
// printMap(*(layers.getCostmap()));
@@ -265,7 +265,7 @@ TEST_F(TestNode, testZThreshold) {
265265
nav2_costmap_2d::LayeredCostmap layers("frame", false, true);
266266
layers.resizeMap(10, 10, 1, 0, 0);
267267

268-
nav2_costmap_2d::ObstacleLayer * olayer = addObstacleLayer(layers, tf, node_);
268+
auto olayer = addObstacleLayer(layers, tf, node_);
269269

270270
// A point cloud with 2 points falling in a cell with a non-lethal cost
271271
addObservation(olayer, 0.0, 5.0, 0.4);
@@ -285,7 +285,7 @@ TEST_F(TestNode, testDynamicObstacles) {
285285
nav2_costmap_2d::LayeredCostmap layers("frame", false, false);
286286
addStaticLayer(layers, tf, node_);
287287

288-
nav2_costmap_2d::ObstacleLayer * olayer = addObstacleLayer(layers, tf, node_);
288+
auto olayer = addObstacleLayer(layers, tf, node_);
289289

290290
// Add a point cloud and verify its insertion. There should be only one new one
291291
addObservation(olayer, 0.0, 0.0);
@@ -310,7 +310,7 @@ TEST_F(TestNode, testMultipleAdditions) {
310310
nav2_costmap_2d::LayeredCostmap layers("frame", false, false);
311311
addStaticLayer(layers, tf, node_);
312312

313-
nav2_costmap_2d::ObstacleLayer * olayer = addObstacleLayer(layers, tf, node_);
313+
auto olayer = addObstacleLayer(layers, tf, node_);
314314

315315
// A point cloud with one point that falls within an existing obstacle
316316
addObservation(olayer, 9.5, 0.0);
@@ -327,7 +327,9 @@ TEST_F(TestNode, testMultipleAdditions) {
327327
TEST_F(TestNode, testRepeatedResets) {
328328
tf2_ros::Buffer tf(node_->get_clock());
329329
nav2_costmap_2d::LayeredCostmap layers("frame", false, false);
330-
addStaticLayer(layers, tf, node_);
330+
331+
std::shared_ptr<nav2_costmap_2d::StaticLayer> slayer = nullptr;
332+
addStaticLayer(layers, tf, node_, slayer);
331333

332334
// TODO(orduno) Add obstacle layer
333335

‎nav2_costmap_2d/test/integration/test_collision_checker.cpp‎

Lines changed: 5 additions & 2 deletions
Original file line numberDiff line numberDiff line change
@@ -128,12 +128,15 @@ class TestCollisionChecker : public nav2_util::LifecycleNode
128128

129129
layers_ = new nav2_costmap_2d::LayeredCostmap("map", false, false);
130130
// Add Static Layer
131-
auto slayer = addStaticLayer(*layers_, *tf_buffer_, shared_from_this());
131+
std::shared_ptr<nav2_costmap_2d::StaticLayer> slayer = nullptr;
132+
addStaticLayer(*layers_, *tf_buffer_, shared_from_this(), slayer);
133+
132134
while (!slayer->isCurrent()) {
133135
rclcpp::spin_some(this->get_node_base_interface());
134136
}
135137
// Add Inflation Layer
136-
addInflationLayer(*layers_, *tf_buffer_, shared_from_this());
138+
std::shared_ptr<nav2_costmap_2d::InflationLayer> ilayer = nullptr;
139+
addInflationLayer(*layers_, *tf_buffer_, shared_from_this(), ilayer);
137140

138141
return nav2_util::CallbackReturn::SUCCESS;
139142
}

‎nav2_map_server/test/component/test_map_saver_node.cpp‎

Lines changed: 19 additions & 20 deletions
Original file line numberDiff line numberDiff line change
@@ -39,25 +39,23 @@ class RclCppFixture
3939

4040
RclCppFixture g_rclcppfixture;
4141

42-
class TestNode : public ::testing::Test
42+
class MapSaverTestFixture : public ::testing::Test
4343
{
4444
public:
45-
TestNode()
45+
static void SetUpTestCase()
4646
{
4747
node_ = rclcpp::Node::make_shared("map_client_test");
48-
map_server_node_name_ = "map_saver";
4948
lifecycle_client_ =
50-
std::make_shared<nav2_util::LifecycleServiceClient>(map_server_node_name_, node_);
49+
std::make_shared<nav2_util::LifecycleServiceClient>("map_saver", node_);
5150
RCLCPP_INFO(node_->get_logger(), "Creating Test Node");
5251

53-
54-
std::this_thread::sleep_for(std::chrono::seconds(1)); // allow node to start up
52+
std::this_thread::sleep_for(std::chrono::seconds(5)); // allow node to start up
5553
const std::chrono::seconds timeout(5);
5654
lifecycle_client_->change_state(Transition::TRANSITION_CONFIGURE, timeout);
5755
lifecycle_client_->change_state(Transition::TRANSITION_ACTIVATE, timeout);
5856
}
5957

60-
~TestNode()
58+
static void TearDownTestCase()
6159
{
6260
lifecycle_client_->change_state(Transition::TRANSITION_DEACTIVATE);
6361
lifecycle_client_->change_state(Transition::TRANSITION_CLEANUP);
@@ -73,10 +71,7 @@ class TestNode : public ::testing::Test
7371
auto result = client->async_send_request(request);
7472

7573
// Wait for the result
76-
if (
77-
rclcpp::spin_until_future_complete(node, result) ==
78-
rclcpp::executor::FutureReturnCode::SUCCESS)
79-
{
74+
if (rclcpp::spin_until_future_complete(node, result) == rclcpp::FutureReturnCode::SUCCESS) {
8075
return result.get();
8176
} else {
8277
return nullptr;
@@ -96,19 +91,23 @@ class TestNode : public ::testing::Test
9691
}
9792
}
9893

99-
std::string map_server_node_name_;
100-
rclcpp::Node::SharedPtr node_;
101-
std::shared_ptr<nav2_util::LifecycleServiceClient> lifecycle_client_;
94+
static rclcpp::Node::SharedPtr node_;
95+
static std::shared_ptr<nav2_util::LifecycleServiceClient> lifecycle_client_;
10296
};
10397

98+
99+
rclcpp::Node::SharedPtr MapSaverTestFixture::node_ = nullptr;
100+
std::shared_ptr<nav2_util::LifecycleServiceClient> MapSaverTestFixture::lifecycle_client_ =
101+
nullptr;
102+
104103
// Send map saving service request.
105104
// Load saved map and verify obtained OccupancyGrid.
106-
TEST_F(TestNode, SaveMap)
105+
TEST_F(MapSaverTestFixture, SaveMap)
107106
{
108107
RCLCPP_INFO(node_->get_logger(), "Testing SaveMap service");
109108
auto req = std::make_shared<nav2_msgs::srv::SaveMap::Request>();
110109
auto client = node_->create_client<nav2_msgs::srv::SaveMap>(
111-
"/" + map_server_node_name_ + "/save_map");
110+
"/map_saver/save_map");
112111

113112
RCLCPP_INFO(node_->get_logger(), "Waiting for save_map service");
114113
ASSERT_TRUE(client->wait_for_service());
@@ -132,12 +131,12 @@ TEST_F(TestNode, SaveMap)
132131

133132
// Send map saving service request with default parameters.
134133
// Load saved map and verify obtained OccupancyGrid.
135-
TEST_F(TestNode, SaveMapDefaultParameters)
134+
TEST_F(MapSaverTestFixture, SaveMapDefaultParameters)
136135
{
137136
RCLCPP_INFO(node_->get_logger(), "Testing SaveMap service");
138137
auto req = std::make_shared<nav2_msgs::srv::SaveMap::Request>();
139138
auto client = node_->create_client<nav2_msgs::srv::SaveMap>(
140-
"/" + map_server_node_name_ + "/save_map");
139+
"/map_saver/save_map");
141140

142141
RCLCPP_INFO(node_->get_logger(), "Waiting for save_map service");
143142
ASSERT_TRUE(client->wait_for_service());
@@ -162,12 +161,12 @@ TEST_F(TestNode, SaveMapDefaultParameters)
162161
// Send map saving service requests with different sets of parameters.
163162
// In case of map is expected to be saved correctly, load map from a saved
164163
// file and verify obtained OccupancyGrid.
165-
TEST_F(TestNode, SaveMapInvalidParameters)
164+
TEST_F(MapSaverTestFixture, SaveMapInvalidParameters)
166165
{
167166
RCLCPP_INFO(node_->get_logger(), "Testing SaveMap service");
168167
auto req = std::make_shared<nav2_msgs::srv::SaveMap::Request>();
169168
auto client = node_->create_client<nav2_msgs::srv::SaveMap>(
170-
"/" + map_server_node_name_ + "/save_map");
169+
"/map_saver/save_map");
171170

172171
RCLCPP_INFO(node_->get_logger(), "Waiting for save_map service");
173172
ASSERT_TRUE(client->wait_for_service());

0 commit comments

Comments
 (0)