From b4956be68ef214931d985cd4cd4452831d14a185 Mon Sep 17 00:00:00 2001 From: Michael Ferguson Date: Thu, 18 Jan 2024 11:27:49 -0500 Subject: [PATCH] load image_rotate::ImageRotateNode as component (#855) This is a fixed version of #820 - targeting rolling --- image_rotate/include/image_rotate/image_rotate_node.hpp | 2 +- image_rotate/src/image_rotate.cpp | 3 ++- image_rotate/src/image_rotate_node.cpp | 8 ++++---- 3 files changed, 7 insertions(+), 6 deletions(-) diff --git a/image_rotate/include/image_rotate/image_rotate_node.hpp b/image_rotate/include/image_rotate/image_rotate_node.hpp index 02d4503a9..8482a1c72 100644 --- a/image_rotate/include/image_rotate/image_rotate_node.hpp +++ b/image_rotate/include/image_rotate/image_rotate_node.hpp @@ -71,7 +71,7 @@ struct ImageRotateConfig class ImageRotateNode : public rclcpp::Node { public: - IMAGE_ROTATE_PUBLIC ImageRotateNode(); + IMAGE_ROTATE_PUBLIC ImageRotateNode(const rclcpp::NodeOptions & options); private: const std::string frameWithDefault(const std::string & frame, const std::string & image_frame); diff --git a/image_rotate/src/image_rotate.cpp b/image_rotate/src/image_rotate.cpp index f11a2e834..909d34ef8 100644 --- a/image_rotate/src/image_rotate.cpp +++ b/image_rotate/src/image_rotate.cpp @@ -46,7 +46,8 @@ int main(int argc, char ** argv) } rclcpp::init(argc, argv); - auto node = std::make_shared(); + rclcpp::NodeOptions options; + auto node = std::make_shared(options); rclcpp::spin(node); rclcpp::shutdown(); diff --git a/image_rotate/src/image_rotate_node.cpp b/image_rotate/src/image_rotate_node.cpp index 6839b9ca9..1935a9ec9 100644 --- a/image_rotate/src/image_rotate_node.cpp +++ b/image_rotate/src/image_rotate_node.cpp @@ -69,8 +69,8 @@ namespace image_rotate { -ImageRotateNode::ImageRotateNode() -: rclcpp::Node("ImageRotateNode") +ImageRotateNode::ImageRotateNode(const rclcpp::NodeOptions & options) +: rclcpp::Node("ImageRotateNode", options) { config_.target_frame_id = this->declare_parameter("target_frame_id", std::string("")); config_.target_x = this->declare_parameter("target_x", 0.0); @@ -361,7 +361,7 @@ void ImageRotateNode::onInit() } } // namespace image_rotate -#include "class_loader/register_macro.hpp" +#include "rclcpp_components/register_node_macro.hpp" // Register the component with class_loader. -CLASS_LOADER_REGISTER_CLASS(image_rotate::ImageRotateNode, rclcpp::Node) +RCLCPP_COMPONENTS_REGISTER_NODE(image_rotate::ImageRotateNode)