View on GitHub

introduction-to-ros

ROS (Robot Operating System) 入門

rosparam

前のページ

目次

概要

外部からパラメータの値を受け取れるようなROSノードの書き方について説明します.

前のページで作成したpublisherにパラメータを受け取る記述を追加して,送信する文字列をパラメータで指定可能なようにしましょう.

my_simple_publisher.cpp

#include <ros/ros.h>
#include <std_msgs/String.h>

int main(int argc, char **argv)
{
    ros::init(argc, argv, "my_simple_publisher");
    ros::NodeHandle nh;
    
    // added
    ros::NodeHandle pnh("~");
    std::string pub_string = "hello world";
    pnh.getParam("pub_string", pub_string);

    ros::Publisher simple_pub = nh.advertise<std_msgs::String>("my_topic", 1);
    ros::Rate loop_rate(10);

    while (ros::ok())
    {
        std_msgs::String msg;
        msg.data = pub_string;
        ROS_INFO("publish: %s", msg.data.c_str());
        simple_pub.publish(msg);

        ros::spinOnce();
        loop_rate.sleep();
    }
    return 0;
}

各行の意味

ros::NodeHandle pnh("~");
std::string pub_string = "hello world";
pnh.getParam("pub_string", pub_string);

動作確認

ビルド

catkin build

実行

roscore

したうえで別ターミナルで

rosrun my_ros_tutorial my_simple_publisher _pub_string:="hoge"

すると出力が以下のようになるはず

decwest@DESKTOP-PRFDO60:~/catkin_ws$ rosrun my_ros_tutorial my_simple_publisher _pub_string:="hoge"
[ INFO] [1632634919.572324700]: publish: hoge
[ INFO] [1632634919.672427100]: publish: hoge
[ INFO] [1632634919.772410900]: publish: hoge
[ INFO] [1632634919.872397500]: publish: hoge
[ INFO] [1632634919.972398900]: publish: hoge

演習問題2

上記のpublisherのループ周波数をパラメータで変更できるようにしよう

解答例

リンク

次のページ

目次


余談

パラメータサーバについて

ROSはパラメータをパラメータサーバというもので管理しています.パラメータの値と名前が保存されていて,適宜パラメータの名前と値をサーバーに登録したり,読み出したりします. 興味のある方はこのROS Wikiを見てください.

パラメータの登録にはコマンドラインツール,rosrunのオプション(今回扱ったやつ),launchファイルでの指定(次のページで扱う)等があります.

Dynamic reconfigure

ROSのパラメータは基本的には静的で,一度登録したら値の書き換えができません.しかし,dynamic reconfigureというものを用いれば途中で値の変更が可能な動的なパラメータを作成することができます. こちらがわかりやすいです.

名前空間について

興味のある方はこのROS Wikiを見てください.

rosrunオプション

今回,以下のようにしてノードにパラメータを渡したと思います.

rosrun my_ros_tutorial my_simple_publisher _pub_string:="hoge"

ここで,_の数によって何の名前に関するものを設定するのかが変わります.