Skip to content

Commit d668743

Browse files
Raymanenricosutera
authored andcommitted
Fix compilation with clang (ros-navigation#4131)
Signed-off-by: Ramon Wijnands <ramon.wijnands@nobleo.nl> Signed-off-by: enricosutera <enricosutera@outlook.com>
1 parent ff261d0 commit d668743

File tree

4 files changed

+3
-4
lines changed

4 files changed

+3
-4
lines changed

nav2_behavior_tree/include/nav2_behavior_tree/bt_utils.hpp

Lines changed: 1 addition & 1 deletion
Original file line numberDiff line numberDiff line change
@@ -145,7 +145,7 @@ T1 deconflictPortAndParamFrame(
145145
const T2 * behavior_tree_node)
146146
{
147147
T1 param_value;
148-
bool param_from_input = behavior_tree_node->getInput(param_name, param_value);
148+
bool param_from_input = behavior_tree_node->getInput(param_name, param_value).has_value();
149149

150150
if constexpr (std::is_same_v<T1, std::string>) {
151151
// not valid if port doesn't exist or it is an empty string

nav2_collision_monitor/test/velocity_polygons_test.cpp

Lines changed: 0 additions & 1 deletion
Original file line numberDiff line numberDiff line change
@@ -40,7 +40,6 @@ using namespace std::chrono_literals;
4040
static constexpr double EPSILON = std::numeric_limits<float>::epsilon();
4141

4242
static const char BASE_FRAME_ID[]{"base_link"};
43-
static const char BASE2_FRAME_ID[]{"base2_link"};
4443
static const char POLYGON_PUB_TOPIC[]{"polygon_pub"};
4544
static const char POLYGON_NAME[]{"TestVelocityPolygon"};
4645
static const char SUB_POLYGON_FORWARD_NAME[]{"Forward"};

nav2_costmap_2d/test/integration/test_costmap_subscriber.cpp

Lines changed: 1 addition & 1 deletion
Original file line numberDiff line numberDiff line change
@@ -53,7 +53,7 @@ class TestCostmapSubscriberShould : public ::testing::Test
5353
costmapToSend = std::make_shared<nav2_costmap_2d::Costmap2D>(10, 10, 1.0, 0.0, 0.0);
5454
}
5555

56-
void TearDown()
56+
void TearDown() override
5757
{
5858
costmapSubscriber.reset();
5959
costmapToSend.reset();

nav2_rviz_plugins/src/selector.cpp

Lines changed: 1 addition & 1 deletion
Original file line numberDiff line numberDiff line change
@@ -169,7 +169,7 @@ void Selector::pluginLoader(
169169
}
170170
RCLCPP_INFO(
171171
node->get_logger(),
172-
(server_name + " service not available").c_str());
172+
"%s service not available", server_name.c_str());
173173
server_unavailable = true;
174174
server_failed_ = true;
175175
break;

0 commit comments

Comments
 (0)