9
9

Delete article

Deleted articles cannot be recovered.

Draft of this article would be also deleted.

Are you sure you want to delete this article?

More than 1 year has passed since last update.

ROS講座78 rosparamを使う2

Last updated at Posted at 2019-03-23

環境

この記事は以下の環境で動いています。

項目
CPU Core i5-8250U
Ubuntu 20.04
ROS Noetic

インストールについてはROS講座02 インストールを参照してください。
またこの記事のプログラムはgithubにアップロードされています。ROS講座11 gitリポジトリを参照してください。

概要

前回は基本的なint型のparameterを読み込みましたが、rosparamでは辞書型やリスト型も使えます。これらの型のrosparamをROSノードで使う方法を解説します。

ソースコード

yamlファイル

今回読み込むパラメーターを記述したファイルです。以下の様にリスト型があり、そのアイテムが辞書型になっています。

adv_lecture/config/param2_config
member_list:
  - name: aaa
    id: 1
  - name: bbb
    id: 2
  - name: ccc
    id: 3

launch

adv_lecture/launch/rosparam2.launch
<launch>
  <node name="adv_param2_display" pkg="adv_lecture" type="adv_param2_display" output="screen">
    <rosparam command="load" file="$(find adv_lecture)/config/param2_config.yaml"/>
  </node>
</launch>

先ほどのyamlファイルをロードしています。

ソースコード(rosノード)

adv_lecture/src/adv_param2_display.cpp
#include <ros/ros.h>

int main(int argc, char** argv)
{
  ros::init(argc, argv, "param_sample");
  ros::NodeHandle nh;
  ros::NodeHandle pnh("~");

  XmlRpc::XmlRpcValue member_list;
  pnh.getParam("member_list", member_list);
  ROS_ASSERT(member_list.getType() == XmlRpc::XmlRpcValue::TypeArray);
  ROS_INFO("member size: %i", (int)member_list.size());
  for (int32_t i = 0; i < member_list.size(); ++i)
  {
    ROS_INFO("read [%i]", i);
    int id = 0;
    std::string name = "";
    if (!member_list[i]["id"].valid() || !member_list[i]["name"].valid())
    {
      ROS_WARN("No id or name");
      continue;
    }
    if (member_list[i]["id"].getType() == XmlRpc::XmlRpcValue::TypeInt)
      id = static_cast<int>(member_list[i]["id"]);
    if (member_list[i]["name"].getType() == XmlRpc::XmlRpcValue::TypeString)
      name = static_cast<std::string>(member_list[i]["name"]);
    ROS_INFO("[%i] id: %i, name: %s", i, id, name.c_str());
  }
  return 0;
}
  • XmlRpc::XmlRpcValue member_list; pnh.getParam("member_list", member_list);でxmlrpc形式で読み込みます。
  • 辞書やリストにはmember_list[i]["id"]のように添え字でアクセスします。
  • getType()でその値の型を判別します。TypeInvalid, TypeBoolean, TypeInt, TypeDouble, TypeString, TypeArrayなどがあります。
  • リスト型なら.size()でサイズを取得できます。
  • 辞書型なら.valid()でそのキーがあるかどうかを判定します。
  • 値を読むときはstatic_cast<int>()のようにキャストします。

ビルド

cd ~/catkin_ws
catkin_make

実行

各ターミナルごとに実行前にsource ~/catkin_ws/devel/setup.bashを実行する必要があります。

roslaunch adv_lecture rosparam2.launch 

以下のように表示されるはずです。

結果
[ INFO] [1588423525.235388960]: member size: 3
[ INFO] [1588423525.235467370]: read [0]
[ WARN] [1588423525.235506030]: No id or name
[ INFO] [1588423525.235519417]: read [1]
[ INFO] [1588423525.235534347]: [1] id: 1, name: bbb
[ INFO] [1588423525.235543629]: read [2]
[ INFO] [1588423525.235553543]: [2] id: 2, name: ccc

補足

  • XmlRpc::XmlRpcValue::getType()で判定できる値として以下があります(本当はもう少しありますが、ROSで出てくるのはこれぐらい)。
    • TypeBoolean
    • TypeInt
    • TypeDouble
    • TypeString
    • TypeArray
    • TypeStruct
  • TypeArrayやTypeStructは範囲for文が使えます

参考

rosparamタグ
parameter_server

目次ページへのリンク

ROS講座の目次へのリンク

9
9
0

Register as a new user and use Qiita more conveniently

  1. You get articles that match your needs
  2. You can efficiently read back useful information
  3. You can use dark theme
What you can do with signing up
9
9

Delete article

Deleted articles cannot be recovered.

Draft of this article would be also deleted.

Are you sure you want to delete this article?