こんにちは、趣味で自律航行船の開発に取り組んでいる片岡です。
いい加減ROS2移行したいよなあと重い、公開しているパッケージ群をROS2移行したらいろんな罠にハマりまくったのでその対応に関して備忘録を残しておきます。
罠その1 CMakeのバージョンが変わってる
colcon buildしようとしたらいきなり謎のエラー、何なんだこれは・・・・
CMake Warning (dev) at /opt/ros/dashing/share/ament_cmake_core/cmake/core/list_append_unique.cmake:30 (if):
Policy CMP0057 is not set: Support new IN_LIST if() operator. Run "cmake
--help-policy CMP0057" for policy details. Use the cmake_policy command to
set the policy and suppress this warning.
IN_LIST will be interpreted as an operator when the policy is set to NEW.
Since the policy is not set the OLD behavior will be used.
よく見てみたところ、cmake_minimum_requiredのバージョンが2.8.3になっている、ROS1だとそのあたりのバージョンが標準になっており、amentパッケージはこのバージョンのCMakeにはないオプションを使っているらしい。
cmake_minimum_required(VERSION 3.5)
と設定したらエラーが消えた
罠その2 メッセージの名前空間に::msgが入ってる
ROS1ではgeometry_msgs::PoseとかだったのがROS2ではgeometry_msgs::msg::Poseとかになっています。
つまりメッセージ型は前部型の名前が変更になっているので、前部書き直し
おまけにメッセージのヘッダファイル名も変わっている。
ROS1では
#include <geometry_msgs/Pose.h>
で行けたのを
#include <geometry_msgs/msg/pose.hpp>
のように間にmsgを間にいれてやらないといけない
さらにヘッダファイル名の命名規則も変更されている。
アッパーキャメルケースがスネークケースになっており、
ROS1では
#include <geometry_msgs/PoseStamped.h>
だっとものは
#include <geometry_msgs/msg/pose_stamped.hpp>
となる
罠その3 独自メセージのビルド過程でFastRTPSが入ってないよエラーがでる
CMake Error at /usr/local/share/cmake-3.15/Modules/FindPackageHandleStandardArgs.cmake:137 (message):
Could NOT find FastRTPS (missing: FastRTPS_INCLUDE_DIR FastRTPS_LIBRARIES)
初見でコレに出会ったときにはえ・・・・FastRTPSってDashingインストールするときにいれたよね・・・
という顔になります。が、これはCMakeにfind_package忘れや依存解決忘れ起こっていたりするのではなく、package.xmlのexportタグに抜け漏れがあるのが原因です。
<export>
<build_type>ament_cmake</build_type>
</export>
build_typeにament_cmakeを追加するとこのエラーは消えます。
罠その4 他のROSパッケージのヘッダをインクルードしようとするとそんなものはないと言われる
ROS1では特に何も書かなくても他のパッケージのincludeディレクトリにあるヘッダをインクルードしてくれました。
ですがROS2からはそれができなくなっているようです。
これをするにはCMakeLists.txtに以下の行を追加する必要があります。
ament_export_include_directories(include)
罠その5 ros::Time::nowが使えない
ROS1ではros::Timeで時間を管理していましたが、ROS2からはここが変わっています。詳細はここを参照してください。https://index.ros.org//doc/ros2/Contributing/Migration-Guide/
ROS2ではros::Time::now()みたいに時間を取ってくるのではなく、Clockオブジェクトを作ってそこから時間を参照するようです。
ClockのTime SourceはSystemTime、ROSTime、SteadyTimeの3つがあります。
System Timeはシステムクロックをダイレクトに取ってきて時刻を計算します。
ROSTimeはuse_sim_timeがtrueならば/clockトピックから時刻を計算します。
SteadyTimeはハードウェアのペリフェラルが絡むときにのみ使う時刻ソースだそうです。
巻き戻らないTimeSourceのようなので、確かにハードウェアドライバのタイムアウトの計算には最適ですね。
上の3種類のソースを使って、以下のように時刻を取得するようにros::Time::now()の部分を書き換えていきます。
rcl_clock_type_tの部分はenumなので0,1,2,3でも指定できます(http://docs.ros2.org/latest/api/rcl/time_8h.html)
rclcpp::Clock system_clock(rcl_clock_type_t RCL_SYSTEM_TIME);
rclcpp::Time now = system_clock.now();
rclcpp::Clock ros_clock(rcl_clock_type_t RCL_ROS_TIME);
rclcpp::Time now = ros_clock.now();
rclcpp::Clock steady_clock(rcl_clock_type_t RCL_STEADY_TIME);
rclcpp::Time now = steady_clock.now();
罠その6 ROS_ASSERTが使えなくなっている
ちょっと未確認ですが、rclcppのexecutorを確認したところ、普通にassertを使っている。https://github.com/ros2/rclcpp/blob/07cb443a18f9f279f7982c6cca33ea2acf69ea9d/rclcpp/src/rclcpp/executor.cpp#L592
assertを普通に使えばいいのかな・・・???
罠その7 ROS_ERROR_STREAMの類が使えなくなっている
ROS1では
ROS_ERROR_STREAM(hogehoge)
ってかけばよかったのでかなり楽だったのですが、ROS2になりここのAPIが変更になっています。http://docs.ros2.org/bouncy/api/rclcpp/logging_8hpp.html#ad8f3687eda7312561768319e99cd4ca6
nodehandler経由でLoggerオブジェクトの取得が必要になりました。
なので、以下のように書くとエラー等の情報を吐き出すことができます。
std::shared_ptr<rclcpp::Node> node_ptr = rclcpp::Node::make_shared("ros_node_name");
RCLCPP_ERROR(node_ptr_->get_logger(), "Error Message");
のように書き換える必要があります。
まとめ
ROS1 -> ROS2のポーティングとかそんな難しくないやろと思っていたらいろんなところに罠が散りばめられており、なかなかつらいお気持ちになりました。
ですが、一個一個APIの変更とか名前空間とかの変化を確認するとガバガバだったROS1のアーキテクチャがどんどん良くなっているのを感じて嬉しくなります。
そろそろPython2のサポートも切れる頃ですし、自作パッケージをROS1からROS2に移行されてみてはいかがでしょうか??