詳解 ROS2 エグゼキューター (Executor) - 1 -

執筆者:井上 叡
監修者:稲葉 貴昭・高橋 浩和

※ 「ROS2」連載記事一覧はこちら


はじめに

本連載では、ROS2のC++ APIを利用しているほとんどの方が利用しているにも関わらず、その仕組みや仕様についてあまり知られていないエグゼキューター (Executor) を紹介します。rclcppライブラリに実装されたエグゼキューターについてソースコードなどを追いながら、その仕組みについて詳しく追っていければと思います。 エグゼキューターは、ROS2の各ノードなどが持つコールバック関数等の"実行" (execute) を司る機能です。この機能はROSには無く、ROS2から導入されたものですが、ROS2の全てのバージョンに含まれています。この機能を理解することで、ノードに設定された種々のコールバックがどのようにスケジューリングされているか、どのように実行されるかを理解することができます。

なお、本連載ではROS2 jazzyでの各APIについて解説していきます。各ライブラリのバージョンは、rcl 9.2.5rclcpp 28.1.9rmw 7.3.2rclcpputils 2.11.2です。 以下にそれぞれのリポジトリへのリンクを掲載します。ソースコードを参照する際はクローンすると便利です。 また、本連載で掲載する各ライブラリのコードは全てこれらのリポジトリより引用します。

※ 本記事中では、機能としての総称としては「エグゼキューター」とカタカナで記述し、エグゼキューターの特定の具体的な実装を表す際には「rclcpp::Executor」のように名前空間付きで記述します。

コールバックはどこで実行される?

ROS2では、メッセージのsubscription、サービスのServerを構築する時など、様々な場面でコールバックを設定します。しかし、この設定したコールバック達はどのようにして、どこで実行されているのでしょうか?

以下は、公式のtutorialに掲載されている、最も単純なROSノードのコードです。(クラス定義等は省略)

  //  ~~~ 省略 ~~~

class MinimalPublisher : public rclcpp::Node
{
  //  ~~~ 省略 ~~~
};

int main(int argc, char * argv[])
{
  rclcpp::init(argc, argv);
  rclcpp::spin(std::make_shared<MinimalPublisher>());  // <-- ここが怪しい?
  rclcpp::shutdown();
  return 0;
}

上記コードのmain関数の中を見てみると、rclcpp::spin()関数がノードの実行を扱っていそうな気がします。そこで次に、この関数の実体が定義されている、executors.cppを見てみましょう。

// ~~~ 省略 ~~~

void
rclcpp::spin(rclcpp::node_interfaces::NodeBaseInterface::SharedPtr node_ptr)
{
  rclcpp::ExecutorOptions options;
  options.context = node_ptr->get_context();
  rclcpp::executors::SingleThreadedExecutor exec(options);
  exec.add_node(node_ptr);
  exec.spin();
  exec.remove_node(node_ptr);
}

void
rclcpp::spin(rclcpp::Node::SharedPtr node_ptr)
{
  rclcpp::spin(node_ptr->get_node_base_interface());
}

--- rclcpp/executors.cppより引用

上記をみると、rclcpp::spin系の関数は全てrclcpp::executors::SingleThreadedExecutorというものを利用して、そのspin系のメソッドを呼び出している事が分かります。 ここに出てくるrclcpp::executors::SingleThreadedExecutorはエグゼキューター(Executor)という機能です。次章からはこのエグゼキューターについて紹介していきます。

エグゼキューター(Executor)とは

エグゼキューター(Executor)は、ROS2の各ノードなどが持つコールバック関数等の"実行"(execute)を司るクラスです。このクラスはノードが持つユーザーが設定したコールバックなどの実行を管理するクラスで、主に以下の4つの役割を果たします。

  • コールバックをどこのスレッドで実行するか決定する
  • コールバック実行のスケジューリングを行う
  • 呼び出し準備が完了したコールバックを実行する
  • ノードに実装されている、コールバックを発生させる機能(subscription等)を管理する
  • (※ リアルタイム性能の提供 (標準では提供されていないが、ユーザーがExecutorを実装することで可能))

エグゼキューターはROS1には実装されておらず、ROS2から新たに導入されました。ROS1では各種コールバック等をマルチスレッドで実行したい場合などには、nodeletを利用する必要がありましたが、ROS2ではこのエグゼキューターを利用することでマルチスレッドでのコールバック実行が実現できます。また、ユーザーがエグゼキューターをカスタマイズしたり実装することで、リアルタイム要件へも対応することができます。実際、エグゼキューターを独自に実装し、リアルタイムに対応させた例があります。

エグゼキューター(Executor)の基礎

さて、エグゼキューターがコールバックを管理したり実行することは分かりましたが、そのコールバックは何によって設定されるのでしょうか?ROS2をお使いの方々はお分かりだと思いますが、ROS2ではユーザーがノードに設定するであろう機能のほとんどが、コールバックの設定を要求します。以下のノードの機能は実行結果をユーザーが設定したコールバックに渡して処理させるものです。

  • メッセージのSubscription
  • タイマー機能
  • Service
  • Action

エグゼキューターは各ノードに設定されたこれらの機能を監視し、条件(メッセージ受信やタイマー切れ)を満たした際にコールバックを呼び出します。 実はこの処理パターンは、Proactorパターンと呼ばれる非同期デザインパターンです。このパターンは、非同期で行われる何らかの操作の完了をイベントとして待機し、イベントが発生した際に対応した操作(コールバック)を呼び出すという処理を行うものです。これはROS2だと具体的には、タイマーイベントの発生、Subscriptionによるメッセージの受信完了、Service要求の受信完了などがイベントになり、イベント発生時に呼び出されるのはユーザーが設定したコールバック関数等になります。典型的には、Proactorパターンを利用すると非同期I/O(ROS2の場合はDDSによるデータの送受信でしょうか)を効率よく管理することができます。Proactorパターンについては筆者が以前執筆した以下の記事で詳しく解説を行っていますので、そちらをご覧ください。

valinux.hatenablog.com

エグゼキューター動作の図示 (https://docs.ros.org/en/jazzy/Concepts/Intermediate/About-Executors.html より引用)

上図は、エグゼキューターが行う以下のような動作を図示したものです。

  1. 設定された各種機能(Subscription、タイマー、Service、Actionなど)の準備完了を待機する
  2. 1.で待っている機能の1つ以上が準備完了したら、それらからデータ(受信したメッセージなど)を取り出す
  3. 2.で取り出したデータ(メッセージ等)を、対応したコールバックたちに渡して実行する
  4. 1.へ戻る

ユーザーにコールバックの設定を要求するノードの機能として、Subscription、タイマー、Action、Serviceなどがあると先ほど紹介しましたが、これらはROS2のノードの機能の大部分を占めます。これはつまり、ROS2ではノードのほとんどの機能がコールバックによって実行されるということで、ノードはエグゼキューターによって管理実行されるとも言えます。逆に、ノードの機能の中でコールバックではない関数として実装されるものは、主にシステムのエッジ(ユーザー入力・センサー入力など)に存在します。

ノードがエグゼキューターによって実行されるという点を利用して、ユーザーはエグゼキューターを通して複数のノードを同一のプロセスとして実行することができます。これは、ROS1ではnodeletという機能を新たに導入することで実現していました。しかしROS2では、複数ノードのコールバックをまとめて1つのエグゼキューターに管理させるなどすると、1プロセスで複数ノードを実行する事が可能です。また、エグゼキューターはコールバックの実行スレッドを複数用意することで、ROS1のAsyncSpinnerのようにコールバックの並列実行が可能です。これらを応用すると、複数のノードを同一プロセスで複数スレッドで実行するなどもできます。

エグゼキューターの種類

現在、デフォルトでrclcppに用意されたエグゼキューターには、以下の2種類があります。

  • rclcpp::SingleThreadedExecutor
  • rclcpp::MultiThreadedExecutor

これらの主な違いは、コールバックを実行するためのスレッドの違いです。クラス名の通り、rclcpp::SingleThreadedExecutorはコールバックをシングルスレッドで実行し、そのスレッドはノードのメインスレッドです。それに対してrclcpp::MultiThreadedExecutorはスレッドを ユーザーが指定した数 - 1 だけ生成し、それらのスレッド + メインスレッドでコールバックを並列実行します。

また、上記以外にも機能としては以下が存在しています。

その他 - ※ 次期rollingで削除予定 - rclcpp::executors::StaticSingleThreadedExecutor - ※ Experimentalな機能 - rclcpp::experimental::executors::EventExecutor

rclcpp::executors::StaticSingleThreadedExecutorは、jazzyの公式ドキュメントに説明が掲載されているものの、この説明はメンテナンスされておらず、不正確と思われます。*1ページ内説明ではSingleThreadedExecutorよりも効率が良いといった内容が主張されていますが、jazzy時点でのコードを読む限りではSingleThreadedExecutorとほぼ同じ動作をしていますし、むしろ少し効率が悪そうな実装になっています。ちなみに、kilted kaijuではまだ残っているものの、次期バージョンのrollingでは削除されるようです。rollingのドキュメントを見るとExecutorのリストから取り除かれています。ですので次のメジャーバージョン辺りで正式に削除されるのではないかという雰囲気です。

rclcpp::spin()をもう一度見てみる

さて、ここで最初に紹介したrclcpp::spin()関数の実装をもう一度見てみましょう。

void
rclcpp::spin(rclcpp::node_interfaces::NodeBaseInterface::SharedPtr node_ptr)
{
  rclcpp::ExecutorOptions options;
  options.context = node_ptr->get_context();
  rclcpp::executors::SingleThreadedExecutor exec(options);
  exec.add_node(node_ptr);
  exec.spin();
  exec.remove_node(node_ptr);
}

--- rclcpp/executors.cppより引用

exec.add_node(node_ptr);は、ノードをエグゼキューターの管理対象に設定するメソッドです。このメソッドでノードを設定すると、Subscriptionやそれらに設定されたコールバック等がエグゼキューターの管理対象に入ります。その後spin()関数を呼び出すことでrclレイヤーや通信ミドルウェアレイヤーに対して、コールバックの準備が完了したかの問い合わせなどを開始します。そして、ユーザー割り込み等でExecutor::cancel()Node::shutdown()が呼びだされるなどしてノードが停止させられるまで、問い合わせとコールバック実行のループを続けます。今回はSingleThreadedExecutorを使っているので、現在のスレッドでそのループが実行されます。

コールバックグループ(Callback Group)

ノードは複数のコールバックを持つことが多いですが、これらは「グループ」に分けることができます。これは、コールバックグループ(Callback Group)と呼ばれます。コールバックグループは、MultiThreadedExecutorなど、コールバックを複数スレッドで並列実行する可能性があるエグゼキューターを利用する際に重要です。実行方法で分けて以下の2種類が存在します。

  • Mutually exclusive (相互排他)
    • このグループに含まれるコールバック同士は並列実行してはいけない
  • Reentrant (リエントラント)
    • このグループに含まれるコールバック同士は並列に実行可能

上記に加えて、異なるコールバックグループに属しているコールバック同士は、いつでも並列実行可能です。 1つのノードが排他しなくてはいけない資源を扱うコールバックと、そうではないコールバックを同時に所有している場合などにコールバックグループは有効に活用できます。排他制御が必要な資源を扱うコールバックはMutually exclusiveなグループに、それ以外はReentrantに分けて設定しておくことで、コールバックを最大限並列に効率よく実行することが可能になります。 また、1つのノードがもつコールバックを2つ以上のコールバックグループに分けて、それらを違うエグゼキューターに設定することも可能です。例えば1つのノードがA,B,Cというコールバックを持っている時、それらを2つのコールバックグループに分けます。そして、Aだけが入っているコールバックグループと、BとCが入っているコールバックグループをそれぞれ違う2つのエグゼキューターに分けて管理させることも可能です。コールバックグループは適切にリエントラントと相互排他を選択しないと、容易にデッドロックしてしまいます。特に、内部で同期呼び出しを行うコールバックが存在する場合は気をつける必要があります。

コールバックに対してコールバックグループを明示的に指定しなかった場合、ノードが持つデフォルトのコールバックグループに属すると設定されます。設定するコールバックの種類が少なかったり、実行頻度が低い場合など特に設定する必要がないこともあります。また、シングルスレッドで実行したい場合もあまり設定の必要はありません。

プロセス内通信

複数ノードを同じプロセスで実行することが可能だと紹介しました。複数ノードを同一プロセスで実行している場合、それらのノードはプロセス内通信(intra-process communication)をすることができます。このプロセス内通信では、メッセージは外部の通信ミドルウェアのレイヤーを通ることなく、単なるポインタ渡しによって受け渡しが行われます。これによってプロセス間通信でどうしても発生するバッファへのコピー等が無くなり、ゼロコピーで高速に通信することができるようになります。画像データや点群データなどの大容量のデータを送受信する際に、上手く必要なノードを同一プロセスにまとめることで通信の効率化・高速化を図ることができます。

ROS2のプロセス内通信のデザインについては以下の公式ページに詳細があります。

プロセス内通信に関しては、これ以降は本連載ではあまり扱いません。 利用例などはいくつか日本語記事がありますので、気になる方はこちらをご覧ください。

ROS2 APIの階層構造

さて、次の章からrclcppのAPIであるrclcpp::Executorの詳しい機能や実装について紹介していきますが、その前にROS2のAPIの階層構造について把握しておく必要があります。まず、以下の図をご覧ください。

https://doi.org/10.1126/scirobotics.abm6074 より引用

上記の図から分かるように、私たちが普段利用するrclcppは最も上のレイヤーになります。その下に各言語実装向けの統一的なAPIを提供するrclが存在し、その下にはDDS等の通信ミドルウェアを抽象化する層である、rmwが存在します。rmwの下にようやく各通信ミドルウェアのrmw対応した層が存在します。以下にrmw対応したミドルウェアの実装の例を以下にいくつか挙げます。

上記のリポジトリを見ると、シグネチャの定義は行っておらず実装だけが書いてあります。rmwの中でも通信ミドルウェアのAPIを直接利用しないと実装できないAPI、例えば通信機能や待機機能は、rmw側ではシグネチャだけが定義されている形になります。その定義に対して、各ミドルウェア側ではミドルウェアのAPIを直接利用して書いた定義を用意している形になります。

以下に実際の例を掲載します。

// rclcpp/sequential_synchronization.hpp SequentialSynchronization::sync_wait()より
  rcl_ret_t ret = rcl_wait(&rcl_wait_set, time_left_to_wait_ns.count());

--- rclcpp/sequential_synchronization.hppより引用

上記は、Executor内での待機を実現している、SequentialSynchronization::sync_wait()という関数の実装の一部です。ここで、rcl_○○のような、rcl_というprefixがついた関数や構造体はrclのAPIです。ここではrcl_wait()が使われており、これが待機を行っていそうです。次はこれの実装を追ってみます。

//  rcl/wait.c rcl_wait()より
    // Wait.
  rmw_ret_t ret = rmw_wait(
    &wait_set->impl->rmw_subscriptions,
    &wait_set->impl->rmw_guard_conditions,
    &wait_set->impl->rmw_services,
    &wait_set->impl->rmw_clients,
    &wait_set->impl->rmw_events,
    wait_set->impl->rmw_wait_set,
    timeout_argument);

--- rcl/wait.cより引用

上記は、rcl_wait()の実装の一部です。ここで、rmw_○○というprefixがついた関数や構造体はrmwのAPIです。コードを見ると、待機を行っている関数はrmw_waitだと思われます。では次にこのrmw_waitの実装を追ってみましょう。

RMW_PUBLIC
RMW_WARN_UNUSED
rmw_wait_set_t *
rmw_create_wait_set(rmw_context_t * context, size_t max_conditions);

--- rmw/rmw.hより引用

すると、rmwのフォルダ内のrmw.hというファイルの中に上記のような関数のシグネチャの定義が見つかりました。しかし、rmwリポジトリのどこを見ても、rmw.cのような実装を定義したファイルは無く、rmw_waitの実装も見当たりません。これ以上実装を追いたい場合、上で紹介したように、各通信ミドルウェアを直接利用した実装を読みに行く必要があります。

例として、CycloneDDSでのrmw_wait実装を以下に掲載します。

// src/rmw_node.cppより
extern "C" rmw_ret_t rmw_wait(
  rmw_subscriptions_t * subs, rmw_guard_conditions_t * gcs,
  rmw_services_t * srvs, rmw_clients_t * cls, rmw_events_t * evs,
  rmw_wait_set_t * wait_set, const rmw_time_t * wait_timeout)
  // ~~~   省略   ~~~~
  const dds_return_t ntrig = dds_waitset_wait(
    ws->waitseth, ws->trigs.data(),
    ws->trigs.size(), timeout);
  ws->trigs.resize(ntrig);
  // ~~~   省略   ~~~~

--- https://github.com/ros2/rmw_cyclonedds/tree/jazzy より引用

CycloneDDSのrmw実装を見ると、rmw_node.cppというファイルにようやくrmw_waitの実装を見つけました。これを見るとCycloneDDSをミドルウェアに利用する場合は、最終的に待機はdds_waitset_waitという関数で行っている事が分かりました。

これで、ようやくExecutorの中での待機の具体的なメカニズムをある程度知ることができました。このように、特に通信待機のような通信ミドルウェアの機能と密接に関わる機能は、最終的には自分が使用する各ミドルウェアの実装を見ないと分かりません。ですので、待機の具体的なメカニズムを知りたい場合などは、各ミドルウェアの実装を確認しにいく事をおすすめします。 また、同様の事情から、本記事では待機や通信などについてそれぞれのミドルウェアにおける詳細なメカニズムを紹介することはしません(できません)。あくまで、rclcppのExecutorクラスとしての動作について焦点を当てて紹介していきます。

エグゼキューターの実装 基底クラス rclcpp::Executor <待機機構の概要>

前の項でエグゼキューターとして3種類が用意されていると記載しましたが、それらは全てrclcpp::Executorという基底クラスを継承して実装されています。本章ではそのクラスについて見ていきます。

rclcpp::Executorは、executor.hppexecutor.cppに定義と実装が書かれています。このクラス自身は何も継承しておらず、必要な機能はコンポジションの形でメンバ変数として持っています。

このクラスが持っているメンバ変数だけを抜き出すと、以下のようになります。

  std::atomic_bool spinning;

  std::shared_ptr<rclcpp::GuardCondition> interrupt_guard_condition_;

  std::shared_ptr<rclcpp::GuardCondition> shutdown_guard_condition_;

  mutable std::mutex mutex_;

  std::shared_ptr<rclcpp::Context> context_;

  std::shared_ptr<rclcpp::executors::ExecutorNotifyWaitable> notify_waitable_;

  std::atomic_bool entities_need_rebuild_;

  rclcpp::executors::ExecutorEntitiesCollector collector_;

  rclcpp::WaitSet wait_set_ RCPPUTILS_TSA_GUARDED_BY(mutex_);
  std::optional<rclcpp::WaitResult<rclcpp::WaitSet>> wait_result_ RCPPUTILS_TSA_GUARDED_BY(mutex_);

  rclcpp::executors::ExecutorEntitiesCollection current_collection_ RCPPUTILS_TSA_GUARDED_BY(
    mutex_);

  std::shared_ptr<rclcpp::executors::ExecutorNotifyWaitable> current_notify_waitable_
  RCPPUTILS_TSA_GUARDED_BY(mutex_);

  rclcpp::OnShutdownCallbackHandle shutdown_callback_handle_;

  std::unique_ptr<ExecutorImplementation> impl_;

--- rclcpp/executor.hppより抜粋

RCPPUTILS_TSA_GUARDED_BYというマクロはclangでの静的解析に利用されるものです。コードを読むに当たっては、該当のリソースはマクロの引数に書かれたmutexによって排他制御されるべき対象であると宣言されていると理解しておけば問題ないです。詳しくは、rclcpputilsのリポジトリとclangのドキュメントを確認してください。

rclcpp::Executorのメンバの中で、動作する上で特に重要となるのが以下の4つのクラスです。

  • rclcpp::executors::ExecutorEntitiesCollection
    • エグゼキューターが持つエンティティ(後述)への参照を一括で保持する。
  • rclcpp::ExecutorEntitiesCollector
    • エグゼキューターが持つエンティティ(後述)を収集し、ExecutorEntitiesCollectionにまとめる。
    • エンティティに変更があった場合はそれを再度収集し直す。
  • rclcpp::WaitSet
    • コールバックを発生させる待機機構(subscription、timer、service、actionなど)を監視する。
    • コールバックが準備完了になるまでの待機動作を行う。
  • rclcpp::WaitResult<rclcpp::WaitSet>
    • WaitSetの待機結果を表すクラス。これが準備完了になったエンティティ(後述)とコールバックのリストを持つ。

まずは、上記の中でも最も重要なrclcpp::WaitSetについて紹介します。ここでは、今後の説明に必要な用語や概念についても同時に説明するため、飛ばさずお読みいただけると幸いです。

rclcpp::WaitSet

このクラスは、コールバックの準備完了を待機する機能を持ちます。このクラスが「待機」してコールバック実行の準備が完了するのを待つ対象の機能は以下の5つです。

  • Subscription
  • Timer
  • Service Server
  • Service Client
  • Waitable (∋ Action Server/Client)

これらの、「条件を満たすまで待機する ➡ 条件を満たしたら(=準備完了したら)コールバックを実行する」という共通項を持つ5つの機能を、エグゼキューターの文脈ではエンティティと呼びます。つまり、rclcpp::WaitSetはエンティティを監視し、その準備完了を待つ機能を持っているといえます。ちなみに、「準備完了」というのは、Subscriptionの場合はあるトピックからのメッセージの受信完了、Timerの場合は指定時間経過、などを指します。

しかし、上記のエンティティにはActionが直接的には含まれていません。加えて、代わりに見慣れないWaitableという機能が出てきました。

Waitable

突然登場したこのWaitableという機能は、rclcpp::Waitableというクラスとして実装されています。これはrclcpp/waitable.hppとrclcpp/waitable.cppに実装があります。このクラスは、

  • 何らかの満たすべき条件を設定することができ、現在その条件を達成しているか否かを外部から確認できる。
  • 条件を満たした時に、「実行されるべき一連の処理」をクラス内部に保持する。("一連の処理"はコールバックとして保持しても、クラスメソッドとして直接実装しても良い)

という機能をもつ基底クラスです。これは、TimerやSubscriptionなど、エンティティを一般化したクラスともいえます。このクラスを継承して必要機能を実装したクラスは、他のエンティティと一緒にエグゼキューターに実行を管理させることができます。Actionは正にその例で、Server/Client共にrclcpp::Waitableを継承して実装されているため、Waitableに分類されます。また、rclcpp::Executorはメンバとしてrclcpp::executors::ExecutorNotifyWaitableというクラスを持ちます。今後解説していきますが、このクラスも名前の通りrclcpp::Waitableを継承して実装されています。それ以外には、PublisherやSubscriberが通信ミドルウェア側からの何らかのイベント通知(例:指定したQoSの値が不適切だった等)を受け取る機能も、Waitableによって実装されています。もちろん、ユーザーがこのクラスを継承して実装したクラスもエグゼキューターに管理実行させる事が可能です。

WaitSetの待機機構

rclcpp::WaitSetで実際に待機を行うメソッドは、rclcpp::WaitSet::wait()です。このメソッド内ではrclのAPIである、rcl_wait()を利用して待機を実現しています。

関数のシグネチャと、rcl_wait_set_tの定義は以下の通りです。

typedef struct rcl_wait_set_s
{
  /// Storage for subscription pointers.
  const rcl_subscription_t ** subscriptions;
  /// Number of subscriptions
  size_t size_of_subscriptions;
  /// Storage for guard condition pointers.
  const rcl_guard_condition_t ** guard_conditions;
  /// Number of guard_conditions
  size_t size_of_guard_conditions;
  /// Storage for timer pointers.
  const rcl_timer_t ** timers;
  /// Number of timers
  size_t size_of_timers;
  /// Storage for client pointers.
  const rcl_client_t ** clients;
  /// Number of clients
  size_t size_of_clients;
  /// Storage for service pointers.
  const rcl_service_t ** services;
  /// Number of services
  size_t size_of_services;
  /// Storage for event pointers.
  const rcl_event_t ** events;
  /// Number of events
  size_t size_of_events;
  /// Implementation specific storage.
  rcl_wait_set_impl_t * impl;
} rcl_wait_set_t;


rcl_ret_t
rcl_wait(rcl_wait_set_t * wait_set, int64_t timeout);

--- rcl/wait.hより引用

上記を見て分かるのは、rcl_wait_set_tはエンティティの集合であり、rcl_wait()はそれとタイムアウト時間を受け取って動作するということです。このrcl_wait()の動作は、Linuxのシステムコールのselet()などに代表されるReactorの動作とほぼ同様です。(Reactorについて詳しくは、筆者が以前書いた記事(https://www.valinux.co.jp/blog/entry/20250312)をご参照ください。)

selectシステムコールは、同期I/Oを多重化して待機し(=ブロックし)、その中の1つ以上が準備完了になった時にブロックが解除されて戻ります。多重化する対象の同期I/Oは、fd_setとして、ファイルディスクリプタの集合を引数に渡します。結果は、引数として渡されたfd_setに準備完了したファイルディスクリプタだけを残し、それ以外は取り除くことで返します。

rcl_wait()はまさにこのselect()システムコールのアナロジーとして理解できます。rcl_wait()でも、監視対象となるエンティティの集合をrcl_wait_set_tとして引数に渡し、同期I/Oである各エンティティの準備完了を多重化して待ちます。そして、その集合に含まれる1つ以上のエンティティが準備完了になった時に、関数はブロックを解除して戻ります。結果は、準備完了したエンティティだけを引数となったrcl_wait_set_t内に有効なポインタとして残し、そうでないエンティティはrcl_wait_set_tからポインタを消すという手段で返します。ここでの準備完了は、そのエンティティに結びついたコールバックを呼び出す準備が完了した事を表します(Subscriptionにおけるメッセージ受信完了、Timerにおける指定時間経過など)。

rclcpp::WaitSet::wait()は、ここで紹介したrcl_wait()関数をほぼそのまま使っている形に近く、単純な理解としてはそれらはほぼ同一だと考えてもあまり問題ありません。rcl_wait()が返した結果はポインタの集合という扱いにくい形で返ってくるため、rclcpp::WaitResult<rclcpp::WaitSet>クラスを使って利用しやすい形に変換などの処理をして返しています。

-- 余談 -- ちなみに、rcl_wait()の実装を追うと、内部でrmw_wait()によって待機をしていることが分かります。前章の例にも出しましたが、これは各通信ミドルウェアを使ってそれぞれの実装が行われるAPIです。先ほど紹介したrcl_wait()の動作はどのようなミドルウェアを利用しても同じになるように決められていますが、待機機構の細かい実装は当然ながら利用する通信ミドルウェアによって違います。参考までに、CycloneDDSのrmw実装ではCycloneDDSのAPIである、dds_waitset_wait()という関数を使って待機が実装されているようです。

ここまで読んだ方の中には、rcl_wait_set_tにWaitableのようなものが含まれていない事に気づいた方もいるかもしれません。実は、Waitable相当の機能はrclには存在せず、rclcppの機能として実装されています。Waitableによる待機解除(= 準備完了した事をrcl_wait()に通知する)は、上記rcl_wait_set_tがメンバとして持っているrcl_event_tや、rcl_guard_condition_tを利用して実装されています。Waitableの実装や、rcl_guard_condition_trcl_event_tなどについては今後説明します。

また、前述の5つのエンティティのうち、Subscription、Service Client、Service Serverの3つは、「それらがメッセージを受け取ったかどうか」というのがコールバック呼び出し準備完了の最大の基準です。通信機能はrmwレイヤーに実装されているので、それらのエンティティの準備完了の判定のほとんどの部分はrmwレイヤー内で完了します。(具体的には、rmw_wait()が結果としてそれらのエンティティを返してきたら、準備完了したと判断してあまり問題ないでしょう。) しかし、タイマーはそれらとは少し違ってrclレイヤーの中に準備完了の判定の多くの部分が実装されています。これは、タイマー機能のほとんどがrclレイヤー内で実装されていることによります。(タイマー機能の実現には通信ミドルウェアは必要無いので、タイマーがrmwレイヤーとあまり関係ないのはある意味当然ではあります。)例えば、rcl_wait()内のタイマーのチェックに関する実装を追っていくと、rmw_○○系の関数が登場せず、ほぼrcl/time.hとrcl/timer.hのもので完結しています。 当然ながら、Waitableもrmwレイヤーだけでは準備完了の判定はできません。こちらの場合はそもそもrclcppレイヤーに実装されていますので、rclcppレイヤー内でしっかりと準備完了したかどうかを判定してやる必要があります。 ちなみに、ここで紹介したのはあくまで「準備完了したかどうかの判定」についてです。rmw_wait()関数を起床させるための機構に関しては、Waitableもタイマーもrmwレイヤーの機能を利用してwait関数を起床させます。

おわりに

今回は、エグゼキューターの基礎的な知識について解説しました。次回はrclcpp::Executorの実装を追いながら、スケジューリングメカニズムやエンティティの管理方法などについて紹介していきます。

参考文献

*1:残念な事にコード側のコメントも長らく更新されていません。