Skip to content
New issue

Have a question about this project? Sign up for a free GitHub account to open an issue and contact its maintainers and the community.

By clicking “Sign up for GitHub”, you agree to our terms of service and privacy statement. We’ll occasionally send you account related emails.

Already on GitHub? Sign in to your account

Fix compilation with clang #4131

Merged
merged 1 commit into from
Feb 21, 2024
Merged
Show file tree
Hide file tree
Changes from all commits
Commits
File filter

Filter by extension

Filter by extension

Conversations
Failed to load comments.
Loading
Jump to
Jump to file
Failed to load files.
Loading
Diff view
Diff view
2 changes: 1 addition & 1 deletion nav2_behavior_tree/include/nav2_behavior_tree/bt_utils.hpp
Original file line number Diff line number Diff line change
Expand Up @@ -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<T1, std::string>) {
// not valid if port doesn't exist or it is an empty string
Expand Down
1 change: 0 additions & 1 deletion nav2_collision_monitor/test/velocity_polygons_test.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -40,7 +40,6 @@ using namespace std::chrono_literals;
static constexpr double EPSILON = std::numeric_limits<float>::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"};
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -53,7 +53,7 @@ class TestCostmapSubscriberShould : public ::testing::Test
costmapToSend = std::make_shared<nav2_costmap_2d::Costmap2D>(10, 10, 1.0, 0.0, 0.0);
}

void TearDown()
void TearDown() override
{
costmapSubscriber.reset();
costmapToSend.reset();
Expand Down
2 changes: 1 addition & 1 deletion nav2_rviz_plugins/src/selector.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -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;
Expand Down
Loading