クラスでのパラメータの使用 (C++)
目標: C++を使用してROSパラメータを持つクラスを作成し実行する。
チュートリアルレベル: 初心者
所要時間: 20分
背景
独自のノードを作成する際、ローンチファイルから設定できるパラメータを追加する必要がある場合があります。
このチュートリアルでは、C++クラスでそれらのパラメータを作成する方法と、ローンチファイルでそれらを設定する方法を示します。
前提条件
これまでのチュートリアルで、ワークスペースの作成とパッケージの作成の方法を学びました。 また、パラメータとROS 2システムでのその機能についても学びました。
タスク
1 パッケージの作成
新しいターミナルを開き、ROS 2インストレーションをソースしてros2コマンドが機能するようにします。
これらの手順に従って、ros2_wsという名前の新しいワークスペースを作成します。
パッケージはワークスペースのルートではなく、srcディレクトリに作成する必要があることを思い出してください。 ros2_ws/srcに移動し、新しいパッケージを作成します:
ros2 pkg create --build-type ament_cmake --license Apache-2.0 cpp_parameters --dependencies rclcppターミナルには、パッケージcpp_parametersとそのすべての必要なファイルとフォルダーの作成を確認するメッセージが返されます。
--dependencies引数により、package.xmlとCMakeLists.txtに必要な依存関係行が自動的に追加されます。
1.1 package.xmlの更新
パッケージ作成時に--dependenciesオプションを使用したため、package.xmlやCMakeLists.txtに手動で依存関係を追加する必要はありません。
ただし、いつものように、package.xmlに説明、メンテナーのメールアドレスと名前、ライセンス情報を追加してください。
<description>C++ parameter tutorial</description>
<maintainer email="you@email.com">Your Name</maintainer>
<license>Apache License 2.0</license>2 C++ノードの記述
ros2_ws/src/cpp_parameters/srcディレクトリ内で、cpp_parameters_node.cppという新しいファイルを作成し、以下のコードを貼り付けます:
#include <chrono>
#include <functional>
#include <string>
#include <rclcpp/rclcpp.hpp>
using namespace std::chrono_literals;
class MinimalParam : public rclcpp::Node
{
public:
MinimalParam()
: Node("minimal_param_node")
{
this->declare_parameter("my_parameter", "world");
timer_ = this->create_wall_timer(
1000ms, std::bind(&MinimalParam::timer_callback, this));
}
void timer_callback()
{
std::string my_param = this->get_parameter("my_parameter").as_string();
RCLCPP_INFO(this->get_logger(), "Hello %s!", my_param.c_str());
std::vector<rclcpp::Parameter> all_new_parameters{rclcpp::Parameter("my_parameter", "world")};
this->set_parameters(all_new_parameters);
}
private:
rclcpp::TimerBase::SharedPtr timer_;
};
int main(int argc, char ** argv)
{
rclcpp::init(argc, argv);
rclcpp::spin(std::make_shared<MinimalParam>());
rclcpp::shutdown();
return 0;
}2.1 コードの説明
上部の#include文はパッケージの依存関係です。
次のコード部分では、クラスとコンストラクタを作成します。 このコンストラクタの最初の行では、my_parameterという名前のパラメータをデフォルト値worldで作成します。 パラメータタイプはデフォルト値から推定されるため、この場合は文字列タイプに設定されます。 次に、timer_が1000msの周期で初期化され、timer_callback関数が1秒に1回実行されます。
class MinimalParam : public rclcpp::Node
{
public:
MinimalParam()
: Node("minimal_param_node")
{
this->declare_parameter("my_parameter", "world");
timer_ = this->create_wall_timer(
1000ms, std::bind(&MinimalParam::timer_callback, this));
}timer_callback関数の最初の行では、ノードからパラメータmy_parameterを取得し、my_paramに格納します。 次に、RCLCPP_INFO関数がイベントをログに記録することを確実にします。 そしてset_parameters関数がパラメータmy_parameterをデフォルトの文字列値worldに戻します。 ユーザーが外部からパラメータを変更した場合、これは常に元の値にリセットされることを確実にします。
void timer_callback()
{
std::string my_param = this->get_parameter("my_parameter").as_string();
RCLCPP_INFO(this->get_logger(), "Hello %s!", my_param.c_str());
std::vector<rclcpp::Parameter> all_new_parameters{rclcpp::Parameter("my_parameter", "world")};
this->set_parameters(all_new_parameters);
}最後はtimer_の宣言です。
private:
rclcpp::TimerBase::SharedPtr timer_;MinimalParamの後に続くのはmain関数です。 ここでROS 2が初期化され、MinimalParamクラスのインスタンスが構築され、rclcpp::spinがノードからのデータ処理を開始します。
int main(int argc, char ** argv)
{
rclcpp::init(argc, argv);
rclcpp::spin(std::make_shared<MinimalParam>());
rclcpp::shutdown();
return 0;
}2.1.1 (オプション)ParameterDescriptorの追加
オプションとして、パラメータの記述子を設定することができます。 記述子により、パラメータのテキスト説明とその制約(読み取り専用にする、範囲を指定するなど)を指定できます。 これを機能させるには、コンストラクタのコードを以下のように変更する必要があります:
// ...
class MinimalParam : public rclcpp::Node
{
public:
MinimalParam()
: Node("minimal_param_node")
{
auto param_desc = rcl_interfaces::msg::ParameterDescriptor{};
param_desc.description = "This parameter is mine!";
this->declare_parameter("my_parameter", "world", param_desc);
timer_ = this->create_wall_timer(
1000ms, std::bind(&MinimalParam::timer_callback, this));
}コードの残りの部分は変わりません。 ノードを実行すると、ros2 param describe /minimal_param_node my_parameterを実行してタイプと説明を確認できます。
2.2 実行可能ファイルの追加
次にCMakeLists.txtファイルを開きます。 依存関係find_package(rclcpp REQUIRED)の下に以下のコード行を追加します。
add_executable(minimal_param_node src/cpp_parameters_node.cpp)
ament_target_dependencies(minimal_param_node rclcpp)
install(TARGETS
minimal_param_node
DESTINATION lib/${PROJECT_NAME}
)3 ビルドと実行
ワークスペース(ros2_ws)のルートでrosdepを実行して、ビルド前に不足している依存関係をチェックするのが良い習慣です:
rosdep install -i --from-path src --rosdistro humble -yワークスペースのルートros2_wsに戻り、新しいパッケージをビルドします:
colcon build --packages-select cpp_parameters新しいターミナルを開き、ros2_wsに移動し、セットアップファイルをソースします:
source install/setup.bash今度はノードを実行します。 ターミナルには毎秒Hello Worldメッセージが返されるはずです:
ros2 run cpp_parameters minimal_param_node
[INFO] [minimal_param_node]: Hello world!これでパラメータのデフォルト値を確認できますが、自分で設定できるようにしたいでしょう。 これを実現する方法は2つあります。
3.1 コンソール経由での変更
この部分では、パラメータについてのチュートリアルで得た知識を使用し、作成したノードに適用します。
ノードが実行されていることを確認してください:
ros2 run cpp_parameters minimal_param_node別のターミナルを開き、ros2_ws内から再度セットアップファイルをソースし、以下の行を入力します:
ros2 param listそこにカスタムパラメータmy_parameterが表示されます。 変更するには、コンソールで以下の行を実行します:
ros2 param set /minimal_param_node my_parameter earthSet parameter successfulの出力が得られれば成功です。 他のターミナルを見ると、出力が[INFO] [minimal_param_node]: Hello earth!に変わっているのを確認できるはずです。
3.2 ローンチファイル経由での変更
ローンチファイルでパラメータを設定することもできますが、まずlaunchディレクトリを追加する必要があります。 ros2_ws/src/cpp_parameters/ディレクトリ内で、launchという新しいディレクトリを作成します。 そこにcpp_parameters_launch.pyという新しいファイルを作成します:
from launch import LaunchDescription
from launch_ros.actions import Node
def generate_launch_description():
return LaunchDescription([
Node(
package='cpp_parameters',
executable='minimal_param_node',
name='custom_minimal_param_node',
output='screen',
emulate_tty=True,
parameters=[
{'my_parameter': 'earth'}
]
)
])ここでは、ノードminimal_param_nodeを起動する際にmy_parameterをearthに設定していることがわかります。 以下の2行を追加することで、出力がコンソールに印刷されることを確実にします。
output="screen",
emulate_tty=True,次にCMakeLists.txtファイルを開きます。 先ほど追加した行の下に、以下のコード行を追加します。
install(
DIRECTORY launch
DESTINATION share/${PROJECT_NAME}
)コンソールを開き、ワークスペースのルートros2_wsに移動し、新しいパッケージをビルドします:
colcon build --packages-select cpp_parameters次に新しいターミナルでセットアップファイルをソースします:
source install/setup.bash次に、作成したローンチファイルを使用してノードを実行します。 ターミナルには最初に以下のメッセージが返されるはずです:
ros2 launch cpp_parameters cpp_parameters_launch.py
[INFO] [custom_minimal_param_node]: Hello earth!以降の出力では毎秒[INFO] [minimal_param_node]: Hello world!が表示されるはずです。
まとめ
ローンチファイルまたはコマンドラインから設定できるカスタムパラメータを持つノードを作成しました。 依存関係、実行可能ファイル、ローンチファイルをパッケージ設定ファイルに追加して、それらをビルドして実行し、パラメータの動作を確認できるようにしました。
次のステップ
今度は独自のパッケージとROS 2システムがいくつかあるので、次のチュートリアルでは、問題が発生した場合に環境とシステムの問題を調査する方法を示します。