C++で作ったROS 1のパッケージをROS 2に移植するときのつまづきポイント ―その1(2があるかどうかは不明)

Tue Apr 23 15:35:13 JST 2024 (modified: Tue Apr 23 23:12:25 JST 2024)
views: 968, keywords:ROS 2

 https://github.com/ryuichiueda/value_iterationhttps://github.com/ryuichiueda/value_iteration2 に移植中です。前回に引き続き、困った点についてメモ。

CMakeLists.txt どうやって書くの?

 上田研の有志のみなさんがROS 2に移植したemcl2(emcl2_ros2: https://github.com/CIT-Autonomous-Robot-Lab/emcl2_ros2 ) のCMakeLists.txt が参考になりました。無茶振りして知見だけもらって申し訳ないですありがとうございます。 転載してコメントいれさせてもらいます。これ見てたらメシ代請求してください。


   cmake_minimum_required(VERSION 3.8)
   project(emcl2)
   
   if(NOT CMAKE_CXX_STANDARD)
     set(CMAKE_CXX_STANDARD 17)   #この前後3行はいらないかも
   endif()
   
   if(CMAKE_COMPILER_IS_GNUCXX OR CMAKE_CXX_COMPILER_ID MATCHES "Clang")
     add_compile_options(-O3 -Wall -Wextra -Wpedantic)  #Clangかg++に渡すオプション
   endif()
   
   find_package(ament_cmake_auto REQUIRED) #ament_cmake_autoというパッケージを
                                           #使うとpackage.xmlに書いたパッケージを
   ament_auto_find_build_dependencies()    #探してくれるっぽい
   
   ament_auto_add_executable(emcl2_node
     src/Mcl.cpp                           #.cppファイルをここに並べる
     src/ExpResetMcl2.cpp
     (中略)
     src/emcl2_node.cpp
   )
   
   if(BUILD_TESTING)                          #あとはたぶんデフォルト
   (以下略)

 ヘッダファイルを探す命令も書いていませんが、 include/<パッケージ名>/に入れておけば探してくれる模様です。

 emcl2_ros2パッケージについてはpackage.xmlやディレクトリ構成も参考になると思います。

YAMLに制限

 次のような、型の違うデータの並びの読み込みには対応していないとのこと。


   vi_node:
     action_list:
       - name: forward                #文字列
         onestep_forward_m: 0.3       #浮動小数点(ここでエラーが出る)
         onestep_rotation_deg: 0.0
     ・・・

↓ここらへんにこの問題への言及があります。

たぶん、YAMLのデータを流用したければ、すべて文字列型で読み込んで変換すればいいんじゃないっすかね?(投げやり)

 ちなみにYAMLファイル自体はconfigディレクトリを作って次のように書くとよいみたいです。


   vi_node:
     ros__parameters:              #この項目が必要になる(なんでアンダースコア2個なん??)
       global_thread_num: 2
       local_thread_num: 1
       online: true
   #    action_list:                  #以下、ROS 1時代の残骸(よみこめねえ)
   #      - name: "forward"
   #        onestep_forward_m: 0.3
   #        onestep_rotation_deg: 0.0

実行時、YAMLファイルは次のように指定します。

$ ros2 run value_iteration2 vi_node --ros-args --params-file ./config/params.yaml

 C++側でのパラメータの読み込み方もいろいろ変わってます。 ROS 2のコードをのせときます。

/* ROS 2 */
   declare_parameter("global_thread_num", 1); //パラメータを宣言しないとアカンらしい(1はデフォルト値)
   int thread_num = get_parameter("global_thread_num").as_int(); //読み込み

パブリッシャ、サブスクライバの型

 こんなふうに変わるみたいです。なげーよ。 ROS 2のほうのSubscriptionSubscriberにして10分くらい死んでました。 Rustみたいにuse(using)を多用しないといけないのかもしれません。


   /* ROS 1 */
   ros::Publisher pub_cmd_vel_;     //パブリッシャ
   ros::Subscriber sub_laser_scan_; //サブスクライバ
   /* ROS 2 */
   rclcpp::Publisher<geometry_msgs::msg::Twist>::SharedPtr pub_cmd_vel_;         //パブリッシャ
   rclcpp::Subscription<sensor_msgs::msg::LaserScan>::SharedPtr sub_laser_scan_; //サブスクライバ

ConstSharedPtr

 ConstPtrがdeprecatedだと叱られました。 次のようにConstSharedPtrを使えとのことです。 ・・・なげーよ。


   /* ROS 1 */
   void scanReceived(const sensor_msgs::LaserScan::ConstPtr &msg);
   /* ROS 2 */
   void scanReceived(const sensor_msgs::msg::LaserScan::ConstSharedPtr msg);

事情はここらへん にちょろっとだけ書いてあります。

std_msgsのヘッダファイル

 std_msgs/UInt32MultiArray.hstd_msgs/msg/uint32_multi_array.hpp になるんだろうなーと思ったけどビルドが通らず、 そこそこ時間を消耗しました。uのうしろにもアンダースコアがいりました。 死にました。ここらへん が参考になります。 ていうかおじさんが学生のころはhppという拡張子を見たことがなったんですが、 いつごろみんな使い始めたんでしょう?


   /* ROS 1 */
   #include "std_msgs/UInt32MultiArray.h"
   #include "std_msgs/Float32MultiArray.h"
   /* ROS 2 */
   #include <std_msgs/msg/u_int32_multi_array.hpp>
   #include <std_msgs/msg/float32_multi_array.hpp>

おわりに

 また作業進めていて気づいたら書きます。最後に一言。

なげーよ

ノート   このエントリーをはてなブックマークに追加 
 

prev:ROS 2でTurtleBot3のナビゲーションのサンプルを動かすまでのつまづき next:C++で作ったROS 1のパッケージをROS 2に移植するときのつまづきポイント ―その2

やり散らかし一覧

記事いろいろ