autoware_lidar_transfusion#
目的#
autoware_lidar_transfusion
パッケージは、LiDARデータ(x, y, z、強度)に基づく3Dオブジェクト検出に使用されます。
内部動作/アルゴリズム#
実装は[1]のTransFusionの作業に基づいています。データ処理とネットワーク推論にはTensorRTライブラリを使用しています。
モデルはhttps://github.com/open-mmlab/mmdetection3dを使用してトレーニングしました。
入力/出力#
入力#
名称 | タイプ | 説明 |
---|---|---|
~/input/pointcloud |
sensor_msgs::msg::PointCloud2 |
入力点群。 |
出力#
自己位置推定モジュール
目的:
- センサーからのセンサデータから自己位置を推定する。
- Planningモジュールに自己位置を提供する。
入力:
- IMUデータ
- GNSSデータ
- オドメトリデータ
- カメラ画像(オプション)
出力:
- 自車位置
- 自己位置の不確かさ
アルゴリズム:
自己位置推定モジュールは、次のステップで動作します。
- IMU、GNSS、オドメトリデータの統合。
- カメラ画像(使用可能な場合)を使用した自己位置の強化。
- エKFまたはPFを使用して自己位置と不確かさを推定する。
障害検出モジュール
目的:
- センサーからのデータを処理し、エゴカーの周囲の障害物を検出する。
- Planningモジュールに障害物の情報を提供する。
入力:
- レーダーデータ
- カメラ画像
- LIDARデータ
出力:
- 障害物の位置と形状
- 障害物の速度と加速度
アルゴリズム:
障害検出モジュールは、次のアルゴリズムを使用して障害物を検出します。
- 点群処理: LIDARデータを使用して点群を作成します。
- クラスタリング: 点群をクラスタ(障害物)にグループ化します。
- 分類: カメラ画像とレーダーデータを使用して、クラスタを障害物として分類します。
Planningモジュール
目的:
- 自車位置と障害物の情報に基づき、経路を計画し、次のような制御コマンドを生成する。
- ステアリング角
- アクセル/ブレーキコマンド
入力:
- 自車位置
- 障害物の情報
- 地図データ
出力:
- 制御コマンド
アルゴリズム:
Planningモジュールは、次のアルゴリズムを使用して経路を計画し、制御コマンドを生成します。
- 空間探索法: 次の目的地までの可能な経路を探索します。
- コスト関数: 各経路のコストを計算し、障害物逸脱量、速度逸脱量、加速度逸脱量を考慮します。
- 最適化アルゴリズム: コストが最小となる経路を選択します。
- **'post resampling'` による経路の平滑化。
制御モジュール
目的:
- Planningモジュールから生成された制御コマンドを実行する。
- ステアリングシステムと動力伝達システムを制御する。
入力:
- 制御コマンド
出力:
- 車両の運動(ステアリング角、速度、加速度)
アルゴリズム:
制御モジュールは、PID制御器または状態フィードバックコントローラを使用して制御コマンドを実行します。
名称 | タイプ | 説明 |
---|---|---|
/output/objects |
autoware_perception_msgs::msg::DetectedObjects |
検出されたオブジェクト |
debug/cyclic_time_ms |
tier4_debug_msgs::msg::Float64Stamped |
サイクル時間 (ms) |
debug/pipeline_latency_ms |
tier4_debug_msgs::msg::Float64Stamped |
パイプライン遅延時間 (ms) |
debug/processing_time/preprocess_ms |
tier4_debug_msgs::msg::Float64Stamped |
前処理時間 (ms) |
debug/processing_time/inference_ms |
tier4_debug_msgs::msg::Float64Stamped |
推論時間 (ms) |
debug/processing_time/postprocess_ms |
tier4_debug_msgs::msg::Float64Stamped |
後処理時間 (ms) |
debug/processing_time/total_ms |
tier4_debug_msgs::msg::Float64Stamped |
総処理時間 (ms) |
パラメーター#
TransFusionノード#
Name | Type | Description | Default | Range |
---|---|---|---|---|
trt_precision | string | A precision of TensorRT engine. | fp16 | ['fp16', 'fp32'] |
cloud_capacity | integer | Capacity of the point cloud buffer (should be set to at least the maximum theoretical number of points). | 2000000 | ≥1 |
onnx_path | string | A path to ONNX model file. | $(var model_path)/transfusion.onnx | N/A |
engine_path | string | A path to TensorRT engine file. | $(var model_path)/transfusion.engine | N/A |
densification_num_past_frames | integer | A number of past frames to be considered as same input frame. | 1 | ≥0 |
densification_world_frame_id | string | A name of frame id where world coordinates system is defined with respect to. | map | N/A |
circle_nms_dist_threshold | float | A distance threshold between detections in NMS. | 0.5 | ≥0.0 |
iou_nms_target_class_names | array | An array of class names to be target in NMS. | ['CAR'] | N/A |
iou_nms_search_distance_2d | float | A maximum distance value to search the nearest objects. | 10.0 | ≥0.0 |
iou_nms_threshold | float | A threshold value of NMS using IoU score. | 0.1 | ≥0.0 ≤1.0 |
yaw_norm_thresholds | array | A thresholds array of direction vectors norm, all of objects with vector norm less than this threshold are ignored. | [0.3, 0.3, 0.3, 0.3, 0.0] | N/A |
score_threshold | float | A threshold value of confidence score, all of objects with score less than this threshold are ignored. | 0.2 | ≥0.0 |
TransFusionモデル#
Name | Type | Description | Default | Range |
---|---|---|---|---|
class_names | array | An array of class names will be predicted. | ['CAR', 'TRUCK', 'BUS', 'BICYCLE', 'PEDESTRIAN'] | N/A |
voxels_num | array | A maximum number of voxels [min, opt, max]. | [5000, 30000, 60000] | N/A |
point_cloud_range | array | An array of distance ranges of each class. | [-76.8, -76.8, -3.0, 76.8, 76.8, 5.0] | N/A |
voxel_size | array | Voxels size [x, y, z]. | [0.3, 0.3, 8.0] | N/A |
num_proposals | integer | Number of proposals at TransHead. | 500 | ≥1 |
検出クラスリマッパー#
Name | Type | Description | Default | Range |
---|---|---|---|---|
allow_remapping_by_area_matrix | array | Whether to allow remapping of classes. The order of 8x8 matrix classes comes from ObjectClassification msg. | [0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 1, 0, 1, 0, 0, 0, 0, 0, 0, 0, 1, 0, 0, 0, 0, 0, 0, 0, 1, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0] | N/A |
min_area_matrix | array | Minimum area for specific class to consider class remapping. | [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 12.1, 0.0, 36.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 36.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 36.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0] | N/A |
max_area_matrix | array | Maximum area for specific class to consider class remapping. | [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 36.0, 0.0, 999.999, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 999.999, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 999.999, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0] | N/A |
build_only
オプション#
autoware_lidar_transfusion
ノードには、ONNXファイルからTensorRTエンジンファイルを構築するためのbuild_only
オプションがあります。
Autoware Universeの.param.yaml
ファイルにすべてのROSパラメータを移動することが望ましいですが、build_only
オプションは現在.param.yaml
ファイルに移動されていません。これは、ビルドを事前タスクとして実行するためのフラグとして使用される可能性があるためです。次のコマンドで実行できます。
ros2 launch autoware_lidar_transfusion lidar_transfusion.launch.xml build_only:=true
log_level
オプション#
autoware_lidar_transfusion
のデフォルトのログ重要度レベルは info
です。デバッグの目的では、開発者は log_level
パラメータを使用して重要度のレベルを下げることができます:
ros2 launch autoware_lidar_transfusion lidar_transfusion.launch.xml log_level:=debug
仮定 / 公知の制限#
このライブラリは、生のクラウドデータ (バイト) で動作します。入力ポイントクラウドメッセージのフォーマットは次のとおりであると想定されます。
[
sensor_msgs.msg.PointField(name='x', offset=0, datatype=7, count=1),
sensor_msgs.msg.PointField(name='y', offset=4, datatype=7, count=1),
sensor_msgs.msg.PointField(name='z', offset=8, datatype=7, count=1),
sensor_msgs.msg.PointField(name='intensity', offset=12, datatype=2, count=1)
]
この入力には、他のフィールドが含まれる場合もあります。表示されている形式は必要な最小限です。 デバッグの目的で、次のシンプルなコマンドを使用してポイントクラウド・トピックを検証することができます。
ros2 topic echo <input_topic> --field fields
学習済みモデル#
以下のリンクをクリックすると、学習済みモデルのonnx形式をダウンロードできます。
- TransFusion: transfusion.onnx
このモデルは、TIER IV社内データベース(約 11,000 個のLiDARフレーム)で 50 エポックの学習を行いました。
更新履歴#
(任意) エラー検出と処理#
(任意) パフォーマンス特性評価#
参考文献/外部リンク#
[1] Xuyang Bai, Zeyu Hu, Xinge Zhu, Qingqiu Huang, Yilun Chen, Hongbo Fu and Chiew-Lan Tai. "TransFusion: Robust LiDAR-Camera Fusion for 3D Object Detection with Transformers." arXiv preprint arXiv:2203.11496 (2022).
[2] https://github.com/wep21/CUDA-TransFusion
[3] https://github.com/open-mmlab/mmdetection3d
[4] https://github.com/open-mmlab/OpenPCDet
[5] https://www.nuscenes.org/nuscenes