これは、複数のデータ レイヤーを持つ 2 次元グリッド マップを管理するための ROS インターフェイスを備えた C++ ライブラリです。これは、標高、分散、色、摩擦係数、足場の品質、表面法線、通過可能性などのデータを保存するモバイル ロボット マッピング用に設計されています。これは、不整地ナビゲーション用に設計されたロボット中心の標高マッピング パッケージで使用されます。
特徴:
これは研究コードであり、頻繁に変更されることが想定されており、特定の目的への適合性は保証されません。
ソース コードは BSD 3 条項ライセンスに基づいてリリースされています。
著者: ピーター・ファンクハウザー
所属:エニボティクス
管理者: Maximilian Wulf、[email protected]、Magnus Gärtner、[email protected]
寄稿者: Simone Arreghini、Tanja Baumann、Jeff Delmerico、Remo Diethelm、Perry Franklin、Magnus Gärtner、Ruben Grandia、Edo Jelavic、Dominic Jud、Ralph Kaestner、Philipp Krüsi、Alex Millane、Daniel Stonier、Elena Stumm、Martin Wermelinger、Christosザリディス
このプロジェクトは当初、チューリッヒ工科大学 (自律システム研究所およびロボット システム研究所) で開発されました。
この研究は、脚式ロボット工学を進歩させるコミュニティである ANYmal Research の一環として実施されています。
この作品を学術的な文脈で使用する場合は、次の出版物を引用してください。
P. Fankhauser および M. Hutter、 「A Universal Grid Map Library: Implementation and Use Case for Rough Terrain Navigation」 、ロボット オペレーティング システム (ROS) – 完全リファレンス (第 1 巻)、A. Koubaa (編)、Springer 、2016年。(PDF)
@incollection{Fankhauser2016GridMapLibrary,
author = {Fankhauser, P{'{e}}ter and Hutter, Marco},
booktitle = {Robot Operating System (ROS) – The Complete Reference (Volume 1)},
title = {{A Universal Grid Map Library: Implementation and Use Case for Rough Terrain Navigation}},
chapter = {5},
editor = {Koubaa, Anis},
publisher = {Springer},
year = {2016},
isbn = {978-3-319-26052-5},
doi = {10.1007/978-3-319-26054-9{_}5},
url = {http://www.springer.com/de/book/9783319260525}
}
現在、次のブランチが維持されています。
ROS 1 のプル リクエストはmaster
ターゲットにする必要があります。 ROS 2 のプル リクエストはrolling
ターゲットにする必要があり、ABI を破壊しない場合はバックポートされます。
チュートリアルを含むグリッド マップ ライブラリの概要は、この本の章で説明されています。
C++ API については、次の場所に文書化されています。
Debian パッケージとしてグリッド マップ ライブラリからすべてのパッケージをインストールするには、次のようにします。
sudo apt-get install ros-$ROS_DISTRO-grid-map
Grid_map_coreパッケージは、線形代数ライブラリ Eigen のみに依存します。
sudo apt-get install libeigen3-dev
他のパッケージは、ROS 標準インストール ( roscpp 、 tf 、 filters 、 sensor_msgs 、 nav_msgs 、およびcv_bridge ) にさらに依存します。他の形式固有の変換パッケージ (例: Grid_map_cv 、 grid_map_pclなど) は、以下の「パッケージの概要」で説明されているパッケージに依存します。
ソースからビルドするには、このリポジトリから最新バージョンを catkin ワークスペースにクローンし、次を使用してパッケージをコンパイルします。
cd catkin_ws/src
git clone https://github.com/anybotics/grid_map.git
cd ../
catkin_make
パフォーマンスを最大化するには、必ずリリースモードでビルドしてください。設定によりビルドタイプを指定できます
catkin_make -DCMAKE_BUILD_TYPE=Release
このリポジトリは次のパッケージで構成されています。
GridMap
クラスとイテレータなどのいくつかのヘルパー クラスを提供します。このパッケージは、ROS 依存関係なしで実装されています。追加の変換パッケージ:
単体テストを実行します
catkin_make run_tests_grid_map_core run_tests_grid_map_ros
または
catkin build grid_map --no-deps --verbose --catkin-make-args run_tests
catkin ツールを使用している場合。
Grid_map_demosパッケージには、いくつかのデモンストレーション ノードが含まれています。このコードを使用して、グリッド マップ パッケージのインストールを確認し、ライブラリの独自の使用を開始します。
simple_demo は、グリッド マップ ライブラリを使用する簡単な例を示します。この ROS ノードはグリッド マップを作成し、それにデータを追加して公開します。 RViz で結果を確認するには、次のコマンドを実行します。
roslaunch grid_map_demos simple_demo.launch
tutorial_demo は、ライブラリの機能の拡張デモです。でtutorial_demoを起動します
roslaunch grid_map_demos tutorial_demo.launch
iterators_demo では、グリッド マップ イテレーターの使用法を紹介します。で起動します
roslaunch grid_map_demos iterators_demo.launch
image_to_gridmap_demo は、データを画像からグリッド マップに変換する方法を示します。でデモンストレーションを開始します
roslaunch grid_map_demos image_to_gridmap_demo.launch
Grid_map_to_image_demo は、グリッド マップ レイヤーを画像に保存する方法を示します。でデモンストレーションを開始します
rosrun grid_map_demos grid_map_to_image_demo _grid_map_topic:=/grid_map _file:=/home/$USER/Desktop/grid_map_image.png
opencv_demo は、 OpenCV 関数を使用したマップ操作を示します。でデモンストレーションを開始します
roslaunch grid_map_demos opencv_demo.launch
solution_change_demo は、 OpenCV 画像スケーリング メソッドを利用してグリッド マップの解像度を変更する方法を示します。結果を見て、使用してください
roslaunch grid_map_demos resolution_change_demo.launch
filters_demo は、一連の ROS フィルターを使用してグリッド マップを処理します。このデモでは、地形図の標高から始まり、いくつかのフィルターを使用して、表面法線を計算する方法、修復ペイントを使用して穴を埋める方法、マップを滑らかにしたりぼかしたりする方法、数式を使用してエッジを検出し、粗さと通過性を計算する方法を示します。フィルター チェーンのセットアップは、 filters_demo_filter_chain.yaml
ファイルで構成されます。でデモを起動します
roslaunch grid_map_demos filters_demo.launch
グリッド マップ フィルターの詳細については、「grid_map_filters」を参照してください。
interpolation_demo は、結果として得られるサーフェスに対するさまざまな補間法の結果を示します。デモを開始するには、使用します
roslaunch grid_map_demos interpolation_demo.launch
ユーザーは、 interpolation_demo.yaml
ファイルでさまざまなワールド (サーフェス) やさまざまな補間設定を操作して遊ぶことができます。ビジュアライゼーションでは、グラウンド トゥルースが緑と黄色で表示されます。補間結果は赤と紫の色で表示されます。また、デモでは、最大および平均の内挿誤差、および 1 つの内挿クエリに必要な平均時間を計算します。
グリッド マップには 4 つの異なる補間方法があります (精度が高く、複雑さが高い順)。
詳細については、 CubicInterpolation.hpp
ファイルにリストされている文献を確認してください。
グリッド マップ ライブラリには、便宜上、さまざまな反復子が含まれています。
グリッドマップ | サブマップ | 丸 | ライン | ポリゴン |
---|---|---|---|---|
楕円 | スパイラル | |||
for
ループ内でイテレータを使用するのが一般的です。たとえば、 GridMapIterator
を使用してグリッド マップ全体を反復処理します。
for (grid_map::GridMapIterator iterator(map); !iterator.isPastEnd(); ++iterator) {
cout << "The value at index " << (*iterator).transpose() << " is " << map.at("layer", *iterator) << endl;
}
他のグリッド マップ反復子も同じ形式に従います。さまざまなイテレーターの使用方法に関するその他の例は、 iterators_demoノードで見つけることができます。
注: イテレータを使用する際の効率を最大にするために、 for
ループの外側でgrid_map::Matrix& data = map["layer"]
を使用してグリッド マップのデータ レイヤーへの直接アクセスをローカルに保存することをお勧めします。
grid_map::Matrix& data = map["layer"];
for (GridMapIterator iterator(map); !iterator.isPastEnd(); ++iterator) {
const Index index(*iterator);
cout << "The value at index " << index.transpose() << " is " << data(index(0), index(1)) << endl;
}
イテレータのパフォーマンスのベンチマークは、 grid_map_demos
パッケージのiterator_benchmark
ノードで確認できます。
rosrun grid_map_demos iterator_benchmark
イテレータは便利ですが、多くの場合、組み込みのeigenメソッドを使用するのが最もクリーンで効率的であることに注意してください。以下にいくつかの例を示します。
レイヤーのすべてのセルに定数値を設定します。
map["layer"].setConstant(3.0);
2 つのレイヤーを追加します。
map["sum"] = map["layer_1"] + map["layer_2"];
レイヤーの拡大縮小:
map["layer"] = 2.0 * map["layer"];
最大。 2 つのレイヤー間の値:
map["max"] = map["layer_1"].cwiseMax(map["layer_2"]);
二乗平均平方根誤差を計算します。
map.add("error", (map.get("layer_1") - map.get("layer_2")).cwiseAbs());
unsigned int nCells = map.getSize().prod();
double rootMeanSquaredError = sqrt((map["error"].array().pow(2).sum()) / nCells);
地図の位置を変更するには 2 つの異なる方法があります。
setPosition(...)
: マップに格納されているデータを変更せずに、マップの位置を変更します。これにより、データとマップ フレームの対応関係が変更されます。
move(...)
: グリッド マップによってキャプチャされた領域を静的なグリッド マップ フレームに再配置します。これを使用して、グリッド マップ データを再配置せずにグリッド マップの境界を移動します。グリッド マップ データがグリッド マップ フレーム内に固定されるように、すべてのデータ処理を処理します。
注: 循環バッファ構造により、マップ フレーム内で隣接するインデックスが近くに配置されない場合があります。この仮定は、getUnwrappedIndex() によって取得されたインデックスにのみ当てはまります。
setPosition(...) | move(...) |
---|---|
この RViz プラグインは、グリッド マップ レイヤーを 3D サーフェス プロット (高さマップ) として視覚化します。カラー情報のレイヤーとして別のレイヤーを選択できます。
このパッケージは、標高マップを高密度の 3D 符号付き距離フィールドに変換する効率的なアルゴリズムを提供します。 3D グリッド内の各ポイントには、マップ内の最も近いポイントまでの距離と勾配が含まれています。
このノードは、grid_map_msgs/GridMap タイプのトピックをサブスクライブし、RViz で視覚化できるメッセージをパブリッシュします。ビジュアライザーの公開トピックは、YAML パラメーター ファイルを使用して完全に構成できます。さまざまなパラメータを持つビジュアライゼーションをいくつでも追加できます。ここでは、 tutorial_demoの設定ファイルの例を示します。
点群 | ベクトル | 占有グリッド | グリッドセル |
---|---|---|---|
grid_map_topic
(文字列、デフォルト: "/grid_map")
視覚化するグリッド マップ トピックの名前。ビジュアライザの説明については、以下を参照してください。
/grid_map
(grid_map_msgs/GridMap)
視覚化するグリッド マップ。
公開されたトピックは、YAML パラメーター ファイルを使用して構成されます。考えられるトピックは次のとおりです。
point_cloud
(センサー_msgs/PointCloud2)
グリッド マップを点群として表示します。 layer
パラメーターを使用して、どのレイヤーをポイントとして変換するかを選択します。
name: elevation
type: point_cloud
params:
layer: elevation
flat: false # optional
flat_point_cloud
(sensor_msgs/PointCloud2)
グリッド マップを「平らな」点群として表示します。つまり、すべての点が同じ高さzにあります。これは、 Color Transformer
を使用して RViz で 2D マップまたは画像 (またはビデオ ストリーム) を視覚化するのに便利です。パラメーターのheight
平坦な点群の望ましいZ位置が決まります。
name: flat_grid
type: flat_point_cloud
params:
height: 0.0
注: 空/無効なセルから平らな点群内の点を除外するには、 setBasicLayers(...)
で有効性をチェックする必要があるレイヤーを指定します。
vectors
(visualization_msgs/マーカー)
グリッド マップのベクトル データを視覚的なマーカーとして視覚化します。 layer_prefix
パラメーターを使用して、ベクトルのx成分、 y成分、およびz成分を保持するレイヤーを指定します。パラメーターposition_layer
ベクトルの開始点として使用されるレイヤーを定義します。
name: surface_normals
type: vectors
params:
layer_prefix: normal_
position_layer: elevation
scale: 0.06
line_width: 0.005
color: 15600153 # red
occupancy_grid
(nav_msgs/OccupancyGrid)
グリッド マップのレイヤーを占有グリッドとして視覚化します。 layer
パラメータで可視化する層を指定し、 data_min
とdata_max
で上限と下限を指定します。
name: traversability_grid
type: occupancy_grid
params:
layer: traversability
data_min: -0.15
data_max: 0.15
grid_cells
(nav_msgs/GridCells)
グリッド マップのレイヤーをグリッド セルとして視覚化します。視覚化するレイヤーをlayer
パラメーターで指定し、上限と下限をlower_threshold
とupper_threshold
で指定します。
name: elevation_cells
type: grid_cells
params:
layer: elevation
lower_threshold: -0.08 # optional, default: -inf
upper_threshold: 0.08 # optional, default: inf
region
(visualization_msgs/Marker)
グリッドマップの境界を表示します。
name: map_region
type: map_region
params:
color: 3289650
line_width: 0.003
注: カラー値は、連結された整数としての RGB 形式です (各チャネル値は 0 ~ 255)。値は、緑色の例として次のように生成できます (赤: 0、緑: 255、青: 0)。
Grid_map_filtersパッケージには、レイヤー内のデータの計算を実行するためにグリッド マップに適用できるいくつかのフィルターが含まれています。グリッド マップ フィルターは ROS フィルターに基づいており、フィルターのチェーンを YAML ファイルとして構成できることを意味します。さらに、追加のフィルターを作成し、 grid_map_cv
パッケージのInpaintFilter
などの ROS プラグイン メカニズムを通じて利用できるようにすることができます。
いくつかの基本的なフィルターがGrid_map_filtersパッケージで提供されています。
gridMapFilters/ThresholdFilter
Condition_layer が上限または下限のしきい値を超えている場合は、出力レイヤーの値を指定された値に設定します (一度に 1 つのしきい値のみ)。
name: lower_threshold
type: gridMapFilters/ThresholdFilter
params:
condition_layer: layer_name
output_layer: layer_name
lower_threshold: 0.0 # alternative: upper_threshold
set_to: 0.0 # # Other uses: .nan, .inf
gridMapFilters/MeanInRadiusFilter
レイヤーの各セルについて、半径内の平均値を計算します。
name: mean_in_radius
type: gridMapFilters/MeanInRadiusFilter
params:
input_layer: input
output_layer: output
radius: 0.06 # in m.
gridMapFilters/MedianFillFilter
層の各NaNセルについて、半径のあるパッチ内の (有限の) 中央値を計算します。必要に応じて、すでに有限になっている値に対して中央値の計算を適用します。これらの点のパッチ半径は、existing_value_radius によって与えられます。塗りつぶしの計算は、fill_mask がその点に対して有効な場合にのみ実行されることに注意してください。
name: median
type: gridMapFilters/MedianFillFilter
params:
input_layer: input
output_layer: output
fill_hole_radius: 0.11 # in m.
filter_existing_values: false # Default is false. If enabled it also does a median computation for existing values.
existing_value_radius: 0.2 # in m. Note that this option only has an effect if filter_existing_values is set true.
fill_mask_layer: fill_mask # A layer that is used to compute which areas to fill. If not present in the input it is automatically computed.
debug: false # If enabled, the additional debug_infill_mask_layer is published.
debug_infill_mask_layer: infill_mask # Layer used to visualize the intermediate, sparse-outlier removed fill mask. Only published if debug is enabled.
gridMapFilters/NormalVectorsFilter
マップ内のレイヤーの法線ベクトルを計算します。
name: surface_normals
type: gridMapFilters/NormalVectorsFilter
params:
input_layer: input
output_layers_prefix: normal_vectors_
radius: 0.05
normal_vector_positive_axis: z
gridMapFilters/NormalColorMapFilter
法線ベクトル レイヤーに基づいて新しいカラー レイヤーを計算します。
name: surface_normals
type: gridMapFilters/NormalColorMapFilter
params:
input_layers_prefix: normal_vectors_
output_layer: normal_color
gridMapFilters/MathExpressionFilter
グリッド マップのレイヤーを使用して数学的な行列式を解析して評価します。式のドキュメントについては、EigenLab を参照してください。
name: math_expression
type: gridMapFilters/MathExpressionFilter
params:
output_layer: output
expression: acos(normal_vectors_z) # Slope.
# expression: abs(elevation - elevation_smooth) # Surface roughness.
# expression: 0.5 * (1.0 - (slope / 0.6)) + 0.5 * (1.0 - (roughness / 0.1)) # Weighted and normalized sum.
gridMapFilters/SlidingWindowMathExpressionFilter
グリッド マップのレイヤー上のスライディング ウィンドウ内で数学的な行列式を解析して評価します。式のドキュメントについては、EigenLab を参照してください。
name: math_expression
type: gridMapFilters/SlidingWindowMathExpressionFilter
params:
input_layer: input
output_layer: output
expression: meanOfFinites(input) # Box blur
# expression: sqrt(sumOfFinites(square(input - meanOfFinites(input))) ./ numberOfFinites(input)) # Standard deviation
# expression: 'sumOfFinites([0,-1,0;-1,5,-1;0,-1,0].*elevation_inpainted)' # Sharpen with kernel matrix
compute_empty_cells: true
edge_handling: crop # options: inside, crop, empty, mean
window_size: 5 # in number of cells (optional, default: 3), make sure to make this compatible with the kernel matrix
# window_length: 0.05 # instead of window_size, in m
gridMapFilters/DuplicationFilter
グリッド マップのレイヤーを複製します。
name: duplicate
type: gridMapFilters/DuplicationFilter
params:
input_layer: input
output_layer: output
gridMapFilters/DeletionFilter
グリッド マップからレイヤーを削除します。
name: delete
type: gridMapFilters/DeletionFilter
params:
layers: [color, score] # List of layers.
さらに、 grid_map_cvパッケージは次のフィルターを提供します。
gridMapCv/InpaintFilter
OpenCV を使用して、レイヤーの穴を修復/埋めることができます。
name: inpaint
type: gridMapCv/InpaintFilter
params:
input_layer: input
output_layer: output
radius: 0.05 # in m
キネティック | メロディック | ノエティック | |
---|---|---|---|
グリッドマップ | |||
博士 |
キネティック | メロディック | ノエティック | |
---|---|---|---|
グリッドマップ | |||
グリッドマップコア | |||
グリッドマップ_コストマップ_2d | |||
グリッドマップ_CV | |||
グリッドマップデモ | |||
グリッドマップフィルター | |||
グリッドマップローダー | |||
グリッドマップ_メッセージ | |||
グリッドマップ_オクトマップ | |||
グリッドマップ_pcl | |||
グリッドマップロス | |||
グリッドマップ_rviz_plugin | |||
グリッドマップ_sdf | |||
グリッドマップの視覚化 |
バグを報告し、機能をリクエストするには、Issue Tracker を使用してください。