Getting Started with ROS on Embedded Systems - User Guide - C++ - Initialization

From RidgeRun Developer Wiki





Previous: User Guide/C++/Package set up Index Next: User Guide/C++/Topics




Introduction

Based on our previous example, this section will try to cover the initialization part of the code.

Initialization

In every ROS2 code, we need to call ROS and initialize it:

int main(int argc, char * argv[])
{
  rclcpp::init(argc, argv);
  ...

Starting

After initialization, we actually need to create a node, a basic empty node:

class MinimalPublisher : public rclcpp::Node
{
  public:
    MinimalPublisher() : Node(NODE_NAME), count_(0)
    {
      publisher_ = this->create_publisher<MSG_TYPE>(TOPIC, PUB_QUEUE);
    }

  private:
    rclcpp::Publisher<std_msgs::msg::String>::SharedPtr publisher_;
};
  • NODE_NAME, the name of the node, helps to locate it using the ROS logger or using the ROS cmdline tools.
  • TOPIC, the actual topic name where the node will publish its messages.
  • PUB_QUEUE, length of the publisher queue.
  • MSG_TYPE, the data type for the ROS messages.

In this case we have a simple timer-based publisher that publishes an increasing counter every 500 ms, but most importantly, this is the line needed to publish data:

  publisher_->publish(message);

Running the node

ROS executables have a main loop, and to actually run anything, we need to attach a node to it, to do so we have the following apis:

  • rclcpp::spin(std::make_shared<MinimalPublisher>()): run forever.
  • rclcpp::spin_some(std::make_shared<MinimalPublisher>()): run once and exit.
  • rclcpp::spin_until_future_complete: checks for a condition to be met, and after that condition is true, it stops and exits.

Running Multiple Nodes

It's possible to run multiple nodes on the same executable; to do so, you can use a MultiThreadedExecutor and add N nodes to it like:

rclcpp::executors::MultiThreadedExecutor executor;

To do so, we can use the following code for a dual-node publisher example:

class MinimalPublisher : public rclcpp::Node
{
  public:
    MinimalPublisher(std::string node_name, std::string topic_name) : Node(node_name)
    {
      publisher_ = this->create_publisher<std_msgs::msg::String>(topic_name, 10);
      timer_ = this->create_wall_timer(500ms, std::bind(&MinimalPublisher::timer_callback, this));
      count_ = 0;
    }

  private:
    void timer_callback()
    {
      auto message = std_msgs::msg::String();
      message.data = "Hello, world! " + std::to_string(count_++);
      RCLCPP_INFO(this->get_logger(), "Publishing: '%s'", message.data.c_str());
      publisher_->publish(message);
    }

    rclcpp::TimerBase::SharedPtr timer_;
    rclcpp::Publisher<std_msgs::msg::String>::SharedPtr publisher_;
    size_t count_;
};

int main(int argc, char * argv[])
{
  rclcpp::init(argc, argv);
  rclcpp::executors::MultiThreadedExecutor executor;
  auto node1 = std::make_shared<MinimalPublisher>("PUB_1", "TOPIC_1");
  auto node2 = std::make_shared<MinimalPublisher>("PUB_2", "TOPIC_2");
  executor.add_node(node1);
  executor.add_node(node2);

  executor.spin();
  rclcpp::shutdown();
  return 0;
}

And when executing, we can see both nodes sending data:

^C[INFO] [1710200815.973955444] [rclcpp]: signal_handler(signum=2)
root@vision:/test/build/test# ./talker 
[INFO] [1710200998.614902468] [PUB_1]: Publishing: 'Hello, world! 0'
[INFO] [1710200998.623128763] [PUB_2]: Publishing: 'Hello, world! 0'
[INFO] [1710200999.114898206] [PUB_1]: Publishing: 'Hello, world! 1'
[INFO] [1710200999.123280536] [PUB_2]: Publishing: 'Hello, world! 1'
[INFO] [1710200999.614873945] [PUB_1]: Publishing: 'Hello, world! 2'
[INFO] [1710200999.623183985] [PUB_2]: Publishing: 'Hello, world! 2'
[INFO] [1710201000.114919412] [PUB_1]: Publishing: 'Hello, world! 3'

If needed, we can mix publisher and receiver nodes on the same code, using the same approach.

Previous: User Guide/C++/Package set up Index Next: User Guide/C++/Topics