From e04dc4307b3cee57cba5ec3bb1c05c5c865bec04 Mon Sep 17 00:00:00 2001 From: Anton Kesy Date: Sat, 21 Oct 2023 17:06:09 +0200 Subject: [PATCH] fix minor typos Signed-off-by: Anton Kesy --- .../nav2_behavior_tree/bt_action_node.hpp | 2 +- .../src/collision_monitor_node.cpp | 2 +- nav2_costmap_2d/test/module_tests.cpp | 4 ++-- .../test/unit/binary_filter_test.cpp | 18 +++++++++--------- .../test/unit/keepout_filter_test.cpp | 14 +++++++------- .../test/unit/speed_filter_test.cpp | 18 +++++++++--------- nav2_mppi_controller/test/utils_test.cpp | 2 +- .../nav2_smac_planner/thirdparty/robin_hood.h | 4 ++-- .../behaviors/spin/spin_behavior_tester.cpp | 4 ++-- .../include/nav2_voxel_grid/voxel_grid.hpp | 6 +++--- .../plugins/photo_at_waypoint.hpp | 2 +- 11 files changed, 38 insertions(+), 38 deletions(-) diff --git a/nav2_behavior_tree/include/nav2_behavior_tree/bt_action_node.hpp b/nav2_behavior_tree/include/nav2_behavior_tree/bt_action_node.hpp index 5e316835ae..e6eef2992f 100644 --- a/nav2_behavior_tree/include/nav2_behavior_tree/bt_action_node.hpp +++ b/nav2_behavior_tree/include/nav2_behavior_tree/bt_action_node.hpp @@ -268,7 +268,7 @@ class BtActionNode : public BT::ActionNodeBase // Action related failure that should not fail the tree, but the node return BT::NodeStatus::FAILURE; } else { - // Internal exception to propogate to the tree + // Internal exception to propagate to the tree throw e; } } diff --git a/nav2_collision_monitor/src/collision_monitor_node.cpp b/nav2_collision_monitor/src/collision_monitor_node.cpp index a1395a7b70..f816118625 100644 --- a/nav2_collision_monitor/src/collision_monitor_node.cpp +++ b/nav2_collision_monitor/src/collision_monitor_node.cpp @@ -414,7 +414,7 @@ void CollisionMonitor::process(const Velocity & cmd_vel_in) notifyActionState(robot_action, action_polygon); } - // Publish requred robot velocity + // Publish required robot velocity publishVelocity(robot_action); // Publish polygons for better visualization diff --git a/nav2_costmap_2d/test/module_tests.cpp b/nav2_costmap_2d/test/module_tests.cpp index 989d81fe72..7a5fe811e4 100644 --- a/nav2_costmap_2d/test/module_tests.cpp +++ b/nav2_costmap_2d/test/module_tests.cpp @@ -1123,7 +1123,7 @@ TEST(costmap, testTrickyPropagation) { // Add a dynamic obstacle pcl::PointCloud c2; c2.points.resize(3); - // Dynamic obstacle that raytaces. + // Dynamic obstacle that raytraces. c2.points[0].x = 7.0; c2.points[0].y = 8.0; c2.points[0].z = 1.0; @@ -1167,7 +1167,7 @@ TEST(costmap, testTrickyPropagation) { pcl::PointCloud c; c.points.resize(1); - // Dynamic obstacle that raytaces the one at (3.0, 4.0). + // Dynamic obstacle that raytraces the one at (3.0, 4.0). c.points[0].x = 4.0; c.points[0].y = 5.0; c.points[0].z = 1.0; diff --git a/nav2_costmap_2d/test/unit/binary_filter_test.cpp b/nav2_costmap_2d/test/unit/binary_filter_test.cpp index 31bdfc025b..fa7fed4e10 100644 --- a/nav2_costmap_2d/test/unit/binary_filter_test.cpp +++ b/nav2_costmap_2d/test/unit/binary_filter_test.cpp @@ -703,7 +703,7 @@ void TestNode::reset() TEST_F(TestNode, testBinaryState) { - // Initilize test system + // Initialize test system createMaps("map"); publishMaps(nav2_costmap_2d::BINARY_FILTER, MASK_TOPIC, 0.0, 1.0); ASSERT_TRUE(createBinaryFilter("map", 10.0)); @@ -718,7 +718,7 @@ TEST_F(TestNode, testBinaryState) TEST_F(TestNode, testBinaryStateScaled) { - // Initilize test system + // Initialize test system createMaps("map"); publishMaps(nav2_costmap_2d::BINARY_FILTER, MASK_TOPIC, 100.0, -1.0); ASSERT_TRUE(createBinaryFilter("map", 35.0)); @@ -733,7 +733,7 @@ TEST_F(TestNode, testBinaryStateScaled) TEST_F(TestNode, testInvertedBinaryState) { - // Initilize test system + // Initialize test system createMaps("map"); publishMaps(nav2_costmap_2d::BINARY_FILTER, MASK_TOPIC, 0.0, 1.0); setDefaultState(true); @@ -749,7 +749,7 @@ TEST_F(TestNode, testInvertedBinaryState) TEST_F(TestNode, testOutOfBounds) { - // Initilize test system + // Initialize test system createMaps("map"); publishMaps(nav2_costmap_2d::BINARY_FILTER, MASK_TOPIC, 0.0, 1.0); ASSERT_TRUE(createBinaryFilter("map", 10.0)); @@ -764,7 +764,7 @@ TEST_F(TestNode, testOutOfBounds) TEST_F(TestNode, testInfoRePublish) { - // Initilize test system + // Initialize test system createMaps("map"); // Publish Info with incorrect dummy mask topic publishMaps(nav2_costmap_2d::BINARY_FILTER, "dummy_topic", 0.0, 1.0); @@ -805,7 +805,7 @@ TEST_F(TestNode, testMaskRePublish) TEST_F(TestNode, testIncorrectFilterType) { - // Initilize test system + // Initialize test system createMaps("map"); publishMaps(INCORRECT_TYPE, MASK_TOPIC, 0.0, 1.0); ASSERT_FALSE(createBinaryFilter("map", 10.0)); @@ -817,7 +817,7 @@ TEST_F(TestNode, testIncorrectFilterType) TEST_F(TestNode, testDifferentFrame) { - // Initilize test system + // Initialize test system createMaps("map"); publishMaps(nav2_costmap_2d::BINARY_FILTER, MASK_TOPIC, 0.0, 1.0); ASSERT_TRUE(createBinaryFilter("odom", 10.0)); @@ -833,7 +833,7 @@ TEST_F(TestNode, testDifferentFrame) TEST_F(TestNode, testIncorrectFrame) { - // Initilize test system + // Initialize test system createMaps("map"); publishMaps(nav2_costmap_2d::BINARY_FILTER, MASK_TOPIC, 0.0, 1.0); ASSERT_TRUE(createBinaryFilter("odom", 10.0)); @@ -849,7 +849,7 @@ TEST_F(TestNode, testIncorrectFrame) TEST_F(TestNode, testResetState) { - // Initilize test system + // Initialize test system createMaps("map"); publishMaps(nav2_costmap_2d::BINARY_FILTER, MASK_TOPIC, 0.0, 1.0); ASSERT_TRUE(createBinaryFilter("map", 10.0)); diff --git a/nav2_costmap_2d/test/unit/keepout_filter_test.cpp b/nav2_costmap_2d/test/unit/keepout_filter_test.cpp index 304b423f5c..3f236dd4d4 100644 --- a/nav2_costmap_2d/test/unit/keepout_filter_test.cpp +++ b/nav2_costmap_2d/test/unit/keepout_filter_test.cpp @@ -341,7 +341,7 @@ void TestNode::reset() TEST_F(TestNode, testFreeMasterLethalKeepout) { - // Initilize test system + // Initialize test system createMaps(nav2_costmap_2d::FREE_SPACE, nav2_util::OCC_GRID_OCCUPIED, "map"); publishMaps(); createKeepoutFilter("map"); @@ -356,7 +356,7 @@ TEST_F(TestNode, testFreeMasterLethalKeepout) TEST_F(TestNode, testUnknownMasterNonLethalKeepout) { - // Initilize test system + // Initialize test system createMaps( nav2_costmap_2d::NO_INFORMATION, (nav2_util::OCC_GRID_OCCUPIED - nav2_util::OCC_GRID_FREE) / 2, @@ -376,7 +376,7 @@ TEST_F(TestNode, testUnknownMasterNonLethalKeepout) TEST_F(TestNode, testFreeKeepout) { - // Initilize test system + // Initialize test system createMaps(nav2_costmap_2d::FREE_SPACE, nav2_util::OCC_GRID_FREE, "map"); publishMaps(); createKeepoutFilter("map"); @@ -395,7 +395,7 @@ TEST_F(TestNode, testFreeKeepout) TEST_F(TestNode, testUnknownKeepout) { - // Initilize test system + // Initialize test system createMaps(nav2_costmap_2d::FREE_SPACE, nav2_util::OCC_GRID_UNKNOWN, "map"); publishMaps(); createKeepoutFilter("map"); @@ -414,7 +414,7 @@ TEST_F(TestNode, testUnknownKeepout) TEST_F(TestNode, testInfoRePublish) { - // Initilize test system + // Initialize test system createMaps(nav2_costmap_2d::FREE_SPACE, nav2_util::OCC_GRID_OCCUPIED, "map"); publishMaps(); createKeepoutFilter("map"); @@ -433,7 +433,7 @@ TEST_F(TestNode, testInfoRePublish) TEST_F(TestNode, testMaskRePublish) { - // Initilize test system + // Initialize test system createMaps(nav2_costmap_2d::FREE_SPACE, nav2_util::OCC_GRID_OCCUPIED, "map"); publishMaps(); createKeepoutFilter("map"); @@ -451,7 +451,7 @@ TEST_F(TestNode, testMaskRePublish) TEST_F(TestNode, testDifferentFrames) { - // Initilize test system + // Initialize test system createMaps(nav2_costmap_2d::FREE_SPACE, nav2_util::OCC_GRID_OCCUPIED, "map"); publishMaps(); createKeepoutFilter("odom"); diff --git a/nav2_costmap_2d/test/unit/speed_filter_test.cpp b/nav2_costmap_2d/test/unit/speed_filter_test.cpp index d419cade36..2e1d2b4e8c 100644 --- a/nav2_costmap_2d/test/unit/speed_filter_test.cpp +++ b/nav2_costmap_2d/test/unit/speed_filter_test.cpp @@ -633,7 +633,7 @@ void TestNode::reset() TEST_F(TestNode, testPercentSpeedLimit) { - // Initilize test system + // Initialize test system createMaps("map"); publishMaps(nav2_costmap_2d::SPEED_FILTER_PERCENT, 0.0, 1.0); EXPECT_TRUE(createSpeedFilter("map")); @@ -648,7 +648,7 @@ TEST_F(TestNode, testPercentSpeedLimit) TEST_F(TestNode, testIncorrectPercentSpeedLimit) { - // Initilize test system + // Initialize test system createMaps("map"); publishMaps(nav2_costmap_2d::SPEED_FILTER_PERCENT, -50.0, 2.0); EXPECT_TRUE(createSpeedFilter("map")); @@ -663,7 +663,7 @@ TEST_F(TestNode, testIncorrectPercentSpeedLimit) TEST_F(TestNode, testAbsoluteSpeedLimit) { - // Initilize test system + // Initialize test system createMaps("map"); publishMaps(nav2_costmap_2d::SPEED_FILTER_ABSOLUTE, 1.23, 4.5); EXPECT_TRUE(createSpeedFilter("map")); @@ -678,7 +678,7 @@ TEST_F(TestNode, testAbsoluteSpeedLimit) TEST_F(TestNode, testIncorrectAbsoluteSpeedLimit) { - // Initilize test system + // Initialize test system createMaps("map"); publishMaps(nav2_costmap_2d::SPEED_FILTER_ABSOLUTE, -50.0, 2.0); EXPECT_TRUE(createSpeedFilter("map")); @@ -693,7 +693,7 @@ TEST_F(TestNode, testIncorrectAbsoluteSpeedLimit) TEST_F(TestNode, testOutOfBounds) { - // Initilize test system + // Initialize test system createMaps("map"); publishMaps(nav2_costmap_2d::SPEED_FILTER_PERCENT, 0.0, 1.0); EXPECT_TRUE(createSpeedFilter("map")); @@ -708,7 +708,7 @@ TEST_F(TestNode, testOutOfBounds) TEST_F(TestNode, testInfoRePublish) { - // Initilize test system + // Initialize test system createMaps("map"); publishMaps(nav2_costmap_2d::SPEED_FILTER_ABSOLUTE, 1.23, 4.5); EXPECT_TRUE(createSpeedFilter("map")); @@ -728,7 +728,7 @@ TEST_F(TestNode, testInfoRePublish) TEST_F(TestNode, testMaskRePublish) { - // Initilize test system + // Initialize test system createMaps("map"); publishMaps(nav2_costmap_2d::SPEED_FILTER_ABSOLUTE, 1.23, 4.5); EXPECT_TRUE(createSpeedFilter("map")); @@ -747,7 +747,7 @@ TEST_F(TestNode, testMaskRePublish) TEST_F(TestNode, testIncorrectFilterType) { - // Initilize test system + // Initialize test system createMaps("map"); publishMaps(INCORRECT_TYPE, 1.23, 4.5); EXPECT_FALSE(createSpeedFilter("map")); @@ -759,7 +759,7 @@ TEST_F(TestNode, testIncorrectFilterType) TEST_F(TestNode, testDifferentFrame) { - // Initilize test system + // Initialize test system createMaps("map"); publishMaps(nav2_costmap_2d::SPEED_FILTER_PERCENT, 0.0, 1.0); EXPECT_TRUE(createSpeedFilter("odom")); diff --git a/nav2_mppi_controller/test/utils_test.cpp b/nav2_mppi_controller/test/utils_test.cpp index 89f6d0d667..edeb804b83 100644 --- a/nav2_mppi_controller/test/utils_test.cpp +++ b/nav2_mppi_controller/test/utils_test.cpp @@ -329,7 +329,7 @@ TEST(UtilsTests, SmootherTest) noisey_sequence.vy = 0.0 * xt::ones({30}); noisey_sequence.wz = 0.3 * xt::ones({30}); - // Make the sequence noisey + // Make the sequence noisy auto noises = xt::random::randn({30}, 0.0, 0.2); noisey_sequence.vx += noises; noisey_sequence.vy += noises; diff --git a/nav2_smac_planner/include/nav2_smac_planner/thirdparty/robin_hood.h b/nav2_smac_planner/include/nav2_smac_planner/thirdparty/robin_hood.h index 5d3812a3a3..4d3977937b 100644 --- a/nav2_smac_planner/include/nav2_smac_planner/thirdparty/robin_hood.h +++ b/nav2_smac_planner/include/nav2_smac_planner/thirdparty/robin_hood.h @@ -111,7 +111,7 @@ static Counts& counts() { # error Unsupported bitness #endif -// endianess +// endianness #ifdef _MSC_VER # define ROBIN_HOOD_PRIVATE_DEFINITION_LITTLE_ENDIAN() 1 # define ROBIN_HOOD_PRIVATE_DEFINITION_BIG_ENDIAN() 0 @@ -2132,7 +2132,7 @@ class Table return maxElements * MaxLoadFactor100 / 100; } - // we might be a bit inprecise, but since maxElements is quite large that doesn't matter + // we might be a bit imprecise, but since maxElements is quite large that doesn't matter return (maxElements / 100) * MaxLoadFactor100; } diff --git a/nav2_system_tests/src/behaviors/spin/spin_behavior_tester.cpp b/nav2_system_tests/src/behaviors/spin/spin_behavior_tester.cpp index 27b1f5e800..706767b9ce 100644 --- a/nav2_system_tests/src/behaviors/spin/spin_behavior_tester.cpp +++ b/nav2_system_tests/src/behaviors/spin/spin_behavior_tester.cpp @@ -142,7 +142,7 @@ bool SpinBehaviorTester::defaultSpinBehaviorTest( auto goal_msg = Spin::Goal(); goal_msg.target_yaw = target_yaw; - // Intialize fake costmap + // Initialize fake costmap if (make_fake_costmap_) { sendFakeCostmap(target_yaw); sendFakeOdom(0.0); @@ -160,7 +160,7 @@ bool SpinBehaviorTester::defaultSpinBehaviorTest( fabs(tf2::getYaw(initial_pose.pose.orientation))); RCLCPP_INFO(node_->get_logger(), "Before sending goal"); - // Intialize fake costmap + // Initialize fake costmap if (make_fake_costmap_) { sendFakeCostmap(target_yaw); sendFakeOdom(0.0); diff --git a/nav2_voxel_grid/include/nav2_voxel_grid/voxel_grid.hpp b/nav2_voxel_grid/include/nav2_voxel_grid/voxel_grid.hpp index baff10d684..07c391fff5 100644 --- a/nav2_voxel_grid/include/nav2_voxel_grid/voxel_grid.hpp +++ b/nav2_voxel_grid/include/nav2_voxel_grid/voxel_grid.hpp @@ -112,7 +112,7 @@ class VoxelGrid unsigned int marked_bits = *col >> 16; - // make sure the number of bits in each is below our thesholds + // make sure the number of bits in each is below our thresholds return !bitsBelowThreshold(marked_bits, marked_threshold); } @@ -146,7 +146,7 @@ class VoxelGrid unsigned int unknown_bits = uint16_t(*col >> 16) ^ uint16_t(*col); unsigned int marked_bits = *col >> 16; - // make sure the number of bits in each is below our thesholds + // make sure the number of bits in each is below our thresholds if (bitsBelowThreshold(unknown_bits, 1) && bitsBelowThreshold(marked_bits, 1)) { costmap[index] = 0; } @@ -392,7 +392,7 @@ class VoxelGrid unsigned int unknown_bits = uint16_t(*col >> 16) ^ uint16_t(*col); unsigned int marked_bits = *col >> 16; - // make sure the number of bits in each is below our thesholds + // make sure the number of bits in each is below our thresholds if (bitsBelowThreshold(marked_bits, marked_clear_threshold_)) { if (bitsBelowThreshold(unknown_bits, unknown_clear_threshold_)) { costmap_[offset] = free_cost_; diff --git a/nav2_waypoint_follower/include/nav2_waypoint_follower/plugins/photo_at_waypoint.hpp b/nav2_waypoint_follower/include/nav2_waypoint_follower/plugins/photo_at_waypoint.hpp index 7c56b85e33..9c46fdf1f8 100644 --- a/nav2_waypoint_follower/include/nav2_waypoint_follower/plugins/photo_at_waypoint.hpp +++ b/nav2_waypoint_follower/include/nav2_waypoint_follower/plugins/photo_at_waypoint.hpp @@ -108,7 +108,7 @@ class PhotoAtWaypoint : public nav2_core::WaypointTaskExecutor sensor_msgs::msg::Image::SharedPtr curr_frame_msg_; // global logger rclcpp::Logger logger_{rclcpp::get_logger("nav2_waypoint_follower")}; - // ros susbcriber to get camera image + // ros subscriber to get camera image rclcpp::Subscription::SharedPtr camera_image_subscriber_; }; } // namespace nav2_waypoint_follower