地図作成はロボットのマッピングと位置決めを実行します

カートグラファーフレームワークは、2016年にGoogleによってオープンソース化されました。このフレームワークは、2Dレーザー、3Dレーザー、走行距離計、IMUセンサーからのデータにアクセスし、2Dマップまたは3Dマップを出力できます。同時に、フレームワークには、マップを段階的に更新できるという特徴的な機能があり、カートグラファーがポジショニングモードで実行されている場合は、ポジショニング中に既存のマップを段階的に更新できます。

1地図製作のインストール

インターネットに地図作成をインストールするためのチュートリアルは多数あります[2]。基本的に、これらのチュートリアルまたは公式Webサイトで提供されているチュートリアルには他の問題はありません。唯一の問題は、githubから直接コピーする速度が非常に遅いことです。中国では複製されていないコードを使用できます。 。
公式ウェブサイト[1]に従ってソースコードをダウンロードします。ダウンロードするときは、ceres-solverアドレスをhttps://github.com/ceres-solver/ceres-solver.git(コマンドvim src / .rosinstallを使用)に変更する
か、私にアクセスする必要がありますウェアハウスをダウンロードするには、srcディレクトリにある3つの圧縮パッケージを解凍します。

2 2Dマッピングテスト

ここでは、まず公式Webサイトでデモをテストし、次に私たちのロボットでテストします。ここでは、公式WebサイトのPure localizationセクションのデータセットを実行しています。

2.1 2Dマッピングのデモを開始する

roslaunch cartographer_ros demo_backpack_2d.launch bag_filename:=/media/crp/0E3C06880E3C0688/b2-2016-04-05-14-44-52.bag

bag_filenameは、ROSバッグのデータパケットを表します。

注意:ここでは、公式Webサイトのoffline_backpack_2d.launchファイルをdemo_backpack_2d.launchに置き換えます。これは、offline_backpack_2d.launchファイルがマップ保存サービスを開始していないことが判明したためです。

cartograph_dataセット2Dマッピング(x8)

まず、マップを.pbstreamファイルとして保存します

rosservice call /write_state ~/cartograph_test.pbstream

カートグラフィに付属の変換ノードを使用して、.pbstreamファイルをpgmおよびyamlファイルに変換します

rosrun cartographer_ros cartographer_pbstream_to_ros_map -pbstream_filename /home/crp/cartograph_test.pbstream -map_filestem /home/crp/cartograph_test

ノードを起動すると、フォルダーに生成されたpgmファイルとyamlファイルが表示されますが、
ここに画像の説明を挿入
位置決めに地図作成を使用する必要がある場合は、pgm形式に変換する必要はありません。

2.2 2D配置デモを開始する

次に、既存のマップを使用して、

roslaunch cartographer_ros demo_backpack_2d_localization.launch load_state_filename:=/home/crp/ cartograph_test.pbstream bag_filename:=/media/crp/0E3C06880E3C0688/b2-2016-04-27-12-31-41.bag

その中で、cartograph_test.pbstreamは前のステップで生成されたマップファイルであり、bag_filename:は現在入力されているLIDARデータを表します

Cartograph_Dataセット2D位置決め増分更新マップ

位置決めデータはTF座標系で出力されます。

2.3コブキロボットでのマッピングの実現

ここでは、デモ履歴を参照してパラメーターファイルを構成しますが、ここでは主にluaファイルのいくつかの座標系の構成に注意する必要があります。私自身の試みの後a)
LIDARのみを使用する場合(tracking_frame =” laser”、publish_frame =” laser”)
b)オドメーター+ LIDAR(tracking_frame =” base_link”、publish_frame =” odom”)を使用する場合
c )IMU +レーザー+マイレージタイマーを使用(tracking_frame =” imu_link”、publish_frame =” odom”)

残りのパラメーターは、デモを参照して構成できます。使用した起動ファイル( "kobuki_robot.launch")とlua( "kobuki_robot.lua")のファイル構成は、次のとおりです:
kobuki_robot.launch

<launch>
  
  <arg name="urdf_file" default="$(find xacro)/xacro --inorder '$(find kobuki_description)/urdf/kobuki_standalone.urdf.xacro'"/>
  <param name="robot_description" command="$(arg urdf_file)"/>

  <node pkg="robot_state_publisher" type="robot_state_publisher" name="robot_state_publisher" output="screen">
    <param name="publish_frequency" type="double" value="5.0"/>
  </node>

  <node name="joint_state_publisher" pkg="joint_state_publisher" type="joint_state_publisher">
    <param name="use_gui" value="true"/>
  </node>


  <node name="cartographer_node" pkg="cartographer_ros"
      type="cartographer_node" args="
          -configuration_directory $(find cartographer_ros)/configuration_files
          -configuration_basename kobuki_robot.lua"
      output="screen">
    <remap from="scan" to="/scan" />
    <remap from="odom" to="/odom" />
  </node>
 

  <node name="cartographer_occupancy_grid_node" pkg="cartographer_ros"
      type="cartographer_occupancy_grid_node" args="-resolution 0.05" />

  <node name="rviz" pkg="rviz" type="rviz" required="true"
      args="-d $(find cartographer_ros)/configuration_files/demo_2d.rviz" />
 
</launch>

kobuki_robot.lua

include "map_builder.lua"
include "trajectory_builder.lua"

options = {
    
    
  map_builder = MAP_BUILDER,
  trajectory_builder = TRAJECTORY_BUILDER,
  map_frame = "map",
  tracking_frame = "base_footprint",
  published_frame = "odom",
  odom_frame = "odom",
  provide_odom_frame = false, --算法内部提供里程计
  publish_frame_projected_to_2d = false,
  use_odometry = true, --使用里程计
  use_nav_sat = false,
  use_landmarks = false,

  num_laser_scans = 1,
  num_multi_echo_laser_scans = 0,
  num_subdivisions_per_laser_scan = 1,
  num_point_clouds = 0,
  lookup_transform_timeout_sec = 0.2,
  submap_publish_period_sec = 0.3,
  pose_publish_period_sec = 5e-3,
  trajectory_publish_period_sec = 30e-3,
  rangefinder_sampling_ratio = 1.,
  odometry_sampling_ratio = 1.,
  fixed_frame_pose_sampling_ratio = 1.,
  imu_sampling_ratio = 1.,
  landmarks_sampling_ratio = 1.,
}

MAP_BUILDER.use_trajectory_builder_2d = true

TRAJECTORY_BUILDER_2D.submaps.num_range_data = 35
TRAJECTORY_BUILDER_2D.min_range = 0.3
TRAJECTORY_BUILDER_2D.max_range = 8.
TRAJECTORY_BUILDER_2D.missing_data_ray_length = 1.
TRAJECTORY_BUILDER_2D.use_imu_data = false
TRAJECTORY_BUILDER_2D.imu_gravity_time_constant = 9.8 
TRAJECTORY_BUILDER_2D.use_online_correlative_scan_matching = true
TRAJECTORY_BUILDER_2D.real_time_correlative_scan_matcher.linear_search_window = 0.1
TRAJECTORY_BUILDER_2D.real_time_correlative_scan_matcher.translation_delta_cost_weight = 10.
TRAJECTORY_BUILDER_2D.real_time_correlative_scan_matcher.rotation_delta_cost_weight = 1e-1
POSE_GRAPH.optimization_problem.huber_scale = 1e2
POSE_GRAPH.optimize_every_n_nodes = 35
POSE_GRAPH.constraint_builder.min_score = 0.65

return options

以下は研究室で記録されたビデオです

こぶきカルトグラフ建图

2.4コブキの既存の地図に基づく配置

次に、マップを使用して構築し、位置を特定しながら、マップを段階的に更新します(マップの右上隅の領域に注意してください)
。kobuki_localization.launch

<launch>
  
  <arg name="urdf_file" default="$(find xacro)/xacro --inorder '$(find kobuki_description)/urdf/kobuki_standalone.urdf.xacro'"/>
  <param name="robot_description" command="$(arg urdf_file)"/>

  <node pkg="robot_state_publisher" type="robot_state_publisher" name="robot_state_publisher" output="screen">
    <param name="publish_frequency" type="double" value="5.0"/>
  </node>

  <node name="joint_state_publisher" pkg="joint_state_publisher" type="joint_state_publisher">
    <param name="use_gui" value="true"/>
  </node>


  <node name="cartographer_node" pkg="cartographer_ros"
      type="cartographer_node" args="
          -configuration_directory $(find cartographer_ros)/configuration_files
          -configuration_basename kobuki_localization.lua
	  -load_state_filename $(arg load_state_filename)"
      output="screen">
    <remap from="echoes" to="/scan" />
  </node>
 

  <node name="cartographer_occupancy_grid_node" pkg="cartographer_ros"
      type="cartographer_occupancy_grid_node" args="-resolution 0.05" />

  <node name="rviz" pkg="rviz" type="rviz" required="true"
      args="-d $(find cartographer_ros)/configuration_files/demo_2d.rviz" />
 
</launch>

kobuki_localization.lua位置決めモードのlua構成ファイル。ただし、マップの作成に基づいて2つの構成パラメーターが追加されます。

include "kobuki_robot.lua"

TRAJECTORY_BUILDER.pure_localization = true
POSE_GRAPH.optimize_every_n_nodes = 20

return options

ポジショニングと増分更新マップビデオ:

kobuki_Cartograph_positioning&インクリメンタルマッピング

3. 3Dマッピングテスト

3.1 3Dデータセットのマッピング

3D LIDARを使用してマップを構築する場合、IMUを組み合わせて、IMUによって提供される重力方向ベクトルを使用する必要があります。ここでは、公式Webサイトの手順[1]を直接実行します。最初に、この3Dデータパッケージをダウンロードする必要があります[5]

次に、公式ウェブサイトの「offline_backpack_3d.launch」を「demo_backpack_3d.launch」に置き換える必要があります。そうしないと、マップを保存するときに呼び出すことができません

3D LIDARマッピングを開始

roslaunch cartographer_ros demo_backpack_3d.launch bag_filename:=/media/crp/0E3C06880E3C0688/b3-2016-04-05-13-54-42.bag

地図作成-3Dマッピング

データが実行されるまで待機し、write_stateサービスを呼び出してマップを保存します

rosservice call /write_state ~/3d_local.pbstream

このpbstreamファイルを3Dプライの点群ファイルに変換します

roslaunch cartographer_ros assets_writer_my_rslidar_3d.launch bag_filenames:=b3-2016-04-05-13-54-42.bag pose_graph_filename:=~/3d_local.pbstream

しばらくすると、処理が完了するとコマンドが自動的に終了します。このとき、バッグファイルの隣に.bag_points.plyサフィックスファイルが生成されます。これは点群ファイルです[6]。最後に、PCLツールを使用して、plyファイルをpcdに変換しますファイル

pcl_ply2pcd b3-2016-04-05-13-54-42.bag_points.ply test_3d.pcd

実行すると、下図のようにロボットのポーズがTFで公開されます。したがって、odom-> map間の座標変換を読み取ることにより、ロボットの位置を知ることができます
ここに画像の説明を挿入

3.2 3Dポジショニング

3Dポジショニングの場合、セクション3.1で生成された「***〜/ 3d_local.pbstream ***」を既存のマップとして使用し、現在のレーザーデータ入力を照合して位置を推定します

cartographer_ros demo_backpack_3d_localization.launch load_state_filename:=/home/crp/3d_local.pbstream bag_filename:=/media/crp/0E3C06880E3C0688/b3-2016-04-05-15-52-20.bag

カートグラフィ-3Dポジショニング

また、下図のように、ポジショニングを実行すると、ロボットのポーズもTFで公開されます。したがって、odom-> map間の座標変換を読み取ることで、ロボットの位置を知ることができます。(ポジショニング中のポーズの出力周波数は、マッピング中の周波数よりもはるかに低いことがはっきりとわかります)
ここに画像の説明を挿入

参考資料:

[1] https://google-cartographer-ros.readthedocs.io/en/latest/compilation.html#building-installation
[2] https://www.cnblogs.com/hitcm/p/5939507.html
[3 ] https://zhuanlan.zhihu.com/p/64747755
[4] https://storage.googleapis.com/cartographer-public-data/bags/backpack_3d/b3-2016-04-05-13-54-42 .bag
[5] https://storage.googleapis.com/cartographer-public-data/bags/backpack_3d/b3-2016-04-05-15-52-20.bag
[6] http://community.bwbot .org / topic / 523 /%E8%B0%B7%E6%AD%8Ccartographer%E4%BD%BF%E7%94%A8%E9%80%9F%E8%85%BE%E8%81%9A% E5%88%9B3d%E6%BF%80%E5%85%89%E9%9B%B7%E8%BE%BE%E6%95%B0%E6%8D%AE%E8%BF%9B%E8% A1%8C%E4%B8%89%E7%BB%B4%E5%BB%BA%E5%9B%BE / 2

自律航法車両である友人たちと話し合うか、メッセージを残してください。cenruping@ vip.qq.com

おすすめ

転載: blog.csdn.net/crp997576280/article/details/103279649