15
5

Delete article

Deleted articles cannot be recovered.

Draft of this article would be also deleted.

Are you sure you want to delete this article?

Ros2のゼロコピーを試してみる

Last updated at Posted at 2024-02-05

Ros2のゼロコピーについて

Ros2でpoint cloudなど大きなデータをtopicに流す場合,データのコピーが発生するため全体としての処理が遅くなることがあります.このような問題を解消するためにRos2ではデータそのものを通信するのではなく,データのポインタを送信することによって,データのコピーをせずゼロコピーでノード間のデータ通信をする手法が提供されています.なお,これは一つのマシン内での通信に限り,外部マシンで動いているRos2ノードにデータを通信する場合には利用できません.

2024/02/15追記

これは,実証していないので話半分に聞いてもらえればと思います.
ゼロコピーは処理を軽くする面では強力ですが,すべてのノードをゼロコピーにするのはおすすめしません(できるように作っておくのはOK).Ros2ではExecuterというものがsubscribeのcallback関数やtimerCallback関数などの処理を行っており,ゼロコピーは同一のExecuterに処理を任せているノード間でのみ(おそらく)成立しています.したがって,すべてのトピックをゼロコピーで実現するということは,すべての処理が単一のExecuterで行われるということです.もちろんExecuterはマルチスレッドに対応したものもありますが,場合によってはcallback関数が処理されるまでの遅延が発生します.なので,著しくコピーに時間がかかる部分であったり,地図作成など処理の順番が決まっている部分(ポイントクラウド処理 -> 地図作成処理)だけゼロコピーで実装し,並列に処理される部分についてはゼロコピーにしないほうが(同一のExecuterに処理を任せない方が)良いかと思います.

わかりにくいと思うので,今回紹介する方法に当てはめるとrclcpp::Executerの方法ではノードをadd_nodeするExecuterを分ける,component containerを利用する方法ではロードするcontainerを分けることでゼロコピーの必要性のない処理を並列にさせるということです.

使い方

Node作成

今回は簡単なTalker, Listenerノード間でstd_msgs::msg::Stringをゼロコピーで通信することを目的としています.
ノードの実装については, こちらで公開しています.
重要な部分としては,以下になります.

  1. Ros2ノードのオプションにあるuse_intra_process_commsというものをtrueに設定すること
  2. UniquePtrで送信するメッセージのインスタンスを作成し,パブリッシュする場合にstd::moveを利用すること
  3. 受信側のcallback関数の引数をUniquePtr型で受け取ること

注意点として,ゼロコピーではパブリッシュしたメッセージのインスタンスをその後利用しないという前提があります.なので,メンバ変数ではなくパブリッシュする直前にメッセージのインスタンスを作成するようにしています.
実装は以下の通り.

Talker

talker.hpp
#include <rclcpp/rclcpp.hpp>
#include <std_msgs/msg/string.hpp>
#include <chrono>

class Talker: public rclcpp::Node
{
public:
    // デフォルトでuse_intra_process_comms(true)に設定
    Talker(const rclcpp::NodeOptions options = rclcpp::NodeOptions().use_intra_process_comms(true)); 
    ~Talker();

private:
    rclcpp::Publisher<std_msgs::msg::String>::SharedPtr pub_;
    rclcpp::TimerBase::SharedPtr timer_;
    void callbackTimer();
};
talker.cpp
#include <talker/talker.hpp>
#include <chrono>

using namespace std::chrono_literals;
Talker::Talker(const rclcpp::NodeOptions options)
: rclcpp::Node("talker", options)
{
    timer_ = create_wall_timer(500ms, std::bind(&Talker::callbackTimer, this));
    pub_ = create_publisher<std_msgs::msg::String>(
        "topic", 1
    );
}

Talker::~Talker() {}

void Talker::callbackTimer()
{
    // UniquePtrでメッセージのインスタンス作成
    std_msgs::msg::String::UniquePtr msg(new std_msgs::msg::String);
    msg->data = "Hello world";
    // 送信するデータのポインタを表示
    RCLCPP_INFO(get_logger(), "Publish msg address: %x", &(msg->data));
    // std::moveを利用してパブリッシュ
    pub_->publish(std::move(msg));
}

#include <rclcpp_components/register_node_macro.hpp>
RCLCPP_COMPONENTS_REGISTER_NODE(Talker);

Listener

listener.hpp
#include <rclcpp/rclcpp.hpp>
#include <std_msgs/msg/string.hpp>

class Listener: public rclcpp::Node
{
public:
    Listener(const rclcpp::NodeOptions options = rclcpp::NodeOptions().use_intra_process_comms(true));
    ~Listener();

private:
    rclcpp::Subscription<std_msgs::msg::String>::SharedPtr sub_;
    // UniquePtrでメッセージを取得
    void callbackString(const std_msgs::msg::String::UniquePtr msg);
};
listener.cpp
#include <listener/listener.hpp>

Listener::Listener(const rclcpp::NodeOptions options)
: rclcpp::Node("listener", options)
{
    sub_ = create_subscription<std_msgs::msg::String>(
        "topic", 1, std::bind(&Listener::callbackString, this, std::placeholders::_1)
    );
}

Listener::~Listener() {}

// UniquePtrでメッセージを取得
void Listener::callbackString(const std_msgs::msg::String::UniquePtr msg)
{
    // 受信したデータのポインタを表示
    RCLCPP_INFO(get_logger(), "Received msg address: %x", &(msg->data));
}

#include <rclcpp_components/register_node_macro.hpp>
RCLCPP_COMPONENTS_REGISTER_NODE(Listener);

実行方法

実は上で作成したノードをそれぞれ立ち上げればゼロコピーが達成されるという訳ではありません.ゼロコピーを達成するためには,それに対応した立ち上げ方が必要になります.今回は2つの方法を用いて立ち上げを行います.

component containerを利用する方法

launchファイルにて同じコンテナにノードをロードすることによって,ゼロコピーを達成することができます.
注意点として,(何故か)デフォルトでuse_intra_process_comms(true)にしてもComposableNodeのロードにてextra_arguments=[{"use_intra_process_comms": True}]とする必要があります.

same_container.launch.py
from launch import LaunchDescription
from launch_ros.actions import Node, ComposableNodeContainer, LoadComposableNodes
from launch_ros.descriptions import ComposableNode

def generate_launch_description():
    container = ComposableNodeContainer(
        name="my_container", 
        package="rclcpp_components",
        executable="component_container",
        namespace="",
        composable_node_descriptions=[
            ComposableNode(
                package="talker",
                plugin="Talker",
                name="talker",
                extra_arguments=[{"use_intra_process_comms": True}],
            ),
        ],
        output="screen",
    )
    
    load_composable_nodes = LoadComposableNodes(
        target_container="my_container",
        composable_node_descriptions=[
            ComposableNode(
                package="listener",
                plugin="Listener",
                name="listener",
                extra_arguments=[{"use_intra_process_comms": True}],
            ),
        ],
    )
    
    return LaunchDescription([
        container, 
        load_composable_nodes
    ])

上記launchファイルを実行すると以下のような出力が得られ,送受信するメッセージが同じポインタを持っていることが確認できます.

[INFO] [1707166270.163160339] [talker]: Publish msg address: a0638be0
[INFO] [1707166270.163248935] [listener]: Received msg address: a0638be0
[INFO] [1707166270.663158950] [talker]: Publish msg address: a061aa70
[INFO] [1707166270.663240493] [listener]: Received msg address: a061aa70
[INFO] [1707166271.163155755] [talker]: Publish msg address: a061aa40
[INFO] [1707166271.163250642] [listener]: Received msg address: a061aa40

rclcpp::executerを利用する方法

こちらではlaunchファイルではなく実行ファイル内でノードの立ち上げを行っていきます.
ソースコードは.cppで作成し,rclcpp::executerにノードをロードしていきます.
executerにはいくつか種類があるそうで,詳しくは公式ページに書いてあります.

executer.cpp
#include <rclcpp/rclcpp.hpp>
#include <talker/talker.hpp>
#include <listener/listener.hpp>

int main(int argc, char** argv)
{
    rclcpp::init(argc, argv);
    // nodeを作成
    rclcpp::Node::SharedPtr talker = std::make_shared<Talker>();
    rclcpp::Node::SharedPtr listener = std::make_shared<Listener>();

    // executerにノードをロード
    rclcpp::executors::SingleThreadedExecutor executer;
    executer.add_node(talker);
    executer.add_node(listener);

    executer.spin();

    rclcpp::shutdown();

    return 0;
}

これをビルドしてros2 runにより実行することでcomponent containerの場合と同じような結果が得られます.

まとめ

今回はRos2におけるゼロコピーを2つの実行方法で試してみました.
やってみた感想としては,executerを利用する方法だとパラメータの設定や,リマッピングのために改めてlaunchファイルを作成する必要があるのでcomponent containerを利用した方がいいのかなと思います.
また,自分でパッケージを作る際には単純なlaunchファイルの他に,ロードするcomponent containerの名前を引数として受取り,そのcomponent containerにノードをロードするというようなファイルを作っておくと他のパッケージのノードとゼロコピーをするときにlaunchファイルが綺麗にまとまるのかなと思います.

ソースコード

15
5
0

Register as a new user and use Qiita more conveniently

  1. You get articles that match your needs
  2. You can efficiently read back useful information
  3. You can use dark theme
What you can do with signing up
15
5

Delete article

Deleted articles cannot be recovered.

Draft of this article would be also deleted.

Are you sure you want to delete this article?