ロボット開発記録

ロボット開発の進捗や記録をするブログ

ROS 2パラメータの利用 [ヒューマノイド動歩行]

前回の振り返り & 今回の概要

 前回の記事では、ソフトウェアアーキテクチャの思案を行いました。  今回は、ROS 2の機能の一つであるパラメータ(以下、ROS 2パラメータ)を扱って、ソフトウェアアーキテクチャの中に組み込んでいきます。

前回の記事↓ odome.hatenablog.com

開発リポジトリgithub.com

ROS 2パラメータって何さ?

 一言で言えば、ノードが持てる設定値、みたいなものです。起動時に値を受け取るなどすることでパラメータを持つことができ、他ノードのパラメータを取得、変更することもできます。以下のような特徴が挙げられます。

  • ノードの起動時に、引数としてパラメータの設定(宣言&初期化)を与えることができる。引数には、ROS 2パラメータが記されたYAMLファイルも渡せる。
  • ノード内で利用するには、パラメータの宣言と初期値の定義が必要である(NodeOptionsでの設定で無視することもできる)。
  • 他ノードの特定パラメータの値を、Service通信を利用して取得することができる。また、変更することも可能である。
  • コマンドラインから、全パラメータ名の取得や特定パラメータの値を取得、変更が行える。

Image of ROS 2 Parameter (個人的なイメージです。厳密には違うかも)

何が良いのさ?

 上記の特徴を持つROS 2パラメータの良さは、

  • ノードの起動時に、引数としてパラメータの設定(宣言&初期化)を与えることができる。

これが挙げられます。これを利用することによって、ノード内で利用される値を起動時に容易に定めることができ、ハードコーディングを避けることによる利便性の向上を図ることができます。特にYAMLファイルを渡すことが可能なので、YAMLファイルの変更のみでノードの挙動を変えることも可能となります。

どう活用していくのか?

 本ソフトウェア群でも、このROS 2パラメータの利点を有効に活用していきます。具体的には、以下を担わせます。

  • 制御パラメータなどをYAMLファイルに記述しROS 2パラメータとして扱うことによる、制御パラメータの変更容易性向上

歩行制御において、歩行周期や片足支持期間などの制御パラメータは頻繁に変更することになります。このことから変更容易性は高いに越したことはありません。

ROS 2パラメータを含んだソフトウェアアーキテクチャの思案

 以上を踏まえて、ROS 2パラメータを活用したソフトウェア構成イメージを以下に示します。

structure

 まず、制御パラメータなどをROS 2パラメータに対応したYAMLファイルに記述し、ノードであるParameter Serverで全YAMLファイルを読み込みます。そして、必要に応じて各ノードなどがParameter Serverから特定パラメータの値を取得する、という構成となっています。

この構成の検討箇所と取捨選択を示します。

  • Parameter ServerでROS 2パラメータを一括管理することで、構成内の依存関係を単純化
    • Parameter Serverが単一障害点となってしまうことに加えて各ノードが単独でパラメータを取得することも可能であるが、複数ノードで扱うパラメータ(歩行周期など)が同じ場合が存在することや依存関係の単純化による管理のしやすさを高く評価したため、この構成を採用した。
  • ROS 2パラメータの定義はYAMLファイルにて実装
    • 制御パラメータの数が多いことや今後も増えることを鑑みると、launchファイル内でParameter Serverノードに引数として直接パラメータの定義を渡すよりもYAMLファイルとして記述するほうが、利便性などの観点から良いと判断した。

 この構成イメージをもとに、実装を行いました。

実装

 まず、現時点(2024年1月31日)で実装しているYAMLファイルの一覧(リポジトリディレクトリ構造も含めて)を示します。

  • robot_bringup/: システムの起動および実行などを行うパッケージ
    • config/: ROS 2パラメータのYAMLファイルを持つディレクト
      • param_control.yaml: 歩行制御に関するパラメータを持つYAMLファイル
      • param_debug_mode.yaml: データの可視化や記録を行うモード(デバッグモード)を設定するパラメータを持つYAMLファイル
      • param_mode_switch.yaml: デバッグモードの利用の有無など、動作の切り替えを行うパラメータを持つYAMLファイル
      • param_robot_description.yaml: 利用するロボットモデルの名前やURDFファイルのパスなどのパラメータを持つYAMLファイル

(source: ROS2_Walking_Pattern_Generator/robot_bringup/config at devel · open-rdc/ROS2_Walking_Pattern_Generator · GitHub )

  • robot_description/: ロボットモデルのデータを持つパッケージ
    • config/: ロボットモデルのROS 2パラメータのYAMLファイルを持つディレクト
      • robotis_op2/: ROBOTIS OP2のURDFをもとに生成されたYAMLファイルを持つディレクト
        • param_robotis_op2_joints.yaml: 全Jointの各種情報をROS 2パラメータとして持つYAMLファイル
        • param_robotis_op2_limb.yaml: 四肢および首などのツリー構造の枝に当たる部分の各種情報を持つYAMLファイル。joint_stateトピックで利用可能
        • param_robotis_op2_name_lists.yaml: 全Jointなどの名前を持つYAMLファイル

(source: ROS2_Walking_Pattern_Generator/robot_description/config/robotis_op2 at devel · open-rdc/ROS2_Walking_Pattern_Generator · GitHub )

 なお、robot_descriptionが持つYAMLファイルは、robot_tools/robot_tools/model_parameter_generator.pyによって、URDFファイルから生成されたものです。この生成スクリプトの詳細については、ここでは省きます。

 次に、Parameter Serverのコードの一部を示します。

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

  rclcpp::NodeOptions opt;
  opt.automatically_declare_parameters_from_overrides(true);  // ROS 2パラメータを定義しなくてもget_parameterできるようにする設定

  rclcpp::spin(std::make_shared<ParameterServer>(opt));

  rclcpp::shutdown();

  return 0;
}
  • Get Parameters
      // mode_switch
      on_or_offline_pattern_generate_ = get_parameter("mode_switch.on_or_offline_pattern_generate").as_bool();  // ROS 2パラメータの取得。.as_<>() で型を明示する必要がある。
      debug_mode_ = get_parameter("mode_switch.debug_mode").as_bool();
      using_simulator_ = get_parameter("mode_switch.using_simulator").as_bool();

(source: ROS2_Walking_Pattern_Generator/robot_bringup/src/ParameterServer.cpp at devel · open-rdc/ROS2_Walking_Pattern_Generator · GitHub )

 ROS 2パラメータを通信により他ノードから取得する際は、Service通信とは記述が異なります。Server側で特に記述することはなく、Client側で以下のようにすることで取得することができます。

    node_ptr_ = rclcpp::Node::make_shared("RobotManager");
    client_param_ = std::make_shared<rclcpp::SyncParametersClient>(node_ptr_, "RobotParameterServer");  // 他ノードのROS 2パラメータを取得するために必要な変数。
    // param: mode_switch
    ONLINE_OR_OFFLINE_GENERATE_ = client_param_->get_parameter<bool>("mode_switch.on_or_offline_pattern_generate");  // 他ノードのROS 2パラメータを取得
    DEBUG_MODE_ = client_param_->get_parameter<bool>("mode_switch.debug_mode");
    USING_SIMULATOR_ = client_param_->get_parameter<bool>("mode_switch.using_simulator");

(source: ROS2_Walking_Pattern_Generator/robot_manager/src/robot_manager.cpp at devel · open-rdc/ROS2_Walking_Pattern_Generator · GitHub )

最後に

 今回は、ROS 2パラメータを利用して制御パラメータなどを容易に変更可能にする取り組みを行いました。まだROS 2パラメータ化していないものもあったりするので、今回示したものをアップデートしていきます。

開発リポジトリgithub.com