diff --git a/nav2_behavior_tree/test/plugins/condition/test_is_battery_charging.cpp b/nav2_behavior_tree/test/plugins/condition/test_is_battery_charging.cpp index 46af6d5c6e0..89befdcc357 100644 --- a/nav2_behavior_tree/test/plugins/condition/test_is_battery_charging.cpp +++ b/nav2_behavior_tree/test/plugins/condition/test_is_battery_charging.cpp @@ -20,7 +20,7 @@ #include "sensor_msgs/msg/battery_state.hpp" -#include "utils/test_behavior_tree_fixture.hpp" +#include "../../test_behavior_tree_fixture.hpp" #include "nav2_behavior_tree/plugins/condition/is_battery_charging_condition.hpp" class IsBatteryChargingConditionTestFixture : public ::testing::Test diff --git a/nav2_collision_monitor/include/nav2_collision_monitor/pointcloud.hpp b/nav2_collision_monitor/include/nav2_collision_monitor/pointcloud.hpp index d5af32c2772..8e1d1caf43a 100644 --- a/nav2_collision_monitor/include/nav2_collision_monitor/pointcloud.hpp +++ b/nav2_collision_monitor/include/nav2_collision_monitor/pointcloud.hpp @@ -20,6 +20,7 @@ #include #include "sensor_msgs/msg/point_cloud2.hpp" +#include "nav2_util/robot_utils.hpp" #include "nav2_collision_monitor/source.hpp" diff --git a/nav2_collision_monitor/include/nav2_collision_monitor/range.hpp b/nav2_collision_monitor/include/nav2_collision_monitor/range.hpp index 777b8e404ce..1deb80a448b 100644 --- a/nav2_collision_monitor/include/nav2_collision_monitor/range.hpp +++ b/nav2_collision_monitor/include/nav2_collision_monitor/range.hpp @@ -20,6 +20,7 @@ #include #include "sensor_msgs/msg/range.hpp" +#include "nav2_util/robot_utils.hpp" #include "nav2_collision_monitor/source.hpp" diff --git a/nav2_collision_monitor/include/nav2_collision_monitor/scan.hpp b/nav2_collision_monitor/include/nav2_collision_monitor/scan.hpp index c3f7a11f3fa..690a22564e5 100644 --- a/nav2_collision_monitor/include/nav2_collision_monitor/scan.hpp +++ b/nav2_collision_monitor/include/nav2_collision_monitor/scan.hpp @@ -20,6 +20,7 @@ #include #include "sensor_msgs/msg/laser_scan.hpp" +#include "nav2_util/robot_utils.hpp" #include "nav2_collision_monitor/source.hpp" diff --git a/nav2_costmap_2d/test/unit/costmap_filter_test.cpp b/nav2_costmap_2d/test/unit/costmap_filter_test.cpp index 6aaabe297a2..68037bfe8a9 100644 --- a/nav2_costmap_2d/test/unit/costmap_filter_test.cpp +++ b/nav2_costmap_2d/test/unit/costmap_filter_test.cpp @@ -75,15 +75,15 @@ TEST(CostmapFilter, testWorldToMask) unsigned int mx, my; // Point inside mask ASSERT_TRUE(cf.worldToMask(mask, 4.0, 5.0, mx, my)); - ASSERT_EQ(mx, 1); - ASSERT_EQ(my, 2); + ASSERT_EQ(mx, 1u); + ASSERT_EQ(my, 2u); // Corner cases ASSERT_TRUE(cf.worldToMask(mask, 3.0, 3.0, mx, my)); - ASSERT_EQ(mx, 0); - ASSERT_EQ(my, 0); + ASSERT_EQ(mx, 0u); + ASSERT_EQ(my, 0u); ASSERT_TRUE(cf.worldToMask(mask, 5.9, 5.9, mx, my)); - ASSERT_EQ(mx, 2); - ASSERT_EQ(my, 2); + ASSERT_EQ(mx, 2u); + ASSERT_EQ(my, 2u); // Point outside mask ASSERT_FALSE(cf.worldToMask(mask, 2.9, 2.9, mx, my)); ASSERT_FALSE(cf.worldToMask(mask, 6.0, 6.0, mx, my));