Robotics StackExchange | Archived questions

Create composed publisher with topic as constructor argument

I'm using ros2 dashing. I'm trying to create composed publisher and subscriber nodes and pass the topic and message content to the nodes as an argument.

My starting point for composition are in minimal_composition examples. My starting point for passing the topic as an argument to the publisher or subscriber constructors are in demonodescpp, and specifically the talker and listener. I note that these demos appear to have changed between the dashing and master branches, removing the ability to specify the topic. It's unclear if some part of the API is now deprecated. In any case, I am building this based on dashing and the demos work on my machine.

My header for the composed talker:

 #ifndef MINIMAL_COMPOSITION__TALKER_NODE_HPP_
#define MINIMAL_COMPOSITION__TALKER_NODE_HPP_

#include <memory>

#include "rclcpp/rclcpp.hpp"
#include "std_msgs/msg/string.hpp"
#include "macaroon_test/visibility.h"

class TalkerNode : public rclcpp::Node
{
public:
  MINIMAL_COMPOSITION_PUBLIC TalkerNode(const std::string & topic_name, const std::string & msg_base);

private:
  std::unique_ptr<std_msgs::msg::String> msg_;
  std::string msg_base_;
  rclcpp::Publisher<std_msgs::msg::String>::SharedPtr pub_;
  rclcpp::TimerBase::SharedPtr timer_;
};

#endif // MINIMAL_COMPOSITION__TALKER_NODE_HPP_

My source file for the composed talker (included for completeness, but the error trace below shows compilation doesn't make it through the #include for the header file):

#include <chrono>

#include "macaroon_test/talker_node.hpp"
#include "rclcpp/rclcpp.hpp"
#include "std_msgs/msg/string.hpp"

using namespace std::chrono_literals;

TalkerNode::TalkerNode(const std::string & topic_name, const std::string & msg_base)
: Node("talker")
{
    // Create a function for when messages are to be sent.
    auto publish_message =
        [this]() -> void
        {
        msg_ = std::make_unique<std_msgs::msg::String>();
        msg_->data = msg_base_;
        RCLCPP_INFO(this->get_logger(), "Publishing: '%s'", msg_->data.c_str());

        // Put the message into a queue to be processed by the middleware.
        // This call is non-blocking.
        pub_->publish(std::move(msg_));
        };

    pub_ = this->create_publisher<std_msgs::msg::String>(topic_name, 10);

    // Use a timer to schedule periodic message publishing.
    timer_ = this->create_wall_timer(1s, publish_message);

    // Assign incoming message base
    msg_base_ = msg_base;
}

#include "rclcpp_components/register_node_macro.hpp"

RCLCPP_COMPONENTS_REGISTER_NODE(TalkerNode)

I get the following error when I try to build with colcon:

In file included from /usr/include/x86_64-linux-gnu/c++/7/bits/c++allocator.h:33:0,
             from /usr/include/c++/7/bits/allocator.h:46,
             from /usr/include/c++/7/memory:63,
             from /home/broomstick/ros2_dashing/install/rclcpp/include/rclcpp/rclcpp.hpp:142,
             from /home/broomstick/ros2_macaroons_ws/src/examples/macaroon_test/include/macaroon_test/talker_node.hpp:4,
             from /home/broomstick/ros2_macaroons_ws/src/examples/macaroon_test/src/talker_node.cpp:3:
...
...
/home/broomstick/ros2_dashing/install/rclcpp/include/rclcpp/node_options.hpp:63:3:   required from here
/usr/include/c++/7/ext/new_allocator.h:136:4: error: no matching function for call to ‘TalkerNode::TalkerNode(const rclcpp::NodeOptions&)’
  { ::new((void *)__p) _Up(std::forward<_Args>(__args)...); }
    ^~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~
/home/broomstick/ros2_macaroons_ws/src/examples/macaroon_test/src/talker_node.cpp:11:1: note: candidate: TalkerNode::TalkerNode(const string&, const string&)
 TalkerNode::TalkerNode(const std::string & topic_name, const std::string & msg_base)
 ^~~~~~~~~~
/home/broomstick/ros2_macaroons_ws/src/examples/macaroon_test/src/talker_node.cpp:11:1: note:   candidate expects 2 arguments, 1 provided

As a test, I just rolled all the definitions and implementations of the talker and listener classes into a single file with a short main function, and that compiled and ran just fine, which adds to my confusion. I didn't want to copy it all here, but you can find it in this gist.

Asked by broomstick on 2020-04-28 07:19:44 UTC

Comments

Answers