T265は2つのモノクロ魚眼カメラ、IMU、VPU(Vision Processing Unit)を内蔵していて、自己位置推定(自分の位置の推定)してくれるデバイス。
自己位置推定は実装したことが無いものの、資料を読む限り、とても面倒で難しそう。そんな自己位置推定をこんな小さなデバイスがサクッとお手軽に肩代わりしてくれる。
このT265とLIDARとROSパッケージがあれば、適当に設定するだけで簡単に地図も作れた。
既知の問題がいくつかあり、修正予定もないため用途によっては注意が必要。
動作確認環境
CPUボート: Jetson Nano
OS: Ubuntu 18.04
ROS: Melodic
T265はROS以外のインタフェースも用意してくれているけど、ROSで使いたいのでROSで確認。
ROSノード起動時のパラメータ
launchファイルの説明、パラメータの説明
基本はrelasense-rosのページに説明がある。
relasense-rosパッケージの含まれるlaunchのサンプルが参考になる。
全パラメータやデフォルト値はlaunchのサンプル内にあるnodelet.launchで確認できる。
intelrealsenseのドキュメントにも、launchサンプルのファイル別説明がある。
パラメータ補足
オプション名 | 初期値 | 説明 |
---|---|---|
serial_no, usb_port_id, device_type | "" | 接続するデバイスの指定。同じ機種を複数使わない限りは、device_typeの指定で十分っぽい。 |
enable_fisheye | false | |
enable_fisheye1 | false | 画像トピックを有効にするかどうか。有効にしなくても /camera/odom/sample トピックは配信される |
enable_fisheye2 | false | 同上 |
enable_gyro | false | trueにすると /camera/gyro/imu_info, /camera/gyro/sample トピックが配信される。trueの場合はTFフレームのcamera_gyro_frame, camera_gyro_optical_frameも配信される。有効にしなくても /camera/odom/sampleトピックは配信される。 |
enable_accel | false | trueにすると/camera/accel/imu_info, /camera/accel/sampleトピックが配信される。trueの場合にはTFフレームのcamera_accel_frame, camera_accel_optical_frameも配信される。有効にしなくても /camera/odom/sampleトピックは配信される。 |
enable_pose | false | trueにすると /camera/odom/sample トピックが配信される。trueの場合にはTFフレームのcamera_linkも配信される。publish_odom_tf オプションもtrueなら、TFフレームのcamera_pose_frameも配信される。 |
publish_odom_tf | true | enable_poseオプションの説明参照 |
tf_prefix | "" | TFのID名のプレフィックスに使われる。 base_frame_id パラメータや odom_frame_id パラメータなどを個別のID名が指定された場合は、そちらが優先される。 |
base_frame_id | $(arg tf_prefix)_link | baseのTFフレームID名 |
pose_frame_id | $(arg tf_prefix)_pose_frame | poseのTFフレームID名 |
odom_frame_id | $(arg tf_prefix)_odom_frame | odomのTFフレームID名 |
サンプル(rs_t265.launch)を立ち上げたときの状態
確認で使用したサンプルのlaunchファイルは rs_t265.launch。起動方法は次の通り。
$ roslaunch rs_t265.launch
トピック一覧
$ rostopic list /camera/accel/imu_info /camera/accel/sample /camera/gyro/imu_info /camera/gyro/sample /camera/odom/sample /camera/realsense2_camera_manager/bond /camera/tracking_module/parameter_descriptions /camera/tracking_module/parameter_updates /diagnostics /rosout /rosout_agg /tf /tf_static
rqt_graph
トピックから配信されるメッセージの型
トピック名 | メッセージ型 |
---|---|
/camera/accel/imu_info | realsense2_camera/IMUInfo |
/camera/accel/sample | sensor_msgs/Imu |
/camera/gyro/imu_info | realsense2_camera/IMUInfo |
/camera/gyro/sample | sensor_msgs/Imu |
/camera/odom/sample | nav_msgs/Odometry |
/camera/realsense2_camera_manager/bond | bond/Status |
/camera/tracking_module/parameter_descriptions | dynamic_reconfigure/ConfigDescription |
/camera/tracking_module/parameter_updates | dynamic_reconfigure/Config |
TFツリー
自分用の最小設定で立ち上げたときの状態
欲しいのは自己位置推定の結果だけなので、いらない出力を抑えた。
launchファイル
$ cat rs_t265_test.launch <launch> <arg name="device_type" default="t265"/> <arg name="camera" default="t265"/> <arg name="tf_prefix" default="$(arg camera)"/> <arg name="enable_pose" default="true"/> <arg name="initial_reset" default="true"/> <remap from="/t265/odom/sample" to="/odom"/> <group ns="$(arg camera)"> <include file="$(find realsense2_camera)/launch/includes/nodelet.launch.xml"> <arg name="tf_prefix" value="$(arg tf_prefix)"/> <arg name="device_type" value="$(arg device_type)"/> <arg name="enable_pose" value="$(arg enable_pose)"/> <arg name="initial_reset" value="$(arg initial_reset)"/> </include> </group> </launch>
トピック一覧
$ rostopic list /diagnostics /odom /rosout /rosout_agg /t265/realsense2_camera_manager/bond /t265/tracking_module/parameter_descriptions /t265/tracking_module/parameter_updates /tf /tf_static
rqt_graph
TFツリー
メモ
USB2での利用
魚眼カメラのストリーミングを使用しない場合はUSB2でも動作するとのこと。
車輪のオドメーター
T265があれば車輪のオドメーター(走行距離)はいらないかと思ったけど、T265の自己位置推定をより堅牢にするのにはオドメーターの内容を入力した方がいいとのこと。
精度の低下要因
視野全体に人などが映るとパフォーマンスが低下。屋内で混雑が予想される場合は、カメラを上に向けて、天井の特徴を利用してナビゲートできるようにすることがお勧めされてる。
起動、キャリブレーション
ROSラッパー利用時はノード起動時の場所が原点になる(odom_frameとnode_frameが一致する)。起動時にデバイスが移動していないことを前提としているようなので、起動時の移動は避ける。キャリブレーションは工場で実施済み。
マウンタの3Dデータ
T265単体用のマウンタ
公式サイトにあるD435とセットで使う場合のマウンタ
用語
BMI055 IMU
超小型の6軸慣性センサ。加速度センサーとジャイロセンサーを合わせたデバイス。
6DoF
DOFはdegrees of freedomの略。6DoFだと6自由度。前後、上下、左右、ロール、ピッチ、ヨー。
ジャイロセンサ(Gyro)
別名角速度センサ。角速度を検出するデバイス。
IMU
慣性計測装置(英語: inertial measurement unit、略称:IMU)は、運動を司る3軸の角度(または角速度)と加速度を検出する装置。INU (inertial navigation unit)、IGU (inertial guidance unit)、IRU (inertial reference unit) とも呼ばれる。 基本的には、3軸のジャイロと3方向の加速度計によって、3次元の角速度と加速度が求められる。
Odometry(Odom)
走行距離計(オドメーター)による測定。
オドメトリ(odometry)とは車輪型移動ロボットにおける車輪やステアリングの回転角度の計算から、それぞれの移動量を求め、その累積 計算からロボットの位置を推定する手法の総称です。
リンク
librealsenseのT265ドキュメント
IntelRealSense/realsense-ros
librealsenseのLinuxでのインストール方法
データシート
本体のCADデータ
Jetson Xavier NXでRealSense D435iを使用する際のインストール方法・注意点・実装コード
ソフトリブート時の対策を記載してくれている。
JetsonHacksNano/installLibrealsense
sensor_msgs/Imu Message
nav_msgs/Odometry Message
ROS.org navigation/Tutorials/RobotSetup/Odom
Odom配信の実装例