From bdf1c6f2967cb8f9d768049f652dc89bd7856ebe Mon Sep 17 00:00:00 2001 From: Sergio Portoles Diez Date: Wed, 6 Sep 2023 16:54:22 +0200 Subject: [PATCH] fix api differences on executors in ROS2 humble This patch fixes some changes on deprecated API rclcpp::executor by the workspace rclcpp::Executor and the options passed to the executor. --- rtt_ros2_node/include/orocos/rtt_ros2_node/rtt_ros2_node.hpp | 4 ++-- rtt_ros2_node/src/rtt_ros2_node.cpp | 2 +- rtt_ros2_node/src/rtt_ros2_node_service.cpp | 2 +- 3 files changed, 4 insertions(+), 4 deletions(-) diff --git a/rtt_ros2_node/include/orocos/rtt_ros2_node/rtt_ros2_node.hpp b/rtt_ros2_node/include/orocos/rtt_ros2_node/rtt_ros2_node.hpp index 1213dc1..fb67a08 100644 --- a/rtt_ros2_node/include/orocos/rtt_ros2_node/rtt_ros2_node.hpp +++ b/rtt_ros2_node/include/orocos/rtt_ros2_node/rtt_ros2_node.hpp @@ -51,14 +51,14 @@ struct Node : public RTT::Service virtual ~Node(); rclcpp::Node::SharedPtr node() {return node_;} - rclcpp::executor::Executor::SharedPtr executor() {return executor_;} + rclcpp::Executor::Executor::SharedPtr executor() {return executor_;} void spin(unsigned int number_of_threads = 1); void cancel(); protected: rclcpp::Node::SharedPtr node_; - rclcpp::executor::Executor::SharedPtr executor_; + rclcpp::Executor::Executor::SharedPtr executor_; std::thread thread_; }; diff --git a/rtt_ros2_node/src/rtt_ros2_node.cpp b/rtt_ros2_node/src/rtt_ros2_node.cpp index 0cd0121..b524808 100644 --- a/rtt_ros2_node/src/rtt_ros2_node.cpp +++ b/rtt_ros2_node/src/rtt_ros2_node.cpp @@ -104,7 +104,7 @@ void Node::spin(unsigned int number_of_threads) { cancel(); const auto executor = std::make_shared( - rclcpp::executor::ExecutorArgs(), + rclcpp::ExecutorOptions(), number_of_threads ); executor->add_node(node_); diff --git a/rtt_ros2_node/src/rtt_ros2_node_service.cpp b/rtt_ros2_node/src/rtt_ros2_node_service.cpp index 0f24ecf..21181e0 100644 --- a/rtt_ros2_node/src/rtt_ros2_node_service.cpp +++ b/rtt_ros2_node/src/rtt_ros2_node_service.cpp @@ -74,7 +74,7 @@ static void loadGlobalROSService() // Call rclcpp::init() rclcpp::InitOptions init_options; - init_options.shutdown_on_sigint = false; + init_options.shutdown_on_signal = false; RTT::log(RTT::Info) << "Initializing ROS context with " << __os_main_argc() << " command-line arguments." << RTT::endlog();