Skip to content

Commit

Permalink
load image_rotate::ImageRotateNode as component
Browse files Browse the repository at this point in the history
  • Loading branch information
mikeferguson committed Jan 18, 2024
1 parent 80c4178 commit 6af8973
Show file tree
Hide file tree
Showing 3 changed files with 7 additions and 6 deletions.
2 changes: 1 addition & 1 deletion image_rotate/include/image_rotate/image_rotate_node.hpp
Original file line number Diff line number Diff line change
Expand Up @@ -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);
Expand Down
3 changes: 2 additions & 1 deletion image_rotate/src/image_rotate.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -46,7 +46,8 @@ int main(int argc, char ** argv)
}

rclcpp::init(argc, argv);
auto node = std::make_shared<image_rotate::ImageRotateNode>();
rclcpp::NodeOptions options;
auto node = std::make_shared<image_rotate::ImageRotateNode>(options);

rclcpp::spin(node);
rclcpp::shutdown();
Expand Down
8 changes: 4 additions & 4 deletions image_rotate/src/image_rotate_node.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -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);
Expand Down Expand Up @@ -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)

0 comments on commit 6af8973

Please sign in to comment.