Skip to content

Commit

Permalink
Fix Rolling builds (#439)
Browse files Browse the repository at this point in the history
### Proposed changes

Precisely what the title says. This patch:

- copes with `message_filters` header deprecations
- copes with `rclcpp::Node::create_service` API removals

#### Type of change

- [x] 🐛 Bugfix (change which fixes an issue)
- [ ] 🚀 Feature (change which adds functionality)
- [ ] 📚 Documentation (change which fixes or extends documentation)

### Checklist

- [x] Lint and unit tests (if any) pass locally with my changes
- [x] I have added tests that prove my fix is effective or that my
feature works
- [x] I have added necessary documentation (if appropriate)
- [x] All commits have been signed for
[DCO](https://developercertificate.org/)

Signed-off-by: Michel Hidalgo <michel@ekumenlabs.com>
  • Loading branch information
hidmic authored Sep 30, 2024
1 parent cfd6af2 commit 5c0a780
Show file tree
Hide file tree
Showing 6 changed files with 46 additions and 23 deletions.
4 changes: 4 additions & 0 deletions beluga_amcl/include/beluga_amcl/amcl_node.hpp
Original file line number Diff line number Diff line change
Expand Up @@ -19,7 +19,11 @@
#include <optional>
#include <utility>

#pragma GCC diagnostic push
#pragma GCC diagnostic ignored "-Wcpp"
#include <message_filters/subscriber.h>
#pragma GCC diagnostic pop

#include <tf2_ros/buffer.h>
#include <tf2_ros/message_filter.h>
#include <tf2_ros/transform_broadcaster.h>
Expand Down
3 changes: 3 additions & 0 deletions beluga_amcl/include/beluga_amcl/ndt_amcl_node.hpp
Original file line number Diff line number Diff line change
Expand Up @@ -52,7 +52,10 @@
#include <beluga_ros/laser_scan.hpp>
#include "beluga_amcl/ros2_common.hpp"

#pragma GCC diagnostic push
#pragma GCC diagnostic ignored "-Wcpp"
#include <message_filters/subscriber.h>
#pragma GCC diagnostic pop

/**
* \file
Expand Down
3 changes: 3 additions & 0 deletions beluga_amcl/include/beluga_amcl/ndt_amcl_node_3d.hpp
Original file line number Diff line number Diff line change
Expand Up @@ -40,7 +40,10 @@
#include <beluga_ros/laser_scan.hpp>
#include "beluga_amcl/ros2_common.hpp"

#pragma GCC diagnostic push
#pragma GCC diagnostic ignored "-Wcpp"
#include <message_filters/subscriber.h>
#pragma GCC diagnostic pop

/**
* \file
Expand Down
51 changes: 28 additions & 23 deletions beluga_amcl/src/amcl_node.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -40,7 +40,12 @@
#include <Eigen/Core>
#include <sophus/se2.hpp>

#pragma GCC diagnostic push
#pragma GCC diagnostic ignored "-Wcpp"
#include <message_filters/subscriber.h>
#pragma GCC diagnostic pop

#include <rclcpp/version.h>
#include <bondcpp/bond.hpp>
#include <rclcpp/rclcpp.hpp>
#include <rclcpp_lifecycle/lifecycle_node.hpp>
Expand Down Expand Up @@ -201,29 +206,29 @@ void AmclNode::do_activate(const rclcpp_lifecycle::State&) {
RCLCPP_INFO(get_logger(), "Subscribed to scan_topic: %s", laser_scan_sub_->getTopic().c_str());
}

{
#pragma GCC diagnostic push
#pragma GCC diagnostic ignored "-Wdeprecated-declarations"
// Ignore deprecated declaration warning to support Humble.
// Message: use rclcpp::QoS instead of rmw_qos_profile_t
global_localization_server_ = create_service<std_srvs::srv::Empty>(
"reinitialize_global_localization",
std::bind(
&AmclNode::global_localization_callback, this, std::placeholders::_1, std::placeholders::_2,
std::placeholders::_3),
rmw_qos_profile_services_default, common_callback_group_);
RCLCPP_INFO(get_logger(), "Created reinitialize_global_localization service");

nomotion_update_server_ = create_service<std_srvs::srv::Empty>(
"request_nomotion_update",
std::bind(
&AmclNode::nomotion_update_callback, this, std::placeholders::_1, std::placeholders::_2,
std::placeholders::_3),
rmw_qos_profile_services_default, common_callback_group_);
RCLCPP_INFO(get_logger(), "Created request_nomotion_update service");

#pragma GCC diagnostic pop
}
const auto common_service_qos = [] {
if constexpr (RCLCPP_VERSION_GTE(17, 0, 0)) {
return rclcpp::ServicesQoS();
} else {
return rmw_qos_profile_services_default;
}
}();

global_localization_server_ = create_service<std_srvs::srv::Empty>(
"reinitialize_global_localization",
std::bind(
&AmclNode::global_localization_callback, this, std::placeholders::_1, std::placeholders::_2,
std::placeholders::_3),
common_service_qos, common_callback_group_);
RCLCPP_INFO(get_logger(), "Created reinitialize_global_localization service");

nomotion_update_server_ = create_service<std_srvs::srv::Empty>(
"request_nomotion_update",
std::bind(
&AmclNode::nomotion_update_callback, this, std::placeholders::_1, std::placeholders::_2,
std::placeholders::_3),
common_service_qos, common_callback_group_);
RCLCPP_INFO(get_logger(), "Created request_nomotion_update service");
}

void AmclNode::do_deactivate(const rclcpp_lifecycle::State&) {
Expand Down
4 changes: 4 additions & 0 deletions beluga_amcl/src/ndt_amcl_node.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -43,7 +43,11 @@
#include <tf2_ros/transform_broadcaster.h>
#include <tf2_ros/transform_listener.h>

#pragma GCC diagnostic push
#pragma GCC diagnostic ignored "-Wcpp"
#include <message_filters/subscriber.h>
#pragma GCC diagnostic pop

#include <bondcpp/bond.hpp>
#include <rclcpp/rclcpp.hpp>
#include <rclcpp_lifecycle/lifecycle_node.hpp>
Expand Down
4 changes: 4 additions & 0 deletions beluga_amcl/src/ndt_amcl_node_3d.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -49,7 +49,11 @@
#include <tf2_ros/transform_broadcaster.h>
#include <tf2_ros/transform_listener.h>

#pragma GCC diagnostic push
#pragma GCC diagnostic ignored "-Wcpp"
#include <message_filters/subscriber.h>
#pragma GCC diagnostic pop

#include <bondcpp/bond.hpp>
#include <rclcpp/rclcpp.hpp>
#include <rclcpp_lifecycle/lifecycle_node.hpp>
Expand Down

0 comments on commit 5c0a780

Please sign in to comment.