open-rdc / orne-box

Platform hardware for autonomous robot
BSD 2-Clause "Simplified" License
29 stars 20 forks source link

地図の作成 #95

Open yasuohayashibara opened 10 months ago

yasuohayashibara commented 10 months ago

build_map_bag_box.launchで各種パラメータをデフォルトの値にしてgmappingを実行 https://github.com/open-rdc/orne-box/blob/noetic-devel/orne_box_navigation_executor/launch/build_map_bag_box.launch

わりと良い地図を書くこともあるが,始点と終点が繋がらない地図になる. ジャイロオドメトリのみで作成した点群の方がずれが少ない. https://github.com/open-rdc/orne-box/issues/94#issuecomment-1868692879

IMAGE

その要因であるが,ジャイロオドメトリとLiDARの時間的なずれによる影響が大きいと考える. 以下に,ジャイロオドメトリに従い,LiDARを表示した動画を示す. LiDARは固定された壁を検出しているため,本来は揺れることなく一定であることが望まれるが,動画のように揺れている. この揺れを補正するように自己位置を変更すると,歪の大きな地図になると考える.

IMAGE

対策としては,以下が考えられる.

1)ジャイロオドメトリとLiDARを統合するときの時間的なずれを最小限にする. 2)LiDARの検出距離を伸ばす.   意図的でははないが,おそらく現在は10m程度しか検出していなさそうである.   ただし,動画にあるように地面を壁と検出しているところがあるので,距離を伸ばすためにはその対策が必要である.

あと,今回判明したこととして,上記の時間のずれを取り切れない場合は,

・地図用のデータを取得しているときはできるだけ急旋回しないようにすることが必要である.

yasuohayashibara commented 10 months ago

時間のずれを最小限にするようなパラメータが無いかを確認したが,それらしきものが見つからなかった. ジャイロオドメトリが30Hz(オドメトリとジャイロの値は100Hz)であるのに対して,LiDARは10Hzであるので,最大0.1秒程度の時間のずれが生じると思われる. まずは,ジャイロオドメトリが変化して,その後にLiDARが追従するような様子が見られる. 角速度の最大値を現在0.9rad/s(51deg/s)としているので,0.1秒間のずれは,0.09rad(5deg)となる. https://github.com/open-rdc/icart/blob/noetic-devel/icart_mini_driver/config/elecom_joy.yaml

LiDARの動きを見ているとちょうど5deg程度ずれている気がするので,上記の仮説はあっているかもしれない. (タイムスタンプがどのように利用されるかをいまいち理解していないが.)

とりあえずの対処になるが,角速度の最大値を下げればこのずれは少なくなるので,scale_angular: 0.9->0.3にして走行させてみた.

ぶれは少なくなったと感じるが,まだピッタリと一致する程度になっていない. IMAGE

上記と同様にgmappingで地図を作成した. 上記と異なり,始点と終点がつながる地図を作成できた. IMAGE

なお,上記の地図を生成するにあたり,pointcloud_to_laserscanのパラメータを0~1mに変更した. https://github.com/open-rdc/orne-box/blob/512d69b316fc4f81a24848be12e642681d8c1f31/orne_box_bringup/launch/includes/rfans16.launch#L36-L37

-0.2~0.2mとしていたが,0.2mでは水平に対して±1degの方向にレーザを出しているrfans16の場合,

0.2 / tan(radians(1)) = 11.46m

となる.つまり実質的に11.46mしか検出しないLiDARになっていた.これを0~1mにすることで,

1.0 / tan(radians(1)) = 57.29m

となり,やや遠くの障害物を検出できる. ただし,どちらにしてもLiDARの性能を活かしているとは言えないので,やはり3Dで処理することが必須と考える.

yasuohayashibara commented 10 months ago

屋外を移動してデータを収集した. ジャイロオドメトリに基づいてLiDARデータを出力したところ,結果的に角度がドリフトする様子が見られた. 上記の屋内のデータを取得するときにIMUのキャリブレーションを行ったが,それがリセットされたような値となっている. 今後原因を究明して,このようなことが起きないような手順を作成する.

IMAGE

gmappingで地図を生成した様子を示す. ジャイロオドメトリの影響だと思われるが,始点と終点が一致していない. あと,pointcloud_to_laserscanの上限をもう少し上げたほうが良いと思われる.

gmapping IMAGE

yasuohayashibara commented 10 months ago

IMUのキャリブレーションを行って,上記を再度行った. なお,pointcloud_to_laserscanで検出する高さを0~3mとした.

スタートとゴールはほぼ同じ位置にしたが,位置は10m程度,角度は数度ズレている. この程度であれば,LiDARで少しだけ位置を補正するだけで地図が描けると考える.

IMAGE

pointcloud_to_laserscanの値を3mにしたせいか,レーザが近くの障害物を検出せずに,そのさきのものを検出するようになった. 明らかに歪んだ地図となった.

IMAGE

以下を参考にしながらcartographerで地図を描いた https://github.com/open-rdc/cartographer_ros_3d_mapping パラメータの最適化は行っていないが,それなりに良い地図を描けた

IMAGE

yasuohayashibara commented 9 months ago

上記の地図の生成法を以下に示した.

https://github.com/open-rdc/cartographer_ros

ワーニングが出ていたり,パラメータの最適化を行っていないなど問題はあると思いますが,安定して地図を描けています.

yasuohayashibara commented 9 months ago

以下でマップファイルを生成

rosrun map_server map_saver -f <map_name>

3次元マップ

rosservice call /finish_trajectory 0
rosservice call /write_state "{filename: '/home/mirai/map.pbstream', include_unfinished_submaps: true}"
roslaunch cartographer_ros assets_writer_my_param.launch bag_filenames:=${HOME}/2023-12-28-06-32-13.bag pose_graph_filename:=${HOME}/map.pbstream

ダウンサンプリング

pcl_voxel_grid ${HOME}/2023-12-28-06-32-13.bag_points.pcd ${HOME}/2023-12-28-06-32-13.bag_points.pcd_ds.pcd  -leaf 0.1,0.1,0.1

意図してないものが生成された. おそらく座標系の問題と思われる. image