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 deprecated rolling API #2558

Merged
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 realsense2_camera/CMakeLists.txt
Original file line number Diff line number Diff line change
Expand Up @@ -156,7 +156,7 @@ elseif("$ENV{ROS_DISTRO}" STREQUAL "humble")
elseif("$ENV{ROS_DISTRO}" STREQUAL "rolling")
message(STATUS "Build for ROS2 Rolling")
set(CMAKE_CXX_FLAGS "${CMAKE_CXX_FLAGS} -DROLLING")
set(SOURCES "${SOURCES}" src/ros_param_backend_foxy.cpp)
set(SOURCES "${SOURCES}" src/ros_param_backend_rolling.cpp)
else()
message(FATAL_ERROR "Unsupported ROS Distribution: " "$ENV{ROS_DISTRO}")
endif()
Expand Down
6 changes: 6 additions & 0 deletions realsense2_camera/include/base_realsense_node.h
Original file line number Diff line number Diff line change
Expand Up @@ -6,7 +6,13 @@
#include <librealsense2/rs.hpp>
#include <librealsense2/rsutil.h>
#include "constants.h"

// cv_bridge.h last supported version is humble
#if defined(ROLLING)
#include <cv_bridge/cv_bridge.hpp>
#else
#include <cv_bridge/cv_bridge.h>
#endif

#include <diagnostic_updater/diagnostic_updater.hpp>
#include <diagnostic_updater/publisher.hpp>
Expand Down
10 changes: 9 additions & 1 deletion realsense2_camera/include/ros_param_backend.h
Original file line number Diff line number Diff line change
Expand Up @@ -15,7 +15,15 @@ namespace realsense2_camera
_logger(node.get_logger())
{};
~ParametersBackend();
void add_on_set_parameters_callback(rclcpp::node_interfaces::NodeParametersInterface::OnParametersSetCallbackType callback);


#if defined( ROLLING )
using ros2_param_callback_type = rclcpp::node_interfaces::NodeParametersInterface::OnSetParametersCallbackType;
#else
using ros2_param_callback_type = rclcpp::node_interfaces::NodeParametersInterface::OnParametersSetCallbackType;
#endif

void add_on_set_parameters_callback(ros2_param_callback_type callback);


private:
Expand Down
2 changes: 1 addition & 1 deletion realsense2_camera/src/ros_param_backend_dashing.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -5,7 +5,7 @@

namespace realsense2_camera
{
void ParametersBackend::add_on_set_parameters_callback(rclcpp::node_interfaces::NodeParametersInterface::OnParametersSetCallbackType callback)
void ParametersBackend::add_on_set_parameters_callback(ros2_param_callback_type callback)
{
rclcpp::Node::OnParametersSetCallbackType prev_callback = _node.set_on_parameters_set_callback(callback);
if (prev_callback)
Expand Down
2 changes: 1 addition & 1 deletion realsense2_camera/src/ros_param_backend_foxy.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -5,7 +5,7 @@

namespace realsense2_camera
{
void ParametersBackend::add_on_set_parameters_callback(rclcpp::node_interfaces::NodeParametersInterface::OnParametersSetCallbackType callback)
void ParametersBackend::add_on_set_parameters_callback(ros2_param_callback_type callback)
{
_ros_callback = _node.add_on_set_parameters_callback(callback);
}
Expand Down
21 changes: 21 additions & 0 deletions realsense2_camera/src/ros_param_backend_rolling.cpp
Original file line number Diff line number Diff line change
@@ -0,0 +1,21 @@
// License: Apache 2.0. See LICENSE file in root directory.
// Copyright(c) 2022 Intel Corporation. All Rights Reserved.

#include "ros_param_backend.h"

namespace realsense2_camera
{
void ParametersBackend::add_on_set_parameters_callback(ros2_param_callback_type callback)
{
_ros_callback = _node.add_on_set_parameters_callback(callback);
}

ParametersBackend::~ParametersBackend()
{
if (_ros_callback)
{
_node.remove_on_set_parameters_callback((rclcpp::node_interfaces::OnSetParametersCallbackHandle*)(_ros_callback.get()));
_ros_callback.reset();
}
}
}