diff --git a/nav2_behavior_tree/include/nav2_behavior_tree/bt_utils.hpp b/nav2_behavior_tree/include/nav2_behavior_tree/bt_utils.hpp index 7e8ea23ec7..a3b42011f0 100644 --- a/nav2_behavior_tree/include/nav2_behavior_tree/bt_utils.hpp +++ b/nav2_behavior_tree/include/nav2_behavior_tree/bt_utils.hpp @@ -145,7 +145,7 @@ T1 deconflictPortAndParamFrame( const T2 * behavior_tree_node) { T1 param_value; - bool param_from_input = behavior_tree_node->getInput(param_name, param_value); + bool param_from_input = behavior_tree_node->getInput(param_name, param_value).has_value(); if constexpr (std::is_same_v) { // not valid if port doesn't exist or it is an empty string diff --git a/nav2_collision_monitor/test/velocity_polygons_test.cpp b/nav2_collision_monitor/test/velocity_polygons_test.cpp index 7030ddd2b2..4fd4f8bc0b 100644 --- a/nav2_collision_monitor/test/velocity_polygons_test.cpp +++ b/nav2_collision_monitor/test/velocity_polygons_test.cpp @@ -40,7 +40,6 @@ using namespace std::chrono_literals; static constexpr double EPSILON = std::numeric_limits::epsilon(); static const char BASE_FRAME_ID[]{"base_link"}; -static const char BASE2_FRAME_ID[]{"base2_link"}; static const char POLYGON_PUB_TOPIC[]{"polygon_pub"}; static const char POLYGON_NAME[]{"TestVelocityPolygon"}; static const char SUB_POLYGON_FORWARD_NAME[]{"Forward"}; diff --git a/nav2_costmap_2d/test/integration/test_costmap_subscriber.cpp b/nav2_costmap_2d/test/integration/test_costmap_subscriber.cpp index d674ee7669..849edf282c 100644 --- a/nav2_costmap_2d/test/integration/test_costmap_subscriber.cpp +++ b/nav2_costmap_2d/test/integration/test_costmap_subscriber.cpp @@ -53,7 +53,7 @@ class TestCostmapSubscriberShould : public ::testing::Test costmapToSend = std::make_shared(10, 10, 1.0, 0.0, 0.0); } - void TearDown() + void TearDown() override { costmapSubscriber.reset(); costmapToSend.reset(); diff --git a/nav2_rviz_plugins/src/selector.cpp b/nav2_rviz_plugins/src/selector.cpp index f0f3d4e335..1df075f82d 100644 --- a/nav2_rviz_plugins/src/selector.cpp +++ b/nav2_rviz_plugins/src/selector.cpp @@ -169,7 +169,7 @@ void Selector::pluginLoader( } RCLCPP_INFO( node->get_logger(), - (server_name + " service not available").c_str()); + "%s service not available", server_name.c_str()); server_unavailable = true; server_failed_ = true; break;