🌎

ROS 2: persist_parameter_serverでパラメータを変更する

2024/09/13に公開

海洋ロボコンをやってた人です。
今回はROS 2のパラメータについて、備忘録として記載しておきます。

ROS 2である制御を実装しているときに、パラメータを別々の機能(Client A, B)からそれぞれ個別にアクセスして変化させたいということがあります。

そこで、利用できる方法やパッケージがないかを調べたのが背景になります。

以下箇条書きになりますが、何卒宜しくお願い致します。

また、誤記等あればご指摘ください。

メインはros2_persist_parameter_serverを、サブでgenerate_parameter_library を記載します。


使用する環境は以下です。

OS: Ubuntu 22.04LTS
ROS Distro: Humble

1. ros2_persist_parameter_server

1.1 Setup persist_parameter_server

まずはros2_persist_parameter_serverから記載します。

使用するPKGはForkした以下を使用します。

https://github.com/tasada038/ros2_persist_parameter_server

ROS 2のPersistent Parameter Serverは、パラメータを読み書きできるノードで、yamlファイルに永続的にパラメータを保存できるPersistent Parameterとサーバー起動時のみパラメータを非永続で保存するNot Persistent Parameterの2つに分類されます。

詳細は以下でも解説されていますが、学習率など永続的に保存したいパラメータをROS経由で扱う場合には適していると考えれます。

https://www.theconstruct.ai/learn-how-to-persist-ros2-params/

依存関係として、以下のパッケージを事前にインストールしておきます。

terminal
apt install libyaml-cpp-dev libboost-program-options-dev libboost-filesystem-dev

本家をCloneする場合は以下を、私の方で本記事用にアレンジしたものを使用する場合は上記をCloneしてください。(ここでは本家を記載しておきます)

terminal
cd ~/test_ws/src
git clone https://github.com/fujitatomoya/ros2_persist_parameter_server.git
cd ~/test_ws
colcon build
source install/setup.bash

1.2 Parameter set

クローンし準備ができたら、パラメータを変更しながら動作確認します。

terminal
ros2 run parameter_server server -f /home/ubuntu/test_ws/persistent_parameters.yaml

-f 以降はパラメータファイルの保存先です。 上の場合はtest_ws下に配置となります。

また、この参照先は既存のファイルも選択可能です。

terminal
ros2 param set /parameter_server persistent.some_int 9
ros2 param set /parameter_server persistent.pi 3.14

上述でパラメータセットを行います。

param setしたパラメーターがパラメーターサーバーに追加されていることが確認できます。

Ctrl + C を押すと、parameter_server を起動するときに指定したパスへパラメーターyamlが生成・保存されていることも確認できます。

1.3 Parameter load

1.2 でSetしたパラメータ先でもう一度起動してみます。

するとすでに登録されているパラメーターを読み込んでサーバーが起動することが確認できます。

また以下のように、parameters.yamlを準備しておき指定したパスで起動することも可能です。

terminal
ros2 run parameter_server server -f /home/ubuntu/test_ws/src/ros2_persist_parameter_server/server/param/parameter_server.yaml


ros2_persist_parameter_serverパッケージのserver/param フォルダ下のparameter_server.yamlを起動すると、以下のようなパラメータも確認できます。

デフォルトで用意されているパラメータ.yamlには冒頭で紹介したようにパラメータが2種類定義されています。

  • persistent:
    永続的パラメータで、Ctrl + Cなどでタスクを終了した場合でもパラメータが保存される

  • Not persistent:
    非永続パラメータで、タスク終了とともに値がもとに戻り、保存されない

試しに以下を実施して確認してみると

terminal
ros2 param get /parameter_server some_int
Integer value is: 9
ros2 param get /parameter_server persistent.some_int
Integer value is: 9

# Ctrl + C 後再度server起動
ros2 param get /parameter_server some_int
Integer value is: 1

となることが確認できます。

1.4 Multiple Client Sample

1.1 Setupで紹介した、Frokリポジトリを使用して、複数のClientから Global Parameters Serverにアクセスして、それぞれのClientからグローバルパラメータをGet/Setしてみます。

ClientANode

まずはClient A Nodeの永続的パラメータを5s毎に更新するソースを作成します。

  • Purpose: Updates persistent.some_int parameter every 5 seconds.
  • Functionality: Uses AsyncParametersClient to set new values for these parameters.
client_a.cpp
//------------------------------------------------------------------------------------
//----------------------------------- Include ----------------------------------------
//------------------------------------------------------------------------------------
#include "rclcpp/rclcpp.hpp"
#include <memory>  // For std::shared_ptr
#include <vector>  // For std::vector
#include <chrono>  // For std::chrono literals

using namespace std::chrono_literals;  // Enables 1s, 500ms, etc.


//------------------------------------------------------------------------------------
//----------------------------------- Class ------------------------------------------
//------------------------------------------------------------------------------------
class ClientANode : public rclcpp::Node
{
public:
    ClientANode()
    : Node("client_a_node")
    {
        // Create a parameter client to interact with the parameter server
        parameters_client = std::make_shared<rclcpp::AsyncParametersClient>(this, "/parameter_server");

        // Wait for the parameter server to be available before proceeding
        parameters_client->wait_for_service();

        // Set up a periodic timer to update the parameter every 5 seconds
        timer_ = this->create_wall_timer(
            5s,  // Update every 5 seconds
            std::bind(&ClientANode::updateSomeIntParameter, this));
    }

/**
 * @brief Periodically updates the 'persistent.some_int' parameter by incrementing its value.
 */
    void updateSomeIntParameter()
    {
        // Fetch the current value of 'persistent.some_int'
        auto parameters_future = parameters_client->get_parameters(
            {"persistent.some_int"},
            std::bind(&ClientANode::callbackParamServer, this, std::placeholders::_1));
    }

/**
 * @brief Callback function to handle the result from the parameter server.
 *        This retrieves the current value of the parameter and increments it.
 * @param future Future object containing the fetched parameters from the server.
 */
    void callbackParamServer(std::shared_future<std::vector<rclcpp::Parameter>> future)
    {
        auto result = future.get();

        if (!result.empty()) {
            // Extract the current value of the 'persistent.some_int' parameter
            int64_t current_value = result.at(0).as_int();
            RCLCPP_INFO(this->get_logger(), "Current 'persistent.some_int': %ld", current_value);

            // Increment the value and update it back to the server
            int64_t new_value = current_value + 1;
            parameters_client->set_parameters({rclcpp::Parameter("persistent.some_int", new_value)});
            RCLCPP_INFO(this->get_logger(), "Updated 'persistent.some_int' to: %ld", new_value);
        } else {
            RCLCPP_ERROR(this->get_logger(), "Failed to get 'persistent.some_int' parameter.");
        }
    }


private:
    std::shared_ptr<rclcpp::AsyncParametersClient> parameters_client;  ///< Client for interacting with the parameter server
    rclcpp::TimerBase::SharedPtr timer_;  ///< Timer to trigger the periodic parameter update
};


//------------------------------------------------------------------------------------
//----------------------------------- Main Function ----------------------------------
//------------------------------------------------------------------------------------
int main(int argc, char * argv[])
{
    rclcpp::init(argc, argv);

    // Spin the node to continuously run
    rclcpp::spin(std::make_shared<ClientANode>());

    rclcpp::shutdown();
    return 0;
}

Global Parameter Serverは1.3 Parameter loadで読み込んだものを使用し、Clientノードを実行してみます。

ros2 run ros2_persistent_parameter_server_test client_a_node

以下のようにClientノードから、Global Parameter Serverのパラメータを変更できることが確認できます。

https://twitter.com/tasada038/status/1832737959533318183

2. generate_parameter_library

2.1 Setup generate_parameter_library

続いて、generate_parameter_libraryも見ていきます。インプット資料は以下となります。

https://github.com/PickNikRobotics/generate_parameter_library

https://github.com/NITKK-ROS-Team/generate_parameter_library_example

こちらはapt installでインストールします。

sudo apt install ros-humble-generate-parameter-library

2.1 Build & Run generate_parameter_library

configのパラメータを決めて、そのパッケージをビルドする

sample_params
    config/xxx_controller_parameters.yaml
    CMakeLists.txt
    packages.yaml

これをビルドすると実態は
/xxx_ws/include/${PROJECT_NAME}/include/xxx_controller_parameters/xxx_controller_parameters.hpp
へ生成される

これを利用するには以下のような任意のROS 2パッケージを作成し

test_pkg
  src
    任意のソースファイル名
  include/任意のヘッダーファイル名.hpp

任意のヘッダーファイル名.hppで、ビルドして生成した実態であるxxx_controller_parameters.hppを呼び出すことで利用できる。

つまりパラメータジェネレーター用は一つのパッケージとして分離して管理でき、パラメータをライブラリとして利用できるといえます。

ament_cmakeの場合、依存関係をうまく解決しないと、実態のあるincludeディレクトリを読み込めないことあるので依存関係の記載には注意してください。

Reference

参考サイトは以下となります。
著者の皆様、分かりやすい解説をしていただきありがとうございます。

https://ar-ray.hatenablog.com/entry/2023/07/22/193200

https://www.youtalk.jp/2017/06/20/ros2-parameter.html


今回は以上です。
Likeいただけると大変励みになりますので、よろしくお願いいたします。

Discussion