From 9f5564576adc11927ed0870840560d875edd0f03 Mon Sep 17 00:00:00 2001 From: bpwilcox <bpwilcox@eng.ucsd.edu> Date: Thu, 13 Jun 2019 12:32:42 -0700 Subject: [PATCH] use unsigned int shorthand --- .../test/integration/footprint_tests.cpp | 10 +++---- .../test/integration/inflation_tests.cpp | 26 +++++++++---------- .../test/unit/array_parser_test.cpp | 6 ++--- 3 files changed, 21 insertions(+), 21 deletions(-) diff --git a/nav2_costmap_2d/test/integration/footprint_tests.cpp b/nav2_costmap_2d/test/integration/footprint_tests.cpp index 1a0f2cbf..f2aa7c74 100644 --- a/nav2_costmap_2d/test/integration/footprint_tests.cpp +++ b/nav2_costmap_2d/test/integration/footprint_tests.cpp @@ -118,7 +118,7 @@ TEST_F(TestNode, footprint_empty) std::vector<geometry_msgs::msg::Point> footprint = footprint_tester_->getRobotFootprint(); // With no specification of footprint or radius, // defaults to 0.1 meter radius plus 0.01 meter padding. - EXPECT_EQ((unsigned int)16, footprint.size()); + EXPECT_EQ(16u, footprint.size()); EXPECT_NEAR(0.11f, footprint[0].x, 0.0001); EXPECT_NEAR(0.0f, footprint[0].y, 0.0001); @@ -130,7 +130,7 @@ TEST_F(TestNode, unpadded_footprint_from_string_param) footprint_tester_->testFootprint(0.0, "[[1, 1], [-1, 1], [-1, -1]]"); std::vector<geometry_msgs::msg::Point> footprint = footprint_tester_->getRobotFootprint(); - EXPECT_EQ((unsigned int)3, footprint.size()); + EXPECT_EQ(3u, footprint.size()); EXPECT_EQ(1.0f, footprint[0].x); EXPECT_EQ(1.0f, footprint[0].y); @@ -150,7 +150,7 @@ TEST_F(TestNode, padded_footprint_from_string_param) footprint_tester_->testFootprint(0.5, "[[1, 1], [-1, 1], [-1, -1]]"); std::vector<geometry_msgs::msg::Point> footprint = footprint_tester_->getRobotFootprint(); - EXPECT_EQ((unsigned int)3, footprint.size()); + EXPECT_EQ(3u, footprint.size()); EXPECT_EQ(1.5f, footprint[0].x); EXPECT_EQ(1.5f, footprint[0].y); @@ -170,7 +170,7 @@ TEST_F(TestNode, radius_param) footprint_tester_->testFootprint(0, 10.0); std::vector<geometry_msgs::msg::Point> footprint = footprint_tester_->getRobotFootprint(); // Circular robot has 16-point footprint auto-generated. - EXPECT_EQ((unsigned int)16, footprint.size()); + EXPECT_EQ(16u, footprint.size()); // Check the first point EXPECT_EQ(10.0f, footprint[0].x); @@ -187,7 +187,7 @@ TEST_F(TestNode, footprint_from_same_level_param) { footprint_tester_->testFootprint(0.0, "[[1, 2], [3, 4], [5, 6]]"); std::vector<geometry_msgs::msg::Point> footprint = footprint_tester_->getRobotFootprint(); - EXPECT_EQ((unsigned int)3, footprint.size()); + EXPECT_EQ(3u, footprint.size()); EXPECT_EQ(1.0f, footprint[0].x); EXPECT_EQ(2.0f, footprint[0].y); diff --git a/nav2_costmap_2d/test/integration/inflation_tests.cpp b/nav2_costmap_2d/test/integration/inflation_tests.cpp index deb47c27..1338f9b1 100644 --- a/nav2_costmap_2d/test/integration/inflation_tests.cpp +++ b/nav2_costmap_2d/test/integration/inflation_tests.cpp @@ -232,7 +232,7 @@ TEST_F(TestNode, testInflationShouldNotCreateUnknowns) layers.updateMap(0, 0, 0); nav2_costmap_2d::Costmap2D * costmap = layers.getCostmap(); - EXPECT_EQ(countValues(*costmap, nav2_costmap_2d::NO_INFORMATION), (unsigned int)0); + EXPECT_EQ(countValues(*costmap, nav2_costmap_2d::NO_INFORMATION), 0u); } /** @@ -357,8 +357,8 @@ TEST_F(TestNode, testInflation) layers.updateMap(0, 0, 0); // printMap(*costmap); - ASSERT_EQ(countValues(*costmap, nav2_costmap_2d::LETHAL_OBSTACLE), (unsigned int)20); - ASSERT_EQ(countValues(*costmap, nav2_costmap_2d::INSCRIBED_INFLATED_OBSTACLE), (unsigned int)28); + ASSERT_EQ(countValues(*costmap, nav2_costmap_2d::LETHAL_OBSTACLE), 20u); + ASSERT_EQ(countValues(*costmap, nav2_costmap_2d::INSCRIBED_INFLATED_OBSTACLE), 28u); /*/ Iterate over all id's and verify they are obstacles for(std::vector<unsigned int>::const_iterator it = occupiedCells.begin(); it != occupiedCells.end(); ++it){ @@ -375,7 +375,7 @@ TEST_F(TestNode, testInflation) // It and its 2 neighbors makes 3 obstacles ASSERT_EQ(countValues(*costmap, nav2_costmap_2d::LETHAL_OBSTACLE) + - countValues(*costmap, nav2_costmap_2d::INSCRIBED_INFLATED_OBSTACLE), (unsigned int)51); + countValues(*costmap, nav2_costmap_2d::INSCRIBED_INFLATED_OBSTACLE), 51u); // @todo Rewrite // Add an obstacle at <2,0> which will inflate and refresh to of the other inflated cells @@ -388,7 +388,7 @@ TEST_F(TestNode, testInflation) // but not over-writing the inflation of the obstacle // at <0, 1> ASSERT_EQ(countValues(*costmap, nav2_costmap_2d::LETHAL_OBSTACLE) + - countValues(*costmap, nav2_costmap_2d::INSCRIBED_INFLATED_OBSTACLE), (unsigned int)54); + countValues(*costmap, nav2_costmap_2d::INSCRIBED_INFLATED_OBSTACLE), 54u); // Add an obstacle at <1, 9>. This will inflate obstacles around it addObservation(olayer, 1, 9); @@ -454,8 +454,8 @@ TEST_F(TestNode, testInflation3) // There should be no occupied cells nav2_costmap_2d::Costmap2D * costmap = layers.getCostmap(); - ASSERT_EQ(countValues(*costmap, nav2_costmap_2d::LETHAL_OBSTACLE), (unsigned int)0); - ASSERT_EQ(countValues(*costmap, nav2_costmap_2d::INSCRIBED_INFLATED_OBSTACLE), (unsigned int)0); + ASSERT_EQ(countValues(*costmap, nav2_costmap_2d::LETHAL_OBSTACLE), 0u); + ASSERT_EQ(countValues(*costmap, nav2_costmap_2d::INSCRIBED_INFLATED_OBSTACLE), 0u); printMap(*costmap); // Add an obstacle at 5,5 addObservation(olayer, 5, 5, MAX_Z); @@ -463,14 +463,14 @@ TEST_F(TestNode, testInflation3) printMap(*costmap); // Test fails because updated cell value is 0 - ASSERT_EQ(countValues(*costmap, nav2_costmap_2d::FREE_SPACE, false), (unsigned int)29); - ASSERT_EQ(countValues(*costmap, nav2_costmap_2d::LETHAL_OBSTACLE), (unsigned int)1); - ASSERT_EQ(countValues(*costmap, nav2_costmap_2d::INSCRIBED_INFLATED_OBSTACLE), (unsigned int)4); + ASSERT_EQ(countValues(*costmap, nav2_costmap_2d::FREE_SPACE, false), 29u); + ASSERT_EQ(countValues(*costmap, nav2_costmap_2d::LETHAL_OBSTACLE), 1u); + ASSERT_EQ(countValues(*costmap, nav2_costmap_2d::INSCRIBED_INFLATED_OBSTACLE), 4u); // Update again - should see no change layers.updateMap(0, 0, 0); - ASSERT_EQ(countValues(*costmap, nav2_costmap_2d::FREE_SPACE, false), (unsigned int)29); - ASSERT_EQ(countValues(*costmap, nav2_costmap_2d::LETHAL_OBSTACLE), (unsigned int)1); - ASSERT_EQ(countValues(*costmap, nav2_costmap_2d::INSCRIBED_INFLATED_OBSTACLE), (unsigned int)4); + ASSERT_EQ(countValues(*costmap, nav2_costmap_2d::FREE_SPACE, false), 29u); + ASSERT_EQ(countValues(*costmap, nav2_costmap_2d::LETHAL_OBSTACLE), 1u); + ASSERT_EQ(countValues(*costmap, nav2_costmap_2d::INSCRIBED_INFLATED_OBSTACLE), 4u); } diff --git a/nav2_costmap_2d/test/unit/array_parser_test.cpp b/nav2_costmap_2d/test/unit/array_parser_test.cpp index e872dcc7..3706f0cb 100644 --- a/nav2_costmap_2d/test/unit/array_parser_test.cpp +++ b/nav2_costmap_2d/test/unit/array_parser_test.cpp @@ -38,9 +38,9 @@ TEST(array_parser, basic_operation) std::string error; std::vector<std::vector<float>> vvf; vvf = nav2_costmap_2d::parseVVF("[[1, 2.2], [.3, -4e4]]", error); - EXPECT_EQ((unsigned int)2, vvf.size() ); - EXPECT_EQ((unsigned int)2, vvf[0].size() ); - EXPECT_EQ((unsigned int)2, vvf[1].size() ); + EXPECT_EQ(2u, vvf.size() ); + EXPECT_EQ(2u, vvf[0].size() ); + EXPECT_EQ(2u, vvf[1].size() ); EXPECT_EQ(1.0f, vvf[0][0]); EXPECT_EQ(2.2f, vvf[0][1]); EXPECT_EQ(0.3f, vvf[1][0]); -- GitLab