【ROS2関係トップページへ】
【ROS2レクチャー:初級 -class style-】
【前:ROS2のparameter概要】
【次:YAMLファイルによるROS2のパラメータ設定】
ここではparameterに関するservice側とclietn側のプログラムを作成する.
clientのプログラムとしては非同期に取得・設定を行うAsyncParameterClientと同期的に行うSyncParameterClientがある.ここでは同期型のSyncParameterClientを紹介する.
基本的な機能は,パラメータの宣言・値の設定・取得となり,それぞれ以下の関数となる.詳しくは以下の通り.
- 宣言
- declare_parameter
- パラメータの宣言
- dashing diademataから宣言なしでは値の設定・取得ができなくなった(参考).これにより「パラメータの名前を打ち間違っちゃって似た名前のものが複数できる」などがなくなった.
- undeclare_parameter
- パラメータの無効化
- has_parameter
- パラメータの存在確認
- declare_parameter
- 値の設定
- set_parameters
- 値の取得
- get_parameter
- get_parameters
ROS2のparameter概要の記載通りserviceとしてのparameterとclientとしてのparameterがあるので公式のAPIのrclcpp::NodeとParameters:に記載がある.
[公式のRoadmap][]に詳しく書いてある.
parameter serviceについてはfuture worksで.
準備
$ cd ~/ros2_studies_ws/
$ ros2 pkg create minimal_parameter_class --dependencies rclcpp
Parameter service側
作成物:
- src/minimal_parameter_holder.hpp
- パラメータを保持するnodeのヘッダ
- node名: param_holder
- src/minimal_parameter_holder.cpp
- パラメータを保持するnodeのヘッダ
- src/minimal_parameter_holder_main.cpp
- パラメータを保持するnodeのターゲット
プログラム : src/minimal_parameter_holder.hpp
#include <rclcpp/rclcpp.hpp>
class MinimalParameterHolder : public rclcpp::Node{
public:
MinimalParameterHolder(
const std::string& name_space="",
const rclcpp::NodeOptions& options = rclcpp::NodeOptions()
);
};
概要
コンストラクタのみ.
プログラム : src/minimal_parameter_holder.cpp
#include <rclcpp/rclcpp.hpp>
#include "minimal_parameter_holder.hpp"
MinimalParameterHolder::MinimalParameterHolder(
const std::string& name_space,
const rclcpp::NodeOptions& options
): Node("param_holder",name_space,options){
using namespace std::chrono_literals;
auto param1 = declare_parameter("foo",0);
auto param2 = declare_parameter("bar", "ok");
auto results = set_parameters({
rclcpp::Parameter("foo",2),
rclcpp::Parameter("bar","hello")
});
}
概要
ROS風と同様に,declareして設定.
プログラム : src/minimal_parameter_holder_main.cpp
#include <rclcpp/rclcpp.hpp>
#include "minimal_parameter_holder.hpp"
int main(int argc, char * argv[]){
rclcpp::init(argc, argv);
rclcpp::spin(std::make_shared<MinimalParameterHolder>());
rclcpp::shutdown();
return 0;
}
Parameter 同期client側
作成物:
- src/minimal_param_client.hpp
- 同期クライアントのnodeのヘッダ
- node名: param_client
- src/minimal_param_client.cpp
- 同期クライアントのnodeのヘッダ
- src/minimal_param_client_main.cpp
- 同期クライアントのnodeのターゲット
プログラム : src/minimal_param_client.hpp
#include <rclcpp/rclcpp.hpp>
class MinimalParamClient : public rclcpp::Node{
private:
rclcpp::SyncParametersClient::SharedPtr param_;
public:
MinimalParamClient(
const std::string& name_space="",
const rclcpp::NodeOptions& options = rclcpp::NodeOptions()
);
};
概要
サービス側と異なるところはSyncParametersClientのポインタを宣言しているところ.これはparameter serviceに接続するための情報を持つもので,parameter clientとしては必須.
プログラム : src/minimal_param_client.cpp
#include <rclcpp/rclcpp.hpp>
#include "minimal_param_client.hpp"
MinimalParamClient::MinimalParamClient(
const std::string& name_space,
const rclcpp::NodeOptions& options
): Node("param_client",name_space,options){
using namespace std::chrono_literals;
param_ = std::make_shared<rclcpp::SyncParametersClient>(this,"param_holder");
std::stringstream ss;
while(!param_->wait_for_service(1s)){
RCLCPP_INFO(this->get_logger(), "waiting for service");
}
auto parameters_get_results = param_->get_parameters({"foo", "bar"});
for(auto ¶m : parameters_get_results){
ss << "\nParameter name:" << param.get_name();
ss << "\nParameter type:" << param.get_type_name();
ss << "\nParameter value:" << param.value_to_string();
}
RCLCPP_INFO(this->get_logger(), ss.str().c_str());
ss.str("");
ss.clear(std::stringstream::goodbit);
auto list_results = param_->list_parameters({"foo","bar"},10);
for(auto ¶m_name : list_results.names){
ss << "\n" << param_name;
}
for(auto &prefix : list_results.prefixes){
ss << "\n" << prefix;
}
RCLCPP_INFO(this->get_logger(), ss.str().c_str());
ss.str("");
ss.clear(std::stringstream::goodbit);
auto parameter_set_results = param_->set_parameters({
rclcpp::Parameter("foo",3),
rclcpp::Parameter("bar","welcome")
//rclcpp::Parameter("bar",10) // OK:別種のものを代入することは可能
// rclcpp::Parameter("hoge","hige") // NG:パラメータを増やしても無効?
});
for(auto &result : parameter_set_results){
if(!result.successful){
RCLCPP_ERROR(this->get_logger(), "Failed to set parameter: %s", result.reason.c_str());
}
}
parameters_get_results = param_->get_parameters({"foo", "bar"});
for(auto ¶m : parameters_get_results){
ss << "\nParameter name:" << param.get_name();
ss << "\nParameter type:" << param.get_type_name();
ss << "\nParameter value:" << param.value_to_string();
}
RCLCPP_INFO(this->get_logger(), ss.str().c_str());
ss.str("");
ss.clear(std::stringstream::goodbit);
}
概要
param_holderに接続し,そのnodeが持っているパラメータを参照・変更・また参照するプログラム.
パラメータを取得・変更する場合,パラメータを保持しているnodeと接続しなければいけない.そのため,9行目のようにparameter clientとしての設定を行っている.引数は二つであり,一つ目がSyncParametersClientの機能を持たせるnodeへのポインタ,二つ目がparameterのデータを保持しているparameter nodeの名前(serviceとなるnodeの名前)である.
同期型なので,spin関数を用いなくてもget_parametersやset_parametersなどを実行したらすぐに取得・設定が行われる.
またget_parameter(get_parameters)で得られた返り値は型や名前など色々な情報を含む.パラメータの値そのものを得るためには,param.value_to_string()などの関数を使用する.代表的なものは以下の通り.その他は公式のAPIのrclcpp::Parameterを参照.
param.as_bool()
param.as_int()
param.as_double()
param.as_string()
説明
9行目:SyncParametersClientとして設定.二つ目の引数で参照するparameter nodeの名前を渡している.
10~17行目:parameterの取得,表示.
19~28行目:parameterのlist.詳細情報?20行目の二つ目の引数10は深さで,対象parameterの名前を深さ10まで取得するらしい.
30~41行目:paramter設定.値を変えることは可能(30,31行目).また値の種類を超えて変えることも可能(34行目).しかし新しいキーを設定することはできない模様(エラーにはならない).
43~52行目:parameter取得.
プログラム : src/minimal_param_client_main.cpp
#include <rclcpp/rclcpp.hpp>
#include "minimal_param_client.hpp"
int main(int argc, char * argv[]){
rclcpp::init(argc, argv);
rclcpp::spin(std::make_shared<MinimalParamClient>());
rclcpp::shutdown();
return 0;
}
package.xmlとCMakeLists.txt
<package format="3">
<depend>rclcpp></depend>
find_package(rclcpp REQUIRED)
add_executable(minimal_parameter_holder_test
src/minimal_parameter_holder_main.cpp
src/minimal_parameter_holder.cpp
)
ament_target_dependencies(minimal_parameter_holder_test
rclcpp
)
add_executable(minimal_parameter_client_test
src/minimal_param_client_main.cpp
src/minimal_param_client.cpp
)
ament_target_dependencies(minimal_parameter_client_test
rclcpp
)
install(TARGETS
minimal_parameter_holder_test
minimal_parameter_client_test
DESTINATION lib/${PROJECT_NAME}
)
ビルド・実行
ビルド
$ cd ~/ros2_studies_ws/
$ colcon build --symlink-install --packages-up-to minimal_parameter_class
$ . install/local_setup.bash
実行
param_holderとuser用のterminalを起動.
$ cd ~/ros2_studies_ws/
$ . install/local_setup.bash
$ ros2 run minimal_parameter_class minimal_parameter_holder_test
$ cd ~/ros2_studies_ws/
$ . install/local_setup.bash
$ ros2 run minimal_parameter_class minimal_parameter_client_test
terminal2に出てくるメッセージを見て考える.
またterminal1のparam_holderを終了させないまま,async_userを2回,3回実行させると結果はどうなるか?
メモ
parameterはserviceを提供する側とサービスを提供されるclient側がある.parameterの値を保持し他に与えるnodeはserviceとなり,それを参照したり値を変更したりするものがclientとなる.clientが他のnodeの場合,「serviceを行うnodeはだれか?」という名前の情報が必要である.一方で,自身で自身のparameterを使用する場合(つまりservice=clientとなる場合),別に名前を知る必要はなく,自分のparameterにアクセスすればよいだけである.このことから,service≠clientの場合,clientはAsyncClientsParameterとしてparameter clientの機能を持ち,serviceに接続しなければいけない.一方,service=clientの場合,自分のparameterにアクセスするのでnode->get_parameterやthis->parameter,はてはget_parameterのみでアクセスできる.
つまり同一nodeの場合,「他のノードのparameter機能に接続してパラメータをいじる」ではなく,「nodeのパラメータに直接アクセス」になる.よってこの場合,wait_for_serviceしなくていいんじゃなかろうか.いいんです.