Skip to content

Commit da5edbf

Browse files
fixing merge conflicts for release on humble sync 6 (#3623)
1 parent 59e99ec commit da5edbf

File tree

5 files changed

+10
-7
lines changed

5 files changed

+10
-7
lines changed

nav2_behavior_tree/test/plugins/condition/test_is_battery_charging.cpp

Lines changed: 1 addition & 1 deletion
Original file line numberDiff line numberDiff line change
@@ -20,7 +20,7 @@
2020

2121
#include "sensor_msgs/msg/battery_state.hpp"
2222

23-
#include "utils/test_behavior_tree_fixture.hpp"
23+
#include "../../test_behavior_tree_fixture.hpp"
2424
#include "nav2_behavior_tree/plugins/condition/is_battery_charging_condition.hpp"
2525

2626
class IsBatteryChargingConditionTestFixture : public ::testing::Test

nav2_collision_monitor/include/nav2_collision_monitor/pointcloud.hpp

Lines changed: 1 addition & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -20,6 +20,7 @@
2020
#include <string>
2121

2222
#include "sensor_msgs/msg/point_cloud2.hpp"
23+
#include "nav2_util/robot_utils.hpp"
2324

2425
#include "nav2_collision_monitor/source.hpp"
2526

nav2_collision_monitor/include/nav2_collision_monitor/range.hpp

Lines changed: 1 addition & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -20,6 +20,7 @@
2020
#include <string>
2121

2222
#include "sensor_msgs/msg/range.hpp"
23+
#include "nav2_util/robot_utils.hpp"
2324

2425
#include "nav2_collision_monitor/source.hpp"
2526

nav2_collision_monitor/include/nav2_collision_monitor/scan.hpp

Lines changed: 1 addition & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -20,6 +20,7 @@
2020
#include <vector>
2121

2222
#include "sensor_msgs/msg/laser_scan.hpp"
23+
#include "nav2_util/robot_utils.hpp"
2324

2425
#include "nav2_collision_monitor/source.hpp"
2526

nav2_costmap_2d/test/unit/costmap_filter_test.cpp

Lines changed: 6 additions & 6 deletions
Original file line numberDiff line numberDiff line change
@@ -75,15 +75,15 @@ TEST(CostmapFilter, testWorldToMask)
7575
unsigned int mx, my;
7676
// Point inside mask
7777
ASSERT_TRUE(cf.worldToMask(mask, 4.0, 5.0, mx, my));
78-
ASSERT_EQ(mx, 1);
79-
ASSERT_EQ(my, 2);
78+
ASSERT_EQ(mx, 1u);
79+
ASSERT_EQ(my, 2u);
8080
// Corner cases
8181
ASSERT_TRUE(cf.worldToMask(mask, 3.0, 3.0, mx, my));
82-
ASSERT_EQ(mx, 0);
83-
ASSERT_EQ(my, 0);
82+
ASSERT_EQ(mx, 0u);
83+
ASSERT_EQ(my, 0u);
8484
ASSERT_TRUE(cf.worldToMask(mask, 5.9, 5.9, mx, my));
85-
ASSERT_EQ(mx, 2);
86-
ASSERT_EQ(my, 2);
85+
ASSERT_EQ(mx, 2u);
86+
ASSERT_EQ(my, 2u);
8787
// Point outside mask
8888
ASSERT_FALSE(cf.worldToMask(mask, 2.9, 2.9, mx, my));
8989
ASSERT_FALSE(cf.worldToMask(mask, 6.0, 6.0, mx, my));

0 commit comments

Comments
 (0)