[ROS2] Passing additional arguments to component constructor
Hi,
I am using ROS2 Foxy on Ubuntu 20.04.
I am trying to create a node using components using manual composition.
I would like to pass additional arguments during the creating of the component objects. The following files were created.
Node Code
#include <memory>
#include "test_pkg/test_component.hpp"
#include "rclcpp/rclcpp.hpp"
int main(int argc, char * argv[])
{
setvbuf(stdout, NULL, _IONBF, BUFSIZ);
rclcpp::init(argc, argv);
rclcpp::executors::MultiThreadedExecutor exec;
rclcpp::NodeOptions options;
RCLCPP_INFO(rclcpp::get_logger("rclcpp"), "Adding node...");
std::string test_ID = "J1";
auto test_node = std::make_shared<test_composition::test>(test_ID, options);
exec.add_node(test_node);
RCLCPP_INFO(rclcpp::get_logger("rclcpp"), "Spinning");
exec.spin();
rclcpp::shutdown();
return 0;
}
Component Header
#ifndef COMPOSITION__TEST_COMPONENT_HPP_
#define COMPOSITION__TEST_COMPONENT_HPP_
#include <test_pkg/visibility_control.h>
#include <rclcpp/rclcpp.hpp>
#include <std_msgs/msg/float32.hpp>
#include <std_srvs/srv/set_bool.hpp>
namespace test_composition
{
class Test : public rclcpp::Node
{
public:
COMPOSITION_PUBLIC
explicit Test(const std::string &test_ID, const rclcpp::NodeOptions &options);
protected:
void timer_callback();
void client_output();
private:
rclcpp::Publisher<std_msgs::msg::float32>::SharedPtr test_publisher;
rclcpp::TimerBase::SharedPtr test_publisher_timer;
size_t count_;
std::string test_name;
};
}
#endif
Component Code
#include "test_pkg/test_component.hpp"
#include <chrono>
#include <memory>
#include <iostream>
#include <utility>
#include "rclcpp/rclcpp.hpp"
#include "std_msgs/msg/float32.hpp"
#include "std_srvs/srv/set_bool.hpp"
using namespace std::chrono_literals;
namespace test_composition
{
Test::Test(const std::string &test_ID, const rclcpp::NodeOptions &options)
: Node(test_ID, options)
{
RCLCPP_INFO(get_logger(), "Configuring Node...");
test_name = test_ID;
test_publisher = create_publisher<std_msgs::msg::float32>(test_name + "/speed", 0);
test_publisher_timer = create_wall_timer(500ms, std::bind(&Test::timer_callback, this));
}
void Test::timer_callback()
{
auto msg = std::make_unique<std_msgs::msg::float32>();
msg->data = ++count_;
test_publisher->publish(std::move(msg));
}
}
#include "rclcpp_components/register_node_macro.hpp"
RCLCPP_COMPONENTS_REGISTER_NODE(test_composition::Test)
I want to create multiple nodes using the Test class with different "test_ID" and therefore need to pass the additional argument to the constructor. But when I try to build the program using colcon build, I get the following error.
Error
error: no matching function for call to ‘test_composition::Test::Test(const rclcpp::NodeOptions&)’
146 | { ::new((void *)__p) _Up(std::forward<_Args>(__args)...); }
| ^~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~
/home//user/test_ws/src/test_pkg/src/test_component.cpp:16:5: note: candidate: ‘test_composition::Test::Test(const string&, const rclcpp::NodeOptions&)’
16 | Test::Test(const std::string &test_ID, const rclcpp::NodeOptions &options)
| ^~~~
/home/user/test_ws/src/test_pkg/src/test_component.cpp:16:5: note: candidate expects 2 arguments, 1 provided
make[2]: *** [CMakeFiles/test_component.dir/build.make:63: CMakeFiles/test_component.dir/src/test_component.cpp.o] Error 1
make[1]: *** [CMakeFiles/Makefile2:107: CMakeFiles/test_component.dir/all] Error 2
make: *** [Makefile:141: all] Error 2
Without the additional (test_id) argument the program gets build. I have also tried doing the same with a simple node without composition and it build correctly. Any help is greatly appreciated. Thank you!