From 2f140a7d102ac611079f64bbb57ca443cef2b268 Mon Sep 17 00:00:00 2001 From: yamato-ando Date: Thu, 30 Nov 2023 18:29:49 +0900 Subject: [PATCH 01/12] add Lidar Point Cloud Signed-off-by: yamato-ando --- docs/design/autoware-interfaces/components/sensing.md | 10 ++++++++++ 1 file changed, 10 insertions(+) diff --git a/docs/design/autoware-interfaces/components/sensing.md b/docs/design/autoware-interfaces/components/sensing.md index b1f71d233fc..4746c86bb18 100644 --- a/docs/design/autoware-interfaces/components/sensing.md +++ b/docs/design/autoware-interfaces/components/sensing.md @@ -34,6 +34,8 @@ graph TD radar_msgs/RadarScan"):::cls_sen msg_pc_combined_ldr("Combined Lidar Point Cloud sensor_msgs/PointCloud2"):::cls_sen + msg_pc_ldr("Lidar Point Cloud + sensor_msgs/PointCloud2"):::cls_sen msg_pose_gnss("GNSS-INS Pose geometry_msgs/PoseWithCovarianceStamped"):::cls_sen msg_gnssori_sen("GNSS-INS Orientation @@ -60,6 +62,7 @@ graph TD cmp_sen --> msg_pc_combined_rdr cmp_sen --> msg_pc_rdr cmp_sen --> msg_pc_combined_ldr + cmp_sen --> msg_pc_ldr cmp_sen --> msg_pose_gnss cmp_sen --> msg_gnssacc_sen msg_ult_sen --> cmp_per @@ -68,6 +71,7 @@ graph TD msg_pc_rdr --> cmp_per msg_pc_combined_ldr --> cmp_per msg_pc_combined_ldr --> cmp_loc + msg_pc_ldr --> cmp_loc msg_pose_gnss --> cmp_loc msg_gnssori_sen --> cmp_loc msg_gnssvel_sen --> cmp_loc @@ -166,6 +170,12 @@ Lidar pointcloud after preprocessing. Used by the Perception and Localization. - [sensor_msgs/PointCloud2](https://github.com/ros2/common_interfaces/blob/rolling/sensor_msgs/msg/PointCloud2.msg) +### Lidar Point Cloud + +Lidar pointcloud after preprocessing. Used by the Localization. + +- [sensor_msgs/PointCloud2](https://github.com/ros2/common_interfaces/blob/rolling/sensor_msgs/msg/PointCloud2.msg) + ### GNSS-INS pose Initial pose of the ego vehicle from GNSS. Used by the Localization. From 1393d16dd4fc21b74e7dbabcf9b8fd2a2fc2d329 Mon Sep 17 00:00:00 2001 From: yamato-ando Date: Thu, 30 Nov 2023 18:30:34 +0900 Subject: [PATCH 02/12] update node-diagram. rename localization's input pointcloud Signed-off-by: yamato-ando --- ...-node-diagram-autoware-universe.drawio.svg | 6207 ++++++++++++++++- 1 file changed, 6203 insertions(+), 4 deletions(-) diff --git a/docs/design/autoware-architecture/node-diagram/overall-node-diagram-autoware-universe.drawio.svg b/docs/design/autoware-architecture/node-diagram/overall-node-diagram-autoware-universe.drawio.svg index 9d74a28a5a5..87ba1e2a1e5 100644 --- a/docs/design/autoware-architecture/node-diagram/overall-node-diagram-autoware-universe.drawio.svg +++ b/docs/design/autoware-architecture/node-diagram/overall-node-diagram-autoware-universe.drawio.svg @@ -1,4 +1,6203 @@ - - - -
 
 
Planning
Planning
Control
Control
Perception
Perception
Vehicle
Vehicle
Sensing
Sensing
VehicleInterface
VehicleInterface
Localization
Localization
System
System
/diagnostics
/diagnostics
XX1
XX1
X2
X2
X1
X1
S1
S1
/autoware/engage [Engage]
/current_gate_mode [GateMode]
/autoware/engage [Engage]...
/planning/scenario_planning/max_velocity_candidates
[tier4_planning_msgs/msg/VelocityLimit]
/planning/scenario_planning/max_velocity_candidates...
HMI
HMI
HMI
HMI
/api/external/set/command/remote/control: [tier4_external_api_msgs/msg/ControlCommandStamped]
/api/external/set/command/remote/heartbeat: [tier4_external_api_msgs/msg/Heartbeat]
/api/external/set/command/remote/shift: [tier4_external_api_msgs/msg/GearShiftStamped]
/api/external/set/command/remote/turn_signal: [tier4_external_api_msgs/msg/TurnSignalStamped]
/api/external/set/command/remote/control: [tier4_external_api_msgs/msg/ControlCommandStamped]...
HMI
HMI
/vehicle/engage
/vehicle/engage
HMI
HMI
/diagnostics_err
/diagnostics_err
/initialpose
/initialpose
<pose_initializer
_srv>
<pose_initializer...
HMI
HMI
<differential_map_
loader_srv>
<differential_map_...
<partial_map_
loader_srv>
<partial_map_...
pose_twist_fusion_filter/
pose_with_covariance_
no_yawbias
pose_twist_fusion_filter/...
pose_estimator/
pose_with_covariance
pose_estimator/...
/initialpose3d
/initialpose3d
/tf
(map to base_link)
/tf...
/localization/kinematic_state
[nav_msgs/msg/Odometry]
/localization/kinematic_state...
pose_twist_fusion_filter/
pose_with_covariance
pose_twist_fusion_filter/...
/diagnostics
/diagnostics
pose_twist_fusion_filter/
kinematic_state
pose_twist_fusion_filter/...
/map
/vector_map
/map...
/map/
map_projector_info
/map/...
/api/routing/route
/api/routing/route
/default_ad_api/node/routing
/default_ad_api/node/routing
/planning/mission_planning/mission_planner/srv/set_mrm_route,
/planning/mission_planning/mission_planner/srv/clear_mrm_route
/planning/mission_planning/mission_planner/srv/set_mrm_route,...
Map
Map

/perception/object_recognition/detection/
/perception/object_recognition/detection/
/perception/object_recognition/tracking/
/perception/object_recognition/tracking/
LiDAR pipeline (default)
LiDAR pipeline (default)
Camera-LiDAR pipeline
(optional)
Camera-LiDAR pipeline...
Radar pipeline (optional)
Radar pipeline (optional)
/perception/traffic_light_recognition/
/perception/traffic_light_...
Perception
Perception
/perception/object_recognition/objects
/perception/object_recognition/objects
clustering/clusters
clustering/clusters
euclidean_cluster
euclidean_cluster
centerpoint/validation/objects
centerpoint/validation/objects
DNNベースでLiDAR点群に物体のクラス情報を付与するDNNベースでLiDAR点群に物体のクラス情報を付与する
lidar_centerpoint
lidar_centerpoint
高精度地図情報を用いて、trackingされた動物体情報の移動経路予測を行う高精度地図情報を用いて、trackingされた動物体情報の移動経路予測を行う
map_based_
prediction
map_based_...
traffic_light_detection/rough/rois
traffic_light_detection/rough/rois
自己位置および高精度地図情報、自身の走行ルート情報から、信号機のおおよその位置を計算する自己位置および高精度地図情報、自身の走行ルート情報から、信号機のおおよその位置を計算する
traffic_light_map_
based_detector
traffic_light_map_...
objects
objects
画像に含まれる信号機の色を識別する画像に含まれる信号機の色を識別する
traffic_light_
classifier
traffic_light_...
画像処理を用いて信号機の正確な位置を計算する画像処理を用いて信号機の正確な位置を計算する
traffic_light_
ssd_fine_detector
traffic_light_...
route,
vector_map
route,...
detection同士のassignmentを取り,confidenceが高い方を採用する.overlapしたunknown objectはmergeするdetection同士のassignmentを取り,confidenceが高い方を採用する.overlapしたunknown objectはmergeする
object_association
_merger
object_association...
clustering結果の形状を推定するclustering結果の形状を推定する
shape_estimation
shape_estimation
/perception/occupancy_grid_map/
/perception/occupancy_grid_map/
/perception/obstacle_segmentation/
/perception/obstacle_segmentation/
no_ground/oneshot/pointcloud
no_ground/oneshot/pointcloud
range_cropped/pointcloud
range_cropped/pointcloud
アルゴリズムを使って点群から地面を除去します。アルゴリズムを使って点群から地面を除去します。
common_
ground_filter
common_...
occupancy_grid
occupancy_grid
/perception/occupancy_grid_map/map
/perception/occupancy_grid_map/map
全点群データ、地面除去済み点群、occupancy gridの情報を総合的に見て、障害物が存在するかどうかの確率をoccupancy gridマップの形式で計算します。全点群データ、地面除去済み点群、occupancy gridの情報を総合的に見て、障害物が存在するかどうかの確率をoccupancy gridマップの形式で計算します。
probabilistic_
occupancy_grid_map
probabilistic_...
occupancy gridで与えられる障害物存在確率マップの情報をもとに、障害物点群をフィルタリングします。occupancy gridで与えられる障害物存在確率マップの情報をもとに、障害物点群をフィルタリングします。
occupancy_grid_
map_based_outlier_filter
occupancy_grid_...
/perception/obstacle_segmentation/pointcloud
/perception/obstacle_segmentation/pointcloud
crop_box_filter
crop_box_filter
/concatenated/pointcloud
/concatena...
BBox内に存在するobstacle_segmentation後の点群数を用いて,false positiveを除くBBox内に存在するobstacle_segmentation後の点群数を用いて,false positiveを除く
obstacle_pointcloud _based_validator
obstacle_pointcloud _ba...
detection同士のassignmentを取り,confidenceが高い方を採用する.overlapしたunknown objectはmergeするdetection同士のassignmentを取り,confidenceが高い方を採用する.overlapしたunknown objectはmergeする
object_association
_merger
object_association...
DNNベースで画像に物体のクラス情報を付与するDNNベースで画像に物体のクラス情報を付与する
tensorrt_yolox
tensorrt_yolox
/perception/obstacle_segmentation/pointcloud
/perception/obstacle_segmentation/pointcloud
clustering結果に画像のdetection結果をprojectionしてlabelを付与するclustering結果に画像のdetection結果をprojectionしてlabelを付与する
roi_cluster_fusion
roi_cluster_fusion
/rois*
/rois*
clustering/camera_lidar_fusion
/objects
clustering/camera_lidar_fusion...
clustering結果の形状を推定するclustering結果の形状を推定する
shape_estimation
shape_estimation
detection_by
_tracker/objects
detection_by...
tracker内部のclusterをマージし,shape fittingしたbboxを出力するtracker内部のclusterをマージし,shape fittingしたbboxを出力する
detection_by_
tracker_node
detection_by_...
vector mapの情報を用いて,unknown objectをfilterする.lane内のunknown objectのみを残す.vector mapの情報を用いて,unknown objectをfilterする.lane内のunknown objectのみを残す.
object_lanelet_filter
object_lanelet_filter
/map/vector_map
/map/vector_map
pointcloud_map_filtered/pointcloud
pointcloud_map_filtered/pointcloud
compare_map_filter
compare_map_filter
/perception/obstacle_segmentation/pointcloud
/perception/obstacle_segmentation/pointcloud
map
map
lanelet_filtered_objects
lanelet_filtered_objects
The object_lanelet_filter is a node that filters detected object by using vector map. The objects only inside of the vector map will be published.The object_lanelet_filter is a node that filters detected object by using vector map. The objects only inside of the vector map will be published.
object_lanelet_filter
object_lanelet_filter
far_objects
far_objects
This package can make clustered objects from radar DetectedObjects, the objects which is converted from RadarTracks by radar_tracks_msgs_converter and is processed by noise filter. In other word, this package can combine multiple radar detections from one object into one and adjust class and size.This package can make clustered objects from radar DetectedObjects, the objects which is converted from RadarTracks by radar_tracks_msgs_converter and is processed by noise filter. In other word, this package can combine multiple radar detections from one object into one and adjust class and size.
radar_object_clustering
radar_object_clustering
far_high_speed_objects
far_high_speed_objects
object_range_splitter is a package to divide detected objects into two messages by the distance from the origin.object_range_splitter is a package to divide detected objects into two messages by the distance from the origin.
object_range_splitter
object_range_splitter
high_speed_objects
high_speed_objects
This package contains a object filter module for autoware_auto_perception_msgs/msg/DetectedObject. This package can split DetectedObjects into two messages by object's speed.This package contains a object filter module for autoware_auto_perception_msgs/msg/DetectedObject. This package can split DetectedObjects into two messages by object's speed.
object_velocity_splitter
object_velocity_splitter
noise_filtered_objects
noise_filtered_objects
This package contains a radar noise filter module for autoware_auto_perception_msgs/msg/DetectedObject. This package can filter the noise objects which cross to the ego vehicle.This package contains a radar noise filter module for autoware_auto_perception_msgs/msg/DetectedObject. This package can filter the noise objects which cross to the ego vehicle.
radar_crossing_objects_
noise_filter
radar_crossing_objects_...
/sensing/radar/detected_objects
/sensing/radar/detected_objects
far_objects
far_objects
クラス+位置+形状情報に対してtrackingを行う。(最近上流が速度情報も出せるようになってきたらしい)クラス+位置+形状情報に対してtrackingを行う。(最近上流が速度情報も出せるようになってきたらしい)
multi_object_
tracker
multi_object_...
This package provides a radar object tracking node that processes sequences of detected objects to assign consistent identities to them and estimate their velocities.This package provides a radar object tracking node that processes sequences of detected objects to assign consistent identities to them and estimate their velocities.
radar_object_tracker
radar_object_tracker
This package try to merge two tracking objects from different sensor.This package try to merge two tracking objects from different sensor.
decorative_tracking_
merger
decorative_tracking_...
/sensing/lidar/top/
pointcloud_raw
/sensing/lidar/top/...
交通ルールをもとに、経路上の最大速度を決定します。各モジュールは、自身の計算した最大速度と上段の結果を比較し、小さい速度を経路上に書き込みます。交通ルールをもとに、経路上の最大速度を決定します。各モジュールは、自身の計算した最大速度と上段の結果を比較し、小さい速度を経路上に書き込みます。
behavior_velocity_planner
behavior_velocity_planner
Planning
Planning
/planning/scenario_planning/trajectory [Trajectory]
/planning/scenario_planning/trajectory [Trajectory]
motion_planning/obstacle_avoidance_planner/trajectory [Trajectory]
motion_planning/obstacle_avoidance_planner/trajectory [Trajectory]
車両形状や走行可能領域を考慮して、経路の平滑化を行う。障害物も避けるが、long historyで最近は回避機能はoffになっています。車両形状や走行可能領域を考慮して、経路の平滑化を行う。障害物も避けるが、long historyで最近は回避機能はoffになっています。
obstacle_
avoidance_planner
obstacle_...
motion_planning/obstacle_velocity_limiter/trajectory [Trajectory]
motion_planning/obstacle_velocity_limiter/trajectory [Trajectory]
自車が停止しているときに、周囲の障害物を確認し、近くに障害物がいる場合は車両を発進させない。自車が停止しているときに、周囲の障害物を確認し、近くに障害物がいる場合は車両を発進させない。
obstacle_velocity_limiter
obstacle_velocity_limit...
障害物停止・前車追従・近傍障害物減速の複数の機能を持ち、機能に応じて経路上に速度を埋め込む。 目標経路上に障害物点がある場合は停止、経路近くに障害物点群がある場合は減速、前方に車両が居る場合は前車追従。障害物停止・前車追従・近傍障害物減速の複数の機能を持ち、機能に応じて経路上に速度を埋め込む。 目標経路上に障害物点がある場合は停止、経路近くに障害物点群がある場合は減速、前方に車両が居る場合は前車追従。
obstacle_stop_
planner
obstacle_stop_...
障害物点群や地図の走行可能エリアの情報から、駐車プランナー用のコストマップを生成する。障害物点群や地図の走行可能エリアの情報から、駐車プランナー用のコストマップを生成する。
costmap_generator
costmap_generator
apiとautoware.iv内部から送られてくる制約付き減速指示を受け取り、整合性をとるapiとautoware.iv内部から送られてくる制約付き減速指示を受け取り、整合性をとる
external_velocity_
limit_selector
external_velocity_...
/planning/scenario_planning/max_velocity
[tier4_planning_msgs/msg/VelocityLimit]
/planning/scenario_planning/max_velocity...
/planning/scenario_planning/max_velocity_candidates
[tier4_planning_msgs/msg/VelocityLimit]
/planning/scenario_planning/max_velocity_candidates...
lane_driving/trajectory [Trajectory]
lane_driving/trajectory [Trajectory]
trajectory [Trajectory]
trajectory [Trajectory]
いまのrouteおよび地図情報から、LaneDriving / Parkingのシナリオを判断し、どちらの経路を使うかを切り替える。いまのrouteおよび地図情報から、LaneDriving / Parkingのシナリオを判断し、どちらの経路を使うかを切り替える。
scenario_selector
scenario_selector
/planning/scenario_planning/motion_velocity_smoother/trajectory [Trajectory]
/planning/scenario_planning/motion_velocity_smoother/trajectory [Trajectory]
経路に埋め込まれた最大速度を超過しないように、うまい具合で速度を平滑化する。カーブでの減速もここで行う。経路に埋め込まれた最大速度を超過しないように、うまい具合で速度を平滑化する。カーブでの減速もここで行う。
motion_velocity_
smoother
motion_velocity_...
<Lane Driving>
<Lane Driving>
/planning/mission_planning/route
[autoware_auto_planning_msgs/HADMapRoute]
/planning/mission_planning/route...
/planning/scenario_planning/modified_goal
/planning/scenario_planning/modified_goal
/planning/mission_planning/goal,
/planning/mission_planning/checkpoint
/planning/mission_planning/goal,...
/planning/mission_planning/
route_state
/planning/mission_planning/...
高精度地図情報をもとに、自己位置からゴールまでのルートを計算します。高精度地図情報をもとに、自己位置からゴールまでのルートを計算します。
mission_planner
mission_planner
behavior_planning/path_with_lane_id
behavior_planning/path_with_lane_id
コストマップとゴールから、自車の走行ルートを計算する。いまはHA*を使ってる。コストマップとゴールから、自車の走行ルートを計算する。いまはHA*を使ってる。
freespace_planner
freespace_planner
costmap_generator/occupancy_grid
costmap_generator/occupancy_grid
behavior_planning/path
behavior_planning/path
<Parking>
<Parking>
parking/trajectory [Trajectory]
parking/trajectory [Trajectory]
自車が停止しているときに、周囲の障害物を確認し、近くに障害物がいる場合は車両を発進させない。自車が停止しているときに、周囲の障害物を確認し、近くに障害物がいる場合は車両を発進させない。
surround_obstacle_checker
surround_obstacle_checker
交通ルールをもとに、経路上の最大速度を決定します。各モジュールは、自身の計算した最大速度と上段の結果を比較し、小さい速度を経路上に書き込みます。交通ルールをもとに、経路上の最大速度を決定します。各モジュールは、自身の計算した最大速度と上段の結果を比較し、小さい速度を経路上に書き込みます。
behavior_path_planner
behavior_path_planner
遠隔からの司令をもとに幅寄せを行います。遠隔からの司令をもとに幅寄せを行います。
side_shift
side_shift
ルート情報をもとに路肩への幅寄せ、路肩からの発進を行います。ルート情報をもとに路肩への幅寄せ、路肩からの発進を行います。
pull_over/out
pull_over/out
ルート情報や障害物情報をもとに、障害物回避を実行します。ルート情報や障害物情報をもとに、障害物回避を実行します。
obstacle_avoidance
obstacle_avoidance
ルート情報や障害物情報をもとに、レーンチェンジを実行します。ルート情報や障害物情報をもとに、レーンチェンジを実行します。
lane_change
lane_change
ルート情報をもとに走行経路を作成します。ルート情報をもとに走行経路を作成します。
lane_following
lane_following
Check the trajectory and stop publishing it if it is unsafe.Check the trajectory and stop publishing it if it is unsafe.
planning_validator
planning_validator
/planning/turn_indicators_cmd [TurnIndicatorsCommand]
/planning/hazard_lights_cmd [HazardLightsCommand]
/planning/turn_indicators_cmd [TurnIndicatorsCommand]...
path_smoother/path
path_smoother/path
車両形状や走行可能領域を考慮して、経路の平滑化を行う。障害物も避けるが、long historyで最近は回避機能はoffになっています。車両形状や走行可能領域を考慮して、経路の平滑化を行う。障害物も避けるが、long historyで最近は回避機能はoffになっています。
path_smoother
path_smoother
/default_ad_api/helpers/
routing_adaptor
/default_ad_api/helpers/...
/planning/mission_planning/set_route,
/planning/mission_planning/set_route_points,
/planning/mission_planning/clear_route
/planning/...
/planning/mission_planning/change_route,
/planning/mission_planning/change_route_points
/planning/mission_planning/change_route,...
/api/routing/set_route
/api/routi...
/api/routing/change_route
/api/routing/change_route
/system/operation_mode/change_operation_mode
/system/operation_mode/change_operation_mode
/api/routing/clear_route
/api/routing/clear_route
/api/routing/
set_route_points
/api/routi...
/api/routing/
change_route_points
/api/routing/...
/rviz/routing/
rough_goal
/rviz/routing/...
/rviz/routing/reroute
/rviz/routing/reroute
/rviz
/rviz
/autoware/state
/autoware/state
/default_ad_api/node/
autoware_state
/default_ad_api/node...
<depricated>
<depricated>
/api/routing/state
/api/routing/state
停止禁止区域内で停止しないように、区域手前での進行・停止判断を行います。停止禁止区域内で停止しないように、区域手前での進行・停止判断を行います。
no_stopping_area
no_stopping_area
地図情報および動物体情報から、交差点での停止/発進の判定を行います。地図情報および動物体情報から、交差点での停止/発進の判定を行います。
intersection
intersection
信号の色に応じて停止/発進の指示をします信号の色に応じて停止/発進の指示をします
traffic_light
traffic_light
右左折時に車両後方の巻き込み確認を行い、衝突の危険がある場合は停止します。右左折時に車両後方の巻き込み確認を行い、衝突の危険がある場合は停止します。
blind_spot
blind_spot
規定された停止線で一時停止を行います規定された停止線で一時停止を行います
no_drivable_lane
no_drivable_lane
規定された停止線で一時停止を行います規定された停止線で一時停止を行います
run_out
run_out
規定された停止線で一時停止を行います規定された停止線で一時停止を行います
merge_from_private
merge_from_private
地図情報および動物体情報から、死角手前での減速を行います。地図情報および動物体情報から、死角手前での減速を行います。
occlusion_spot
occlusion_spot
横断歩道に人が居る、もしくは侵入しようとしてきている場合に、横断歩道手前で停止します。近くに人が居る場合は徐行します。横断歩道に人が居る、もしくは侵入しようとしてきている場合に、横断歩道手前で停止します。近くに人が居る場合は徐行します。
cross_walk
cross_walk
規定エリア内の障害物点群がある場合に、対応する位置で停止します規定エリア内の障害物点群がある場合に、対応する位置で停止します
detection_area
detection_area
規定された停止線で一時停止を行います規定された停止線で一時停止を行います
stop_line
stop_line
信号の色に応じて停止/発進の指示をします信号の色に応じて停止/発進の指示をします
virtual_traffic_light
virtual_traffic_li...
規定された停止線で一時停止を行います規定された停止線で一時停止を行います
speed_bump
speed_bump
規定された停止線で一時停止を行います規定された停止線で一時停止を行います
walkway
walkway
規定された停止線で一時停止を行います規定された停止線で一時停止を行います
out_of_lane
out_of_lane
fusion/traffic_signals
fusion/traffic_signals
traffic_light_multi_camera_fusion performs traffic light signal fusion which can be summarized as the following two tasks: Multi-Camera-Fusion: performed on single traffic light signal detected by different cameras. Group-Fusion: performed on traffic light signals within the same group, which means traffic lights sharing the same regulatory element id defined in lanelet2 map.traffic_light_multi_camera_fusion performs traffic light signal fusion which can be summarized as the following two tasks: Multi-Camera-Fusion: performed on single traffic light signal detected by different cameras. Group-Fusion: performed on traffic light signals within the same group, which means traffic lights sharing the same regulatory element id defined in lanelet2 map.
traffic_light_
multi_camera_fusion
traffic_light_...
classification/traffic_signals
classification/traffic_signals
traffic_light_occlusion_predictor receives the detected traffic lights rois and calculates the occlusion ratios of each roi with point cloud. traffic_light_occlusion_predictor receives the detected traffic lights rois and calculates the occlusion ratios of each roi with point cloud.
traffic_light_
occlusion_predictor
traffic_light_...
classification/classified/traffic_signals
classification/classified/traffic_signals
internal/traffic_signals
internal/traffic_signals
crosswalk_traffic_light_estimator is a module that estimates pedestrian traffic signals from HDMap and detected vehicle traffic signals. crosswalk_traffic_light_estimator is a module that estimates pedestrian traffic signals from HDMap and detected vehicle traffic signals.
crosswalk_traffic_
light_estimator
crosswalk_traffic_...
traffic_light_states
traffic_light_states
This package receives traffic signals from perception and external (e.g., V2X) components and combines them using either a confidence-based or a external-preference based approach. This package receives traffic signals from perception and external (e.g., V2X) components and combines them using either a confidence-based or a external-preference based approach.
traffic_light_arbiter
traffic_light_arbiter
trajectory_follower
trajectory_follower
Control
Control
/control/trajectory_follower/control_cmd
[AckermannControlCommand]
/control/trajectory_follower/control_cmd...
経路追従のための目標ステア角とステア角速度を計算します。目標速度と加速度は経路に埋め込まれた値をそのまま出力します。経路追従のための目標ステア角とステア角速度を計算します。目標速度と加速度は経路に埋め込まれた値をそのまま出力します。
lateral_controller
lateral_controller
経路の目標速度に沿うための目標加速度を計算します。遅延補正や停止時のブレーキ抜き操作も行います。経路の目標速度に沿うための目標加速度を計算します。遅延補正や停止時のブレーキ抜き操作も行います。
longitudinal_controller
longitudinal_controller
指示モードに応じて、複数のコマンドの中から後段に渡すコマンドを選択します。指示モードに応じて、複数のコマンドの中から後段に渡すコマンドを選択します。
vehicle_cmd_gate
vehicle_cmd_gate
control/command/control_cmd
 [AckermannControlCommand]
control/command/control_cmd...
/control/shift_decider/gear_cmd
[GearCommand]
/control/shift_decider/gear_cmd...
遠隔から来たコマンド(アクセル/ブレーキ)を目標速度/加速度の信号に変換します遠隔から来たコマンド(アクセル/ブレーキ)を目標速度/加速度の信号に変換します
external_cmd_
converter
external_cmd_...
/external/selected/external_control_cmd
 [tier4_external_api_msgs/msg/ControlCommandStamped]
/external/selected/external_control_cmd...
external_cmd_
selector
external_cmd_...
/api/external/set/command/remote/control 
   [tier4_external_api_msgs/msg/ControlCommandStamped]
/api/external/set/command/remote/shift
   [tier4_external_api_msgs/msg/GearShiftStamped]
/api/external/set/command/remote/turn_signal
   [tier4_external_api_msgs/msg/TurnSignalStamped]
/api/external/set/command/remote/control...
/current_gate_mode [GateMode]
/gear_cmd [GearCommand]
/turn_indicators_cmd  [TurnIndicatorCommand]
/hazard_lights_cmd  [HazardLightsCommand]
/vehicle_emergency_cmd [VehicleEmergencyStamped]
/current_gate_mode [GateMode]...
ヤマハのGCとのインターフェースヤマハのGCとのインターフェース
g30_interface
g30_interface
速度・加速度の目標値を、車両特有の制御信号(アクセル/ブレーキ等)に変換します速度・加速度の目標値を、車両特有の制御信号(アクセル/ブレーキ等)に変換します
raw_vehicle_cmd_
converter
raw_vehicle_cmd_...
/vehicle/command/actuation_cmd
/vehicle/command/actuation_cmd
pacmodとのinterfaced。LexusとかJapanTaxiとか。pacmodとのinterfaced。LexusとかJapanTaxiとか。
pacmod_interface
pacmod_interface
VehicleInterface
VehicleInterface
/vehicle/status/velocity_status
/vehicle/status/steering_status
/vehicle/status/turn_indicators_status
/vehicle/status/gear_status
/vehicle/status/control_mode
/vehicle/status/actuation_status
/vehicle/s...
Autowareと車両のinterfaceです。データの変換が主なタスクです。Autowareと車両のinterfaceです。データの変換が主なタスクです。
    vehicle_interface
    vehicle_interface
accel_map_calibrator
accel_map_calibrator
/pacmod/**
/pacmod/**
Vehicle
Vehicle
<CAN>
<CAN>
ASといろいろあったよASといろいろあったよ
JapanTaxi
JapanTaxi
pacmod3
pacmod3
ゴルフカート!!ゴルフカート!!
YMC GolfCart
YMC GolfCart
external/traffic_signals
external/traffic_signals
Radar sensing pipeline
Radar sensing pipeline
Camera sensing pipeline
Camera sensing pipeline
top/velodyne_packets
top/velodyne_packets
velodyneのdriverです。VLP16, VLP32, VLS128, Livoxなどなど、たくさん種類があります。velodyneのdriverです。VLP16, VLP32, VLS128, Livoxなどなど、たくさん種類があります。
lidar_driver
lidar_driver
top/rectified/pointcloud
top/rectified/pointcloud
自車の回転によって生じたLiDAR点群の歪みを補正する。(リンクこれで合ってるっけ?)自車の回転によって生じたLiDAR点群の歪みを補正する。(リンクこれで合ってるっけ?)
fix_distortion
fix_distortion
top/pointcloud_raw
top/pointcloud_raw
velodyneのpacketをpointcloud型に変更するvelodyneのpacketをpointcloud型に変更する
packets_to_
pointcloud
packets_to_...
top/self_cropped/pointcloud
top/self_cropped/pointcloud
自車の領域内にある点群を除去する。自車の領域内にある点群を除去する。
crop_box_
filter_self
crop_box_...
top/mirror_cropped/pointcloud
top/mirror_cropped/pointcloud
自車のサイドミラーの部分に当たった点群を除去する自車のサイドミラーの部分に当たった点群を除去する
crop_box_
filter_mirror
crop_box_...
点群のノイズ処理を行う (同一リングから得られたLiDARの点をクラスタリングし、点群数の少ないクラスタに属する点群はノイズとして除去される)点群のノイズ処理を行う (同一リングから得られたLiDARの点をクラスタリングし、点群数の少ないクラスタに属する点群はノイズとして除去される)
ring_outlier_filter
ring_outlier_filter
lidar/*/velodyne_packets
lidar/*/velodyne_packets
lidar_drivers
(left,right,front_right, front_left,rear)
lidar_drivers...
*/rectified/pointcloud
*/rectified/pointcloud
自車の回転によって生じたLiDAR点群の歪みを補正する。(リンクこれで合ってるっけ?)自車の回転によって生じたLiDAR点群の歪みを補正する。(リンクこれで合ってるっけ?)
fix_distortion
fix_distortion
*/pointcloud_raw
*/pointcloud_raw
velodyneのpacketをpointcloud型に変更するvelodyneのpacketをpointcloud型に変更する
packets_to_
pointcloud
packets_to_...
*/self_cropped/pointcloud
*/self_cropped/pointcloud
自車の領域内にある点群を除去する。自車の領域内にある点群を除去する。
crop_box_
filter_self
crop_box_...
*/mirror_cropped/pointcloud
*/mirror_cropped/pointcloud
自車のサイドミラーの部分に当たった点群を除去する自車のサイドミラーの部分に当たった点群を除去する
crop_box_
filter_mirror
crop_box_...
点群のノイズ処理を行う (同一リングから得られたLiDARの点をクラスタリングし、点群数の少ないクラスタに属する点群はノイズとして除去される)点群のノイズ処理を行う (同一リングから得られたLiDARの点をクラスタリングし、点群数の少ないクラスタに属する点群はノイズとして除去される)
ring_outlier_filter
ring_outlier_filter
concatenated/pointcloud
concatenated/pointcloud
複数のLiDAR点群をまとめて1つにする複数のLiDAR点群をまとめて1つにする
concat_filter
concat_filter
MGRS座標系への変換MGRS座標系への変換
gnss_poser
gnss_poser
gnssのdriverですgnssのdriverです
gnss_driver
gnss_driver
imuのdriverですimuのdriverです
imu_driver
imu_driver
/sensing/imu/imu_raw
/sensing/imu/imu_raw
/sensing/lidar/pointcloud
/sensing/lidar/pointcloud
/sensing/lidar/
concatenated/pointcloud
/sensing/lidar/...
/sensing/gnss/
pose_with_covariance
/sensing/gnss/...
ヨーレートのバイアス除去とかをするノードヨーレートのバイアス除去とかをするノード
imu_corrector
imu_corrector
/sensing/imu/imu_data
/sensing/imu/imu_data
Sensing
Sensing
/sensing/radar/detected_objects
/sensing/radar/detected_objects
radar_relay
radar_relay
*/detected_objects
*/detected_objects
This package convert from radar_msgs/msg/RadarTracks into autoware_auto_perception_msgs/msg/DetectedObject and autoware_auto_perception_msgs/msg/TrackedObject.This package convert from radar_msgs/msg/RadarTracks into autoware_auto_perception_msgs/msg/DetectedObject and autoware_auto_perception_msgs/msg/TrackedObject.
radar_tracks_
msg_converter
radar_tracks_...
*/filtered_objects
*/filtered_objects
This package contains a radar object filter module for radar_msgs/msg/RadarTrack. This package can filter noise objects in RadarTracks.This package contains a radar object filter module for radar_msgs/msg/RadarTrack. This package can filter noise objects in RadarTracks.
radar_tracks_
noise_filter
radar_tracks_...
*/objects_raw
*/objects_raw
radar_driver
radar_driver
Text
Text
/sensing/camera/
camera*/image_rect_color
/sensing/camera/...
camera drivercamera driver
camera_driver
camera_driver
/sensing/camera/
camera*/image_raw
/sensing/camera/...
camera drivercamera driver
camera_driver
camera_driver
/sensing/camera/
camera*/image_raw
/sensing/camera/...
/sensing/camera/
camera*/image_raw
/sensing/camera/...
LiDAR sensing pipeline
LiDAR sensing pipeline
GNSS sensing pipeline
GNSS sensing pipeline
IMU sensing pipeline
IMU sensing pipeline
Localization
Localization
GNSS / Userからラフな初期位置を受け取り、NDT+モンテカルロ法で正確な自己位置を推定して出力する。NDTとはserviceでやり取りする。GNSS / Userからラフな初期位置を受け取り、NDT+モンテカルロ法で正確な自己位置を推定して出力する。NDTとはserviceでやり取りする。
pose_initializer
pose_initializer
LiDARの点群とpointcloud_mapとのマッチングを行い、自己位置を計算するLiDARの点群とpointcloud_mapとのマッチングを行い、自己位置を計算する
ndt_scan_matcher
ndt_scan_matcher
localization_error_monitor
localization_error_monitor
Overwrite vx=0 and wz=0 when the vehicle wheel speed is zero to indicate the stop condition.Overwrite vx=0 and wz=0 when the vehicle wheel speed is zero to indicate the stop condition.
stop_filter
stop_filter
twist_estimator/twist_with_covariance
twist_estimator/twist_with_covariance
車両速度とimuを統合する。いまは確か、ただ単にvx=vehicle, wz=imuだった気がする。車両速度とimuを統合する。いまは確か、ただ単にvx=vehicle, wz=imuだった気がする。
gyro_odometer
gyro_odometer
vehicle_velocity_converter/
twist_with_covariance
vehicle_velocity_converter/...
車両速度とimuを統合する。いまは確か、ただ単にvx=vehicle, wz=imuだった気がする。車両速度とimuを統合する。いまは確か、ただ単にvx=vehicle, wz=imuだった気がする。
vehicle_velocity_
converter
vehicle_velocity_...
Estimate ego vehicle's position, orientation, and velocity by EKF algorithm.Estimate ego vehicle's position, orientation, and velocity by EKF algorithm.
ekf_localizer
ekf_localizer
measurement_range/pointcloud
measurement_range/pointcloud
一定範囲内のLiDAR点群のみを切り取って出力する。ホントは遠くまで見たいけど、歪みの影響が大きくなったり、そもそも遠方の点群地図がなかったりするので、近くだけを見てる。一定範囲内のLiDAR点群のみを切り取って出力する。ホントは遠くまで見たいけど、歪みの影響が大きくなったり、そもそも遠方の点群地図がなかったりするので、近くだけを見てる。
crop_box_filter_
measurement_range
crop_box_filter_...
voxel_grid_downsample/pointcloud
voxel_grid_downsample/pointcloud
立体格子の点群密度が一様になるように点群を間引く。点群密度が正規化されるため、NDTのロバスト化に一役買っている。立体格子の点群密度が一様になるように点群を間引く。点群密度が正規化されるため、NDTのロバスト化に一役買っている。
voxel_grid_
downsample_filter
voxel_grid_...
点群数が一定以下になるようにランダムに間引く。基本的にはvoxel grid filterで丁度いいくらい点群数になるように調整してあり、点群数のlimiter的な立ち位置が強い 点群数が一定以下になるようにランダムに間引く。基本的にはvoxel grid filterで丁度いいくらい点群数になるように調整してあり、点群数のlimiter的な立ち位置が強い
random_
downsample_filter
random_...
downsample/pointcloud
downsample/pointcloud
/map/vector_map
/map/vector_map
near_objects
near_objects
/perception/object_recognition/
/perception/object_recognition/
/sensing/camera/
camera*/image_rect_color
/sensing/camera/...
/vehicle/status/velocity_report
/vehicle/status/velocity_report
各々データを監視し、異常があればdiagで通知します各々データを監視し、異常があればdiagで通知します
system_monitors
system_monitors
System
System
autoware_process_
monitor
autoware_process_...
autoware_gpu_
monitor
autoware_gpu_...
autoware_mem_
monitor
autoware_mem_...
autoware_hdd_
monitor
autoware_hdd_...
autoware_net_
monitor
autoware_net_...
autoware_ntp_
monitor
autoware_ntp_...
/system/emergency/hazard_status
/system/emergency/hazard_status
system_error_
monitor
system_error_...
/system/emergency/control_cmd [AckermannControlCommand]
/system/emergency/gear_cmd [GearCommand]
/system/emergency/hazard_lights_cmd [HazardLightsCommand]
/system/emergency/emergency_state [EmergencyStateStamped]
/system/emergency/control_cmd [AckermannControlCommand]...
なにかしてますなにかしてます
emergency_handler
emergency_handler
/autoware/state
/autoware/state
/diagnostics
/diagnostics
なにかしてますなにかしてます
ad_service_
state_monitor
ad_service_...
/control/current_gate_mode
/vehicle/status/control_mode
/autoware/state
/control/c...
    /control/command/control_cmd
    /control/trajectory_follower/control_cmd
    /initialpose2d
    /localization/kinematic_state
    /map/pointcloud_map
    /map/vector_map
    /perception/object_recognition/objects
    /planning/mission_planning/route
    /planning/scenario_planning/trajectory
    /system/emergency/control_cmd
    /vehicle/status/control_mode
    /vehicle/status/steering_status
    /vehicle/status/velocity_status
/contr...
/autoware/engage
/autoware/engage
/planning/
mission_planning/goal
/planning/...
Autoware
Autoware
制御出力に応じてギア変更のコマンドを出力します制御出力に応じてギア変更のコマンドを出力します
shift_decider
shift_decider
/diagnostics
/diagnostics
MPCの出す予測経路と、laneletのレーン情報を用いて、車両がレーン外に出ようとしているかどうかを判定する。diag出力をerror_monitorに送り、逸脱判断字は停止する(option)MPCの出す予測経路と、laneletのレーン情報を用いて、車両がレーン外に出ようとしているかどうかを判定する。diag出力をerror_monitorに送り、逸脱判断字は停止する(option)
lane_departure_
checker
lane_departure_...
prediced_path
prediced_path
map_projection_
loader
map_projection_...
lanelet2_map_loader
lanelet2_map_loader
pointcloud_map_
loader
pointcloud_map_...
Text is not SVG - cannot display
\ No newline at end of file + + + + + + + +
+
+
+
+
+
+
+ + +
+
+ + + + +
+
+
+ Planning +
+
+
+
+ + Planning + +
+
+ + + + +
+
+
+ Control +
+
+
+
+ + Control + +
+
+ + + + +
+
+
+ Perception +
+
+
+
+ + Perception + +
+
+ + + + +
+
+
+ Vehicle +
+
+
+
+ + Vehicle + +
+
+ + + + +
+
+
+ Sensing +
+
+
+
+ + Sensing + +
+
+ + + + +
+
+
+ VehicleInterface +
+
+
+
+ + VehicleInterface + +
+
+ + + + +
+
+
+ Localization +
+
+
+
+ + Localization + +
+
+ + + + +
+
+
+ System +
+
+
+
+ + System + +
+
+ + + + + +
+
+
+ /diagnostics +
+
+
+
+ + /diagnostics + +
+
+ + + + +
+
+
+ XX1 +
+
+
+
+ + XX1 + +
+
+ + + + +
+
+
+ X2 +
+
+
+
+ + X2 + +
+
+ + + + +
+
+
+ X1 +
+
+
+
+ + X1 + +
+
+ + + + +
+
+
+ S1 +
+
+
+
+ + S1 + +
+
+ + + + + +
+
+
+
+ /autoware/engage [Engage] +
+
+ /current_gate_mode [GateMode] +
+
+
+
+
+ + /autoware/engage [Engage]... + +
+
+ + + + + +
+
+
+ /planning/scenario_planning/max_velocity_candidates +
+ [tier4_planning_msgs/msg/VelocityLimit] +
+
+
+
+ + /planning/scenario_planning/max_velocity_candidates... + +
+
+ + + + + + +
+
+
+ HMI +
+
+
+
+ + HMI + +
+
+ + + + +
+
+
+ HMI +
+
+
+
+ + HMI + +
+
+ + + + + +
+
+
+ + /api/external/set/command/remote/control: [tier4_external_api_msgs/msg/ControlCommandStamped] + +
+ + /api/external/set/command/remote/heartbeat: [tier4_external_api_msgs/msg/Heartbeat] + +
+ + /api/external/set/command/remote/shift: [tier4_external_api_msgs/msg/GearShiftStamped] + +
+ + /api/external/set/command/remote/turn_signal: [tier4_external_api_msgs/msg/TurnSignalStamped] + +
+
+
+
+ + /api/external/set/command/remote/control: [tier4_external_api_msgs/msg/ControlCommandStamped]... + +
+
+ + + + +
+
+
+ HMI +
+
+
+
+ + HMI + +
+
+ + + + + + + + + + + +
+
+
+ /vehicle/engage +
+
+
+
+ + /vehicle/engage + +
+
+ + + + +
+
+
+ HMI +
+
+
+
+ + HMI + +
+
+ + + + + +
+
+
+ /diagnostics_err +
+
+
+
+ + /diagnostics_err + +
+
+ + + + + + + +
+
+
+ /initialpose +
+
+
+
+ + /initialpose + +
+
+ + + + +
+
+
+ <pose_initializer +
+ _srv> +
+
+
+
+ + <pose_initializer... + +
+
+ + + + +
+
+
+ HMI +
+
+
+
+ + HMI + +
+
+ + + + +
+
+
+ <differential_map_ +
+ loader_srv> +
+
+
+
+ + <differential_map_... + +
+
+ + + + +
+
+
+ <partial_map_ +
+ loader_srv> +
+
+
+
+ + <partial_map_... + +
+
+ + + + + +
+
+
+ pose_twist_fusion_filter/ +
+ pose_with_covariance_ +
+ no_yawbias +
+
+
+
+ + pose_twist_fusion_filter/... + +
+
+ + + + + +
+
+
+ pose_estimator/ +
+ pose_with_covariance +
+
+
+
+ + pose_estimator/... + +
+
+ + + + + +
+
+
+ /initialpose3d +
+
+
+
+ + /initialpose3d + +
+
+ + + + + +
+
+
+ /tf +
+ (map to base_link) +
+
+
+
+ + /tf... + +
+
+ + + + + +
+
+
+ /localization/kinematic_state +
+ [nav_msgs/msg/Odometry] +
+
+
+
+ + /localization/kinematic_state... + +
+
+ + + + + +
+
+
+ pose_twist_fusion_filter/ +
+ pose_with_covariance +
+
+
+
+ + pose_twist_fusion_filter/... + +
+
+ + + + + +
+
+
+ /diagnostics +
+
+
+
+ + /diagnostics + +
+
+ + + + + +
+
+
+ pose_twist_fusion_filter/ +
+ kinematic_state +
+
+
+
+ + pose_twist_fusion_filter/... + +
+
+ + + + + +
+
+
+ /map +
+ /vector_map +
+
+
+
+ + /map... + +
+
+ + + + + + + +
+
+
+ /map/ +
+ map_projector_info +
+
+
+
+ + /map/... + +
+
+ + + + + +
+
+
+ /api/routing/route +
+
+
+
+ + /api/routing/route + +
+
+ + + + +
+
+
+ /default_ad_api/node/routing +
+
+
+
+ + /default_ad_api/node/routing + +
+
+ + + + + +
+
+
+ /planning/mission_planning/mission_planner/srv/set_mrm_route, +
+ + /planning/mission_planning/mission_planner/srv/clear_mrm_route + +
+
+
+
+
+ + /planning/mission_planning/mission_planner/srv/set_mrm_route,... + +
+
+ + + + +
+
+
+ + Map +
+
+
+
+
+
+ + Map + +
+
+ + + + +
+
+
+
+
+
+
+
+
+
+ + +
+
+ + + + +
+
+
+
+ /perception/object_recognition/detection/ +
+
+
+
+
+
+ + /perception/object_recognition/detection/ + +
+
+ + + + +
+
+
+
+ /perception/object_recognition/tracking/ +
+
+
+
+
+
+ + /perception/object_recognition/tracking/ + +
+
+ + + + +
+
+
+
+ + LiDAR pipeline (default) + +
+
+
+
+
+
+ + LiDAR pipeline (default) + +
+
+ + + + +
+
+
+
+ + + Camera-LiDAR pipeline + + +
+
+ + + (optional) + + +
+
+
+
+
+ + Camera-LiDAR pipeline... + +
+
+ + + + +
+
+
+
+ + Radar pipeline (optional) + +
+
+
+
+
+
+ + Radar pipeline (optional) + +
+
+ + + + +
+
+
+
+ /perception/traffic_light_recognition/ +
+
+
+
+
+
+ + /perception/traffic_light_... + +
+
+ + + + +
+
+
+ Perception +
+
+
+
+ + Perception + +
+
+ + + + + +
+
+
+ /perception/object_recognition/objects +
+
+
+
+ + /perception/object_recognition/objects + +
+
+ + + + + +
+
+
+ clustering/clusters +
+
+
+
+ + clustering/clusters + +
+
+ + + + + +
+
+
+ euclidean_cluster +
+
+
+
+ + euclidean_cluster + +
+
+
+ + + + + + + +
+
+
+ centerpoint/validation/objects +
+
+
+
+ + centerpoint/validation/objects + +
+
+ + + + + +
+
+
+ lidar_centerpoint +
+
+
+
+ + lidar_centerpoint + +
+
+
+ + + + + +
+
+
+ map_based_ +
+ prediction +
+
+
+
+ + map_based_... + +
+
+
+ + + + + +
+
+
+ traffic_light_detection/rough/rois +
+
+
+
+ + traffic_light_detection/rough/rois + +
+
+ + + + + +
+
+
+ traffic_light_map_ +
+ based_detector +
+
+
+
+ + traffic_light_map_... + +
+
+
+ + + + + +
+
+
+ objects +
+
+
+
+ + objects + +
+
+ + + + + +
+
+
+ traffic_light_ +
+ classifier +
+
+
+
+ + traffic_light_... + +
+
+
+ + + + + +
+
+
+ traffic_light_ +
+ ssd_fine_detector +
+
+
+
+ + traffic_light_... + +
+
+
+ + + + + +
+
+
+ route, +
+ vector_map +
+
+
+
+ + route,... + +
+
+ + + + + + + +
+
+
+ object_association +
+ _merger +
+
+
+
+ + object_association... + +
+
+
+ + + + + +
+
+
+ shape_estimation +
+
+
+
+ + shape_estimation + +
+
+
+ + + + +
+
+
+
+ /perception/occupancy_grid_map/ +
+
+
+
+
+
+ + /perception/occupancy_grid_map/ + +
+
+ + + + +
+
+
+
+ /perception/obstacle_segmentation/ +
+
+
+
+
+
+ + /perception/obstacle_segmentation/ + +
+
+ + + + + + + + + +
+
+
+ no_ground/oneshot/pointcloud +
+
+
+
+ + no_ground/oneshot/pointcloud + +
+
+ + + + + +
+
+
+ range_cropped/pointcloud +
+
+
+
+ + range_cropped/pointcloud + +
+
+ + + + + +
+
+
+ common_ +
+ ground_filter +
+
+
+
+ + common_... + +
+
+
+ + + + + +
+
+
+ occupancy_grid +
+
+
+
+ + occupancy_grid + +
+
+ + + + + +
+
+
+ /perception/occupancy_grid_map/map +
+
+
+
+ + /perception/occupancy_grid_map/map + +
+
+ + + + + +
+
+
+ probabilistic_ +
+ occupancy_grid_map +
+
+
+
+ + probabilistic_... + +
+
+
+ + + + + +
+
+
+ occupancy_grid_ +
+ map_based_outlier_filter +
+
+
+
+ + occupancy_grid_... + +
+
+
+ + + + + +
+
+
+ /perception/obstacle_segmentation/pointcloud +
+
+
+
+ + /perception/obstacle_segmentation/pointcloud + +
+
+ + + + + +
+
+
+ crop_box_filter +
+
+
+
+ + crop_box_filter + +
+
+
+ + + + + +
+
+
+ /concatenated/pointcloud +
+
+
+
+ + /concatena... + +
+
+ + + + + +
+
+
+ obstacle_pointcloud _based_validator +
+
+
+
+ + obstacle_pointcloud _ba... + +
+
+
+ + + + + + + +
+
+
+ object_association +
+ _merger +
+
+
+
+ + object_association... + +
+
+
+ + + + + +
+
+
+ tensorrt_yolox +
+
+
+
+ + tensorrt_yolox + +
+
+
+ + + + + +
+
+
+ /perception/obstacle_segmentation/pointcloud +
+
+
+
+ + /perception/obstacle_segmentation/pointcloud + +
+
+ + + + + +
+
+
+ roi_cluster_fusion +
+
+
+
+ + roi_cluster_fusion + +
+
+
+ + + + + + + +
+
+
+ /rois* +
+
+
+
+ + /rois* + +
+
+ + + + + +
+
+
+ clustering/camera_lidar_fusion +
+ /objects +
+
+
+
+ + clustering/camera_lidar_fusion... + +
+
+ + + + + +
+
+
+ shape_estimation +
+
+
+
+ + shape_estimation + +
+
+
+ + + + + + + +
+
+
+ detection_by +
+ + _tracker/objects + +
+
+
+
+ + detection_by... + +
+
+ + + + + +
+
+
+ detection_by_ +
+ tracker_node +
+
+
+
+ + detection_by_... + +
+
+
+ + + + + + + + + +
+
+
+ object_lanelet_filter +
+
+
+
+ + object_lanelet_filter + +
+
+
+ + + + + + + +
+
+
+ /map/vector_map +
+
+
+
+ + /map/vector_map + +
+
+ + + + + +
+
+
+ + pointcloud_map_filtered/pointcloud + +
+
+
+
+ + pointcloud_map_filtered/pointcloud + +
+
+ + + + + +
+
+
+ compare_map_filter +
+
+
+
+ + compare_map_filter + +
+
+
+ + + + + +
+
+
+ + /perception/obstacle_segmentation/pointcloud + +
+
+
+
+ + /perception/obstacle_segmentation/pointcloud + +
+
+ + + + + +
+
+
+ + map + +
+
+
+
+ + map + +
+
+ + + + + +
+
+
+ lanelet_filtered_objects +
+
+
+
+ + lanelet_filtered_objects + +
+
+ + + + + +
+
+
+ object_lanelet_filter +
+
+
+
+ + object_lanelet_filter + +
+
+
+ + + + + +
+
+
+ far_objects +
+
+
+
+ + far_objects + +
+
+ + + + + +
+
+
+ radar_object_clustering +
+
+
+
+ + radar_object_clustering + +
+
+
+ + + + + +
+
+
+ far_high_speed_objects +
+
+
+
+ + far_high_speed_objects + +
+
+ + + + + +
+
+
+ object_range_splitter +
+
+
+
+ + object_range_splitter + +
+
+
+ + + + + +
+
+
+ high_speed_objects +
+
+
+
+ + high_speed_objects + +
+
+ + + + + +
+
+
+ object_velocity_splitter +
+
+
+
+ + object_velocity_splitter + +
+
+
+ + + + + +
+
+
+ noise_filtered_objects +
+
+
+
+ + noise_filtered_objects + +
+
+ + + + + +
+
+
+ radar_crossing_objects_ +
+ noise_filter +
+
+
+
+ + radar_crossing_objects_... + +
+
+
+ + + + + +
+
+
+ /sensing/radar/detected_objects +
+
+
+
+ + /sensing/radar/detected_objects + +
+
+ + + + + +
+
+
+ far_objects +
+
+
+
+ + far_objects + +
+
+ + + + + +
+
+
+ multi_object_ +
+ tracker +
+
+
+
+ + multi_object_... + +
+
+
+ + + + + +
+
+
+ radar_object_tracker +
+
+
+
+ + radar_object_tracker + +
+
+
+ + + + + + + +
+
+
+ decorative_tracking_ +
+ merger +
+
+
+
+ + decorative_tracking_... + +
+
+
+ + + + + +
+
+
+ /sensing/lidar/top/ +
+ pointcloud_raw +
+
+
+
+ + /sensing/lidar/top/... + +
+
+ + + + + + +
+
+
+ behavior_velocity_planner +
+
+
+
+ + behavior_velocity_planner + +
+
+
+ + + + +
+
+
+ Planning +
+
+
+
+ + Planning + +
+
+ + + + + +
+
+
+ + /planning/scenario_planning/trajectory [Trajectory] + +
+
+
+
+ + /planning/scenario_planning/trajectory [Trajectory] + +
+
+ + + + + + + +
+
+
+ motion_planning/obstacle_avoidance_planner/trajectory [Trajectory] +
+
+
+
+ + motion_planning/obstacle_avoidance_planner/trajectory [Trajectory] + +
+
+ + + + + +
+
+
+ obstacle_ +
+ avoidance_planner +
+
+
+
+ + obstacle_... + +
+
+
+ + + + + +
+
+
+ motion_planning/obstacle_velocity_limiter/trajectory [Trajectory] +
+
+
+
+ + motion_planning/obstacle_velocity_limiter/trajectory [Trajectory] + +
+
+ + + + + +
+
+
+ obstacle_velocity_limiter +
+
+
+
+ + obstacle_velocity_limit... + +
+
+
+ + + + + +
+
+
+ obstacle_stop_ +
+ planner +
+
+
+
+ + obstacle_stop_... + +
+
+
+ + + + + +
+
+
+ costmap_generator +
+
+
+
+ + costmap_generator + +
+
+
+ + + + + +
+
+
+ external_velocity_ +
+ limit_selector +
+
+
+
+ + external_velocity_... + +
+
+
+ + + + + +
+
+
+ /planning/scenario_planning/max_velocity +
+ [tier4_planning_msgs/msg/VelocityLimit] +
+
+
+
+ + /planning/scenario_planning/max_velocity... + +
+
+ + + + + +
+
+
+ /planning/scenario_planning/max_velocity_candidates +
+ [tier4_planning_msgs/msg/VelocityLimit] +
+
+
+
+ + /planning/scenario_planning/max_velocity_candidates... + +
+
+ + + + + +
+
+
+ lane_driving/trajectory [Trajectory] +
+
+
+
+ + lane_driving/trajectory [Trajectory] + +
+
+ + + + + +
+
+
+ trajectory [Trajectory] +
+
+
+
+ + trajectory [Trajectory] + +
+
+ + + + + +
+
+
+ scenario_selector +
+
+
+
+ + scenario_selector + +
+
+
+ + + + + +
+
+
+ + /planning/scenario_planning/motion_velocity_smoother/trajectory [Trajectory] + +
+
+
+
+ + /planning/scenario_planning/motion_velocity_smoother/trajectory [Trajectory] + +
+
+ + + + + +
+
+
+ motion_velocity_ +
+ smoother +
+
+
+
+ + motion_velocity_... + +
+
+
+ + + + +
+
+
+ <Lane Driving> +
+
+
+
+ + <Lane Driving> + +
+
+ + + + + + + +
+
+
+ /planning/mission_planning/route +
+ [autoware_auto_planning_msgs/HADMapRoute] +
+
+
+
+ + /planning/mission_planning/route... + +
+
+ + + + + +
+
+
+ + /planning/scenario_planning/modified_goal + +
+
+
+
+ + /planning/scenario_planning/modified_goal + +
+
+ + + + + +
+
+
+ /planning/mission_planning/goal, +
+ + /planning/mission_planning/checkpoint + +
+
+
+
+ + /planning/mission_planning/goal,... + +
+
+ + + + + +
+
+
+ /planning/mission_planning/ +
+ route_state +
+
+
+
+ + /planning/mission_planning/... + +
+
+ + + + + +
+
+
+ mission_planner +
+
+
+
+ + mission_planner + +
+
+
+ + + + + +
+
+
+ behavior_planning/path_with_lane_id +
+
+
+
+ + behavior_planning/path_with_lane_id + +
+
+ + + + + +
+
+
+ freespace_planner +
+
+
+
+ + freespace_planner + +
+
+
+ + + + + +
+
+
+ costmap_generator/occupancy_grid +
+
+
+
+ + costmap_generator/occupancy_grid + +
+
+ + + + + + +
+
+
+ behavior_planning/path +
+
+
+
+ + behavior_planning/path + +
+
+ + + + +
+
+
+ <Parking> +
+
+
+
+ + <Parking> + +
+
+ + + + + +
+
+
+ + parking/trajectory [Trajectory] + +
+
+
+
+ + parking/trajectory [Trajectory] + +
+
+ + + + + +
+
+
+ surround_obstacle_checker +
+
+
+
+ + surround_obstacle_checker + +
+
+
+ + + + + + + +
+
+
+ behavior_path_planner +
+
+
+
+ + behavior_path_planner + +
+
+
+ + + + +
+
+
+ side_shift +
+
+
+
+ + side_shift + +
+
+ + + + +
+
+
+ pull_over/out +
+
+
+
+ + pull_over/out + +
+
+ + + + +
+
+
+ obstacle_avoidance +
+
+
+
+ + obstacle_avoidance + +
+
+ + + + +
+
+
+ lane_change +
+
+
+
+ + lane_change + +
+
+ + + + +
+
+
+ lane_following +
+
+
+
+ + lane_following + +
+
+ + + + + +
+
+
+ planning_validator +
+
+
+
+ + planning_validator + +
+
+
+ + + + + +
+
+
+ /planning/turn_indicators_cmd [TurnIndicatorsCommand] +
+ /planning/hazard_lights_cmd [HazardLightsCommand] +
+
+
+
+ + /planning/turn_indicators_cmd [TurnIndicatorsCommand]... + +
+
+ + + + + +
+
+
+ path_smoother/path +
+
+
+
+ + path_smoother/path + +
+
+ + + + + +
+
+
+ path_smoother +
+
+
+
+ + path_smoother + +
+
+
+ + + + +
+
+
+ /default_ad_api/helpers/ +
+ routing_adaptor +
+
+
+
+ + /default_ad_api/helpers/... + +
+
+ + + + + +
+
+
+ /planning/mission_planning/set_route, +
+ + /planning/mission_planning/set_route_points, +
+
+ /planning/mission_planning/clear_route + +
+
+
+
+
+
+ + /planning/... + +
+
+ + + + + +
+
+
+ /planning/mission_planning/change_route, +
+ + /planning/mission_planning/change_route_points + +
+
+
+
+ + /planning/mission_planning/change_route,... + +
+
+ + + + + + +
+
+
+ + /api/routing/set_route +
+
+
+
+
+
+ + /api/routi... + +
+
+ + + + + + +
+
+
+ /api/routing/change_route +
+
+
+
+ + /api/routing/change_route + +
+
+ + + + + +
+
+
+ /system/operation_mode/change_operation_mode +
+
+
+
+ + /system/operation_mode/change_operation_mode + +
+
+ + + + + +
+
+
+ /api/routing/clear_route +
+
+
+
+ + /api/routing/clear_route + +
+
+ + + + + +
+
+
+ + /api/routing/ +
+ set_route_points +
+
+
+
+
+ + /api/routi... + +
+
+ + + + + +
+
+
+ /api/routing/ +
+ change_route_points +
+
+
+
+ + /api/routing/... + +
+
+ + + + + +
+
+
+ /rviz/routing/ +
+ rough_goal +
+
+
+
+ + /rviz/routing/... + +
+
+ + + + + +
+
+
+ /rviz/routing/reroute +
+
+
+
+ + /rviz/routing/reroute + +
+
+ + + + +
+
+
+ /rviz +
+
+
+
+ + /rviz + +
+
+ + + + + +
+
+
+ /autoware/state +
+
+
+
+ + /autoware/state + +
+
+ + + + +
+
+
+ /default_ad_api/node/ +
+ autoware_state +
+
+
+
+ + /default_ad_api/node... + +
+
+ + + + +
+
+
+ <depricated> +
+
+
+
+ + <depricated> + +
+
+ + + + + +
+
+
+ /api/routing/state +
+
+
+
+ + /api/routing/state + +
+
+ + + + + +
+
+
+ no_stopping_area +
+
+
+
+ + no_stopping_area + +
+
+ + + + +
+
+
+ intersection +
+
+
+
+ + intersection + +
+
+ + + + +
+
+
+ traffic_light +
+
+
+
+ + traffic_light + +
+
+ + + + +
+
+
+ blind_spot +
+
+
+
+ + blind_spot + +
+
+ + + + +
+
+
+ no_drivable_lane +
+
+
+
+ + no_drivable_lane + +
+
+ + + + +
+
+
+ run_out +
+
+
+
+ + run_out + +
+
+ + + + +
+
+
+ merge_from_private +
+
+
+
+ + merge_from_private + +
+
+ + + + +
+
+
+ occlusion_spot +
+
+
+
+ + occlusion_spot + +
+
+ + + + +
+
+
+ cross_walk +
+
+
+
+ + cross_walk + +
+
+ + + + +
+
+
+ detection_area +
+
+
+
+ + detection_area + +
+
+ + + + +
+
+
+ stop_line +
+
+
+
+ + stop_line + +
+
+ + + + +
+
+
+ virtual_traffic_light +
+
+
+
+ + virtual_traffic_li... + +
+
+ + + + +
+
+
+ speed_bump +
+
+
+
+ + speed_bump + +
+
+ + + + +
+
+
+
+ walkway +
+
+
+
+
+ + walkway + +
+
+ + + + +
+
+
+
+ out_of_lane +
+
+
+
+
+ + out_of_lane + +
+
+ + + + + +
+
+
+ fusion/traffic_signals +
+
+
+
+ + fusion/traffic_signals + +
+
+ + + + + +
+
+
+ traffic_light_ +
+ multi_camera_fusion +
+
+
+
+ + traffic_light_... + +
+
+
+ + + + + +
+
+
+ classification/traffic_signals +
+
+
+
+ + classification/traffic_signals + +
+
+ + + + + +
+
+
+ traffic_light_ +
+ occlusion_predictor +
+
+
+
+ + traffic_light_... + +
+
+
+ + + + + +
+
+
+ classification/classified/traffic_signals +
+
+
+
+ + classification/classified/traffic_signals + +
+
+ + + + + +
+
+
+ internal/traffic_signals +
+
+
+
+ + internal/traffic_signals + +
+
+ + + + + +
+
+
+ crosswalk_traffic_ +
+ light_estimator +
+
+
+
+ + crosswalk_traffic_... + +
+
+
+ + + + + +
+
+
+ traffic_light_states +
+
+
+
+ + traffic_light_states + +
+
+ + + + + +
+
+
+ traffic_light_arbiter +
+
+
+
+ + traffic_light_arbiter + +
+
+
+ + + + +
+
+
+ trajectory_follower +
+
+
+
+ + trajectory_follower + +
+
+ + + + +
+
+
+ Control +
+
+
+
+ + Control + +
+
+ + + + + +
+
+
+ /control/trajectory_follower/control_cmd +
+ [AckermannControlCommand] +
+
+
+
+ + /control/trajectory_follower/control_cmd... + +
+
+ + + + + +
+
+
+ lateral_controller +
+
+
+
+ + lateral_controller + +
+
+
+ + + + + +
+
+
+ longitudinal_controller +
+
+
+
+ + longitudinal_controller + +
+
+
+ + + + + +
+
+
+ vehicle_cmd_gate +
+
+
+
+ + vehicle_cmd_gate + +
+
+
+ + + + + +
+
+
+ control/command/control_cmd +
+ [AckermannControlCommand] +
+
+
+
+ + control/command/control_cmd... + +
+
+ + + + + +
+
+
+ /control/shift_decider/gear_cmd +
+ [GearCommand] +
+
+
+
+ + /control/shift_decider/gear_cmd... + +
+
+ + + + + +
+
+
+ external_cmd_ +
+ converter +
+
+
+
+ + external_cmd_... + +
+
+
+ + + + + +
+
+
+ /external/selected/external_control_cmd +
+ [tier4_external_api_msgs/msg/ControlCommandStamped] +
+
+
+
+ + /external/selected/external_control_cmd... + +
+
+ + + + + +
+
+
+ external_cmd_ +
+ selector +
+
+
+
+ + external_cmd_... + +
+
+
+ + + + + +
+
+
+
+ + /api/external/set/command/remote/control +
+
+
+
+ + [tier4_external_api_msgs/msg/ControlCommandStamped] + +
+
+ + /api/external/set/command/remote/shift + +
+
+ + [tier4_external_api_msgs/msg/GearShiftStamped] + +
+
+ + /api/external/set/command/remote/turn_signal + +
+
+ + [tier4_external_api_msgs/msg/TurnSignalStamped] + +
+
+
+
+
+ + /api/external/set/command/remote/control... + +
+
+ + + + + + + +
+
+
+ /current_gate_mode [GateMode] +
+ /gear_cmd [GearCommand] +
+
+ /turn_indicators_cmd  [TurnIndicatorCommand] +
+
+
+ /hazard_lights_cmd  [HazardLightsCommand] +
+
+
+ /vehicle_emergency_cmd [VehicleEmergencyStamped] +
+
+
+
+
+ + /current_gate_mode [GateMode]... + +
+
+ + + + +
+
+
+ g30_interface +
+
+
+
+ + g30_interface + +
+
+ + + + + +
+
+
+ raw_vehicle_cmd_ +
+ converter +
+
+
+
+ + raw_vehicle_cmd_... + +
+
+
+ + + + + +
+
+
+ /vehicle/command/actuation_cmd +
+
+
+
+ + /vehicle/command/actuation_cmd + +
+
+ + + + + +
+
+
+ pacmod_interface +
+
+
+
+ + pacmod_interface + +
+
+
+ + + + +
+
+
+ VehicleInterface +
+
+
+
+ + VehicleInterface + +
+
+ + + + + +
+
+
+ /vehicle/status/velocity_status +
+ /vehicle/status/steering_status +
+ /vehicle/status/turn_indicators_status +
+ /vehicle/status/gear_status +
+ /vehicle/status/control_mode +
+ /vehicle/status/ + + actuation_status + +
+
+
+
+ + /vehicle/s... + +
+
+ + + + +
+
+
+ vehicle_interface +
+
+
+
+ + vehicle_interface + +
+
+ + + + + +
+
+
+ accel_map_calibrator +
+
+
+
+ + accel_map_calibrator + +
+
+
+ + + + + + +
+
+
+ /pacmod/** +
+
+
+
+ + /pacmod/** + +
+
+ + + + +
+
+
+ Vehicle +
+
+
+
+ + Vehicle + +
+
+ + + + + +
+
+
+ <CAN> +
+
+
+
+ + <CAN> + +
+
+ + + + +
+
+
+ JapanTaxi +
+
+
+
+ + JapanTaxi + +
+
+ + + + + +
+
+
+ pacmod3 +
+
+
+
+ + pacmod3 + +
+
+
+ + + + +
+
+
+ YMC GolfCart +
+
+
+
+ + YMC GolfCart + +
+
+ + + + + +
+
+
+ external/traffic_signals +
+
+
+
+ + external/traffic_signals + +
+
+ + + + +
+
+
+
+ + Radar sensing pipeline + +
+
+
+
+
+ + Radar sensing pipeline + +
+
+ + + + +
+
+
+
+ + Camera sensing pipeline + +
+
+
+
+
+ + Camera sensing pipeline + +
+
+ + + + + +
+
+
+ top/velodyne_packets +
+
+
+
+ + top/velodyne_packets + +
+
+ + + + +
+
+
+ lidar_driver +
+
+
+
+ + lidar_driver + +
+
+ + + + + +
+
+
+ top/rectified/pointcloud +
+
+
+
+ + top/rectified/pointcloud + +
+
+ + + + + +
+
+
+ fix_distortion +
+
+
+
+ + fix_distortion + +
+
+
+ + + + + +
+
+
+ top/pointcloud_raw +
+
+
+
+ + top/pointcloud_raw + +
+
+ + + + +
+
+
+ packets_to_ +
+ pointcloud +
+
+
+
+ + packets_to_... + +
+
+ + + + + +
+
+
+ top/self_cropped/pointcloud +
+
+
+
+ + top/self_cropped/pointcloud + +
+
+ + + + + +
+
+
+ crop_box_ +
+ filter_self +
+
+
+
+ + crop_box_... + +
+
+
+ + + + + +
+
+
+ top/mirror_cropped/pointcloud +
+
+
+
+ + top/mirror_cropped/pointcloud + +
+
+ + + + + +
+
+
+ crop_box_ +
+ filter_mirror +
+
+
+
+ + crop_box_... + +
+
+
+ + + + + +
+
+
+ ring_outlier_filter +
+
+
+
+ + ring_outlier_filter + +
+
+
+ + + + + +
+
+
+ lidar/*/velodyne_packets +
+
+
+
+ + lidar/*/velodyne_packets + +
+
+ + + + +
+
+
+ lidar_drivers +
+ (left,right,front_right, front_left,rear) +
+
+
+
+ + lidar_drivers... + +
+
+ + + + + +
+
+
+ + */rectified/pointcloud + +
+
+
+
+ + */rectified/pointcloud + +
+
+ + + + + +
+
+
+ fix_distortion +
+
+
+
+ + fix_distortion + +
+
+
+ + + + + +
+
+
+ + */pointcloud_raw + +
+
+
+
+ + */pointcloud_raw + +
+
+ + + + +
+
+
+ packets_to_ +
+ pointcloud +
+
+
+
+ + packets_to_... + +
+
+ + + + + +
+
+
+ + */self_cropped/pointcloud + +
+
+
+
+ + */self_cropped/pointcloud + +
+
+ + + + + +
+
+
+ crop_box_ +
+ filter_self +
+
+
+
+ + crop_box_... + +
+
+
+ + + + + +
+
+
+ + */mirror_cropped/pointcloud + +
+
+
+
+ + */mirror_cropped/pointcloud + +
+
+ + + + + +
+
+
+ crop_box_ +
+ filter_mirror +
+
+
+
+ + crop_box_... + +
+
+
+ + + + + +
+
+
+ ring_outlier_filter +
+
+
+
+ + ring_outlier_filter + +
+
+
+ + + + + +
+
+
+ concatenated/pointcloud +
+
+
+
+ + concatenated/pointcloud + +
+
+ + + + + +
+
+
+ concat_filter +
+
+
+
+ + concat_filter + +
+
+
+ + + + + + + + + +
+
+
+ gnss_poser +
+
+
+
+ + gnss_poser + +
+
+
+ + + + + + +
+
+
+ gnss_driver +
+
+
+
+ + gnss_driver + +
+
+ + + + +
+
+
+ imu_driver +
+
+
+
+ + imu_driver + +
+
+ + + + + +
+
+
+ /sensing/imu/imu_raw +
+
+
+
+ + /sensing/imu/imu_raw + +
+
+ + + + + +
+
+
+ /sensing/lidar/top/ +
+ outlier_filtered/pointcloud +
+
+
+
+ + /sensing/lidar/top/... + +
+
+ + + + + +
+
+
+ + /sensing/lidar/ +
+ concatenated/pointcloud +
+
+
+
+
+ + /sensing/lidar/... + +
+
+ + + + + +
+
+
+ /sensing/gnss/ +
+ pose_with_covariance +
+
+
+
+ + /sensing/gnss/... + +
+
+ + + + + +
+
+
+ imu_corrector +
+
+
+
+ + imu_corrector + +
+
+
+ + + + + +
+
+
+ /sensing/imu/imu_data +
+
+
+
+ + /sensing/imu/imu_data + +
+
+ + + + +
+
+
+ Sensing +
+
+
+
+ + Sensing + +
+
+ + + + + +
+
+
+ /sensing/radar/detected_objects +
+
+
+
+ + /sensing/radar/detected_objects + +
+
+ + + + +
+
+
+ radar_relay +
+
+
+
+ + radar_relay + +
+
+ + + + + +
+
+
+ */detected_objects +
+
+
+
+ + */detected_objects + +
+
+ + + + + +
+
+
+ radar_tracks_ +
+ msg_converter +
+
+
+
+ + radar_tracks_... + +
+
+
+ + + + + +
+
+
+ */filtered_objects +
+
+
+
+ + */filtered_objects + +
+
+ + + + + +
+
+
+ radar_tracks_ +
+ noise_filter +
+
+
+
+ + radar_tracks_... + +
+
+
+ + + + + +
+
+
+ */objects_raw +
+
+
+
+ + */objects_raw + +
+
+ + + + +
+
+
+ radar_driver +
+
+
+
+ + radar_driver + +
+
+ + + + + +
+
+
+ Text +
+
+
+
+ + Text + +
+
+ + + +
+
+
+ /sensing/camera/ +
+ camera*/image_rect_color +
+
+
+
+ + /sensing/camera/... + +
+
+ + + + +
+
+
+ camera_driver +
+
+
+
+ + camera_driver + +
+
+ + + + + +
+
+
+ /sensing/camera/ +
+ camera*/image_raw +
+
+
+
+ + /sensing/camera/... + +
+
+ + + + +
+
+
+ camera_driver +
+
+
+
+ + camera_driver + +
+
+ + + +
+
+
+ /sensing/camera/ +
+ camera*/image_raw +
+
+
+
+ + /sensing/camera/... + +
+
+ + + + + +
+
+
+ /sensing/camera/ +
+ camera*/image_raw +
+
+
+
+ + /sensing/camera/... + +
+
+ + + + + + +
+
+
+
+ + LiDAR sensing pipeline + +
+
+
+
+
+ + LiDAR sensing pipeline + +
+
+ + + + +
+
+
+
+ + GNSS sensing pipeline + +
+
+
+
+
+ + GNSS sensing pipeline + +
+
+ + + + +
+
+
+
+ + IMU sensing pipeline + +
+
+
+
+
+ + IMU sensing pipeline + +
+
+ + + + +
+
+
+ Localization +
+
+
+
+ + Localization + +
+
+ + + + + +
+
+
+ pose_initializer +
+
+
+
+ + pose_initializer + +
+
+
+ + + + + +
+
+
+ ndt_scan_matcher +
+
+
+
+ + ndt_scan_matcher + +
+
+
+ + + + +
+
+
+ localization_error_monitor +
+
+
+
+ + localization_error_monitor + +
+
+ + + + +
+
+
+ stop_filter +
+
+
+
+ + stop_filter + +
+
+ + + + + +
+
+
+ twist_estimator/twist_with_covariance +
+
+
+
+ + twist_estimator/twist_with_covariance + +
+
+ + + + + +
+
+
+ gyro_odometer +
+
+
+
+ + gyro_odometer + +
+
+
+ + + + + +
+
+
+ vehicle_velocity_converter/ +
+ twist_with_covariance +
+
+
+
+ + vehicle_velocity_converter/... + +
+
+ + + + +
+
+
+ vehicle_velocity_ +
+ converter +
+
+
+
+ + vehicle_velocity_... + +
+
+ + + + + +
+
+
+ ekf_localizer +
+
+
+
+ + ekf_localizer + +
+
+
+ + + + + +
+
+
+ measurement_range/pointcloud +
+
+
+
+ + measurement_range/pointcloud + +
+
+ + + + +
+
+
+ crop_box_filter_ +
+ measurement_range +
+
+
+
+ + crop_box_filter_... + +
+
+ + + + + +
+
+
+ voxel_grid_downsample/pointcloud +
+
+
+
+ + voxel_grid_downsample/pointcloud + +
+
+ + + + +
+
+
+ voxel_grid_ +
+ downsample_filter +
+
+
+
+ + voxel_grid_... + +
+
+ + + + +
+
+
+ random_ +
+ downsample_filter +
+
+
+
+ + random_... + +
+
+ + + + + +
+
+
+ downsample/pointcloud +
+
+
+
+ + downsample/pointcloud + +
+
+ + + + + +
+
+
+ /map/vector_map +
+
+
+
+ + /map/vector_map + +
+
+ + + + + +
+
+
+ near_objects +
+
+
+
+ + near_objects + +
+
+ + + + +
+
+
+ + /perception/object_recognition/ + +
+
+
+
+ + /perception/object_recognition/ + +
+
+ + + + + +
+
+
+ /sensing/camera/ +
+ camera*/image_rect_color +
+
+
+
+ + /sensing/camera/... + +
+
+ + + + + +
+
+
+ /vehicle/status/velocity_report +
+
+
+
+ + /vehicle/status/velocity_report + +
+
+ + + + + +
+
+
+ system_monitors +
+
+
+
+ + system_monitors + +
+
+
+ + + + +
+
+
+ System +
+
+
+
+ + System + +
+
+ + + + +
+
+
+ autoware_process_ +
+ monitor +
+
+
+
+ + autoware_process_... + +
+
+ + + + +
+
+
+ autoware_gpu_ +
+ monitor +
+
+
+
+ + autoware_gpu_... + +
+
+ + + + +
+
+
+ autoware_mem_ +
+ monitor +
+
+
+
+ + autoware_mem_... + +
+
+ + + + +
+
+
+ autoware_hdd_ +
+ monitor +
+
+
+
+ + autoware_hdd_... + +
+
+ + + + +
+
+
+ autoware_net_ +
+ monitor +
+
+
+
+ + autoware_net_... + +
+
+ + + + +
+
+
+ autoware_ntp_ +
+ monitor +
+
+
+
+ + autoware_ntp_... + +
+
+ + + + + +
+
+
+ /system/emergency/hazard_status +
+
+
+
+ + /system/emergency/hazard_status + +
+
+ + + + + +
+
+
+ system_error_ +
+ monitor +
+
+
+
+ + system_error_... + +
+
+
+ + + + + +
+
+
+
+ /system/emergency/control_cmd [AckermannControlCommand] +
+
+ /system/emergency/gear_cmd [GearCommand] +
+
+ /system/emergency/hazard_lights_cmd [HazardLightsCommand] +
+ /system/emergency/emergency_state [EmergencyStateStamped] +
+
+
+
+ + /system/emergency/control_cmd [AckermannControlCommand]... + +
+
+ + + + + +
+
+
+ emergency_handler +
+
+
+
+ + emergency_handler + +
+
+
+ + + + + +
+
+
+ /autoware/state +
+
+
+
+ + /autoware/state + +
+
+ + + + + +
+
+
+ /diagnostics +
+
+
+
+ + /diagnostics + +
+
+ + + + + +
+
+
+ ad_service_ +
+ state_monitor +
+
+
+
+ + ad_service_... + +
+
+
+ + + + + +
+
+
+
+ + /control/current_gate_mode + +
+
+ + /vehicle/status/control_mode + +
+
+ + /autoware/state + +
+
+
+
+
+ + /control/c... + +
+
+ + + + + +
+
+
+ /control/command/control_cmd +
+ /control/trajectory_follower/control_cmd +
+ /initialpose2d +
+ /localization/kinematic_state +
+ /map/pointcloud_map +
+ /map/vector_map +
+ /perception/object_recognition/objects +
+ /planning/mission_planning/route +
+ /planning/scenario_planning/trajectory +
+ /system/emergency/control_cmd +
+ /vehicle/status/control_mode +
+ /vehicle/status/steering_status +
+ /vehicle/status/velocity_status +
+
+
+
+ + /contr... + +
+
+ + + + + +
+
+
+ /autoware/engage +
+
+
+
+ + /autoware/engage + +
+
+ + + + + +
+
+
+ /planning/ +
+ mission_planning/goal +
+
+
+
+ + /planning/... + +
+
+ + + + +
+
+
+ Autoware +
+
+
+
+ + Autoware + +
+
+ + + + + + + +
+
+
+ shift_decider +
+
+
+
+ + shift_decider + +
+
+
+ + + + + + + +
+
+
+ /diagnostics +
+
+
+
+ + /diagnostics + +
+
+ + + + + +
+
+
+ lane_departure_ +
+ checker +
+
+
+
+ + lane_departure_... + +
+
+
+ + + + + +
+
+
+ + prediced_path + +
+
+
+
+ + prediced_path + +
+
+ + + + + +
+
+
+ + map_projection_ +
+ loader +
+
+
+
+
+
+ + map_projection_... + +
+
+
+ + + + + +
+
+
+ + lanelet2_map_loader +
+
+
+
+
+
+ + lanelet2_map_loader + +
+
+
+ + + + + +
+
+
+ + pointcloud_map_ +
+ loader +
+
+
+
+
+
+ + pointcloud_map_... + +
+
+
+
+ + + + + Text is not SVG - cannot display + + + +
\ No newline at end of file From 24842ab08af3900f9b0d85c4c23f0dbe7b2e1e92 Mon Sep 17 00:00:00 2001 From: yamato-ando Date: Tue, 5 Dec 2023 16:15:52 +0900 Subject: [PATCH 03/12] into tables Signed-off-by: yamato-ando --- .../autoware-interfaces/components/sensing.md | 135 +++--------------- 1 file changed, 23 insertions(+), 112 deletions(-) diff --git a/docs/design/autoware-interfaces/components/sensing.md b/docs/design/autoware-interfaces/components/sensing.md index 4746c86bb18..cc65d14c17e 100644 --- a/docs/design/autoware-interfaces/components/sensing.md +++ b/docs/design/autoware-interfaces/components/sensing.md @@ -84,118 +84,29 @@ classDef cls_sen fill:#FFE6CC,stroke:#999,stroke-width:1px; ## Inputs -### Ultrasonics - -Distance data from ultrasonic radar driver. - -- [sensor_msgs/Range](https://github.com/ros2/common_interfaces/blob/rolling/sensor_msgs/msg/Range.msg) - -### Camera Image - -Image data from camera driver. - -- [sensor_msgs/Image](https://github.com/ros2/common_interfaces/blob/rolling/sensor_msgs/msg/Image.msg) - -### Radar Tracks - -Tracks from radar driver. - -- [radar_msgs/RadarTracks](https://github.com/ros-perception/radar_msgs/blob/ros2/msg/RadarTracks.msg) - -### Radar Scan - -Scan from radar driver. - -- [radar_msgs/RadarScan](https://github.com/ros-perception/radar_msgs/blob/ros2/msg/RadarScan.msg) - -### Lidar Point Cloud - -Pointcloud from lidar driver. - -- [sensor_msgs/PointCloud2](https://github.com/ros2/common_interfaces/blob/rolling/sensor_msgs/msg/PointCloud2.msg) - -### GNSS-INS Position - -Initial pose from GNSS driver. - -- [geometry_msgs/NavSatFix](https://github.com/ros2/common_interfaces/blob/rolling/sensor_msgs/msg/NavSatFix.msg) - -### GNSS-INS Orientation - -Initial orientation from GNSS driver. - -- [autoware_sensing_msgs/GnssInsOrientationStamped](https://github.com/autowarefoundation/autoware_msgs/blob/main/autoware_sensing_msgs/msg/GnssInsOrientationStamped.msg) - -### GNSS Velocity - -Initial velocity from GNSS driver. - -- [geometry_msgs/TwistWithCovarianceStamped](https://github.com/ros2/common_interfaces/blob/rolling/geometry_msgs/msg/TwistWithCovarianceStamped.msg) - -### GNSS Acceleration - -Initial acceleration from GNSS driver. - -- [geometry_msgs/AccelWithCovarianceStamped](https://github.com/ros2/common_interfaces/blob/rolling/geometry_msgs/msg/AccelWithCovarianceStamped.msg) +| Name | Topic | Type | Description | +| ---------- | ----------------- | ---------------------------------------------------------------------------------------------------------------------------------------------------- | ------------------------------------------------------ | +| Ultrasonics | | [sensor_msgs/Range](https://github.com/ros2/common_interfaces/blob/rolling/sensor_msgs/msg/Range.msg) | Distance data from ultrasonic radar driver. | +| Camera Image | | [sensor_msgs/Image](https://github.com/ros2/common_interfaces/blob/rolling/sensor_msgs/msg/Image.msg) | Image data from camera driver. | +| Radar Tracks | | [radar_msgs/RadarTracks](https://github.com/ros-perception/radar_msgs/blob/ros2/msg/RadarTracks.msg) | Tracks from radar driver. | +| Radar Scan | | [radar_msgs/RadarScan](https://github.com/ros-perception/radar_msgs/blob/ros2/msg/RadarScan.msg) | Scan from radar driver. | +| Lidar Point Cloud | | [sensor_msgs/PointCloud2](https://github.com/ros2/common_interfaces/blob/rolling/sensor_msgs/msg/PointCloud2.msg) | Pointcloud from lidar driver. | +| GNSS-INS Position | | [geometry_msgs/NavSatFix](https://github.com/ros2/common_interfaces/blob/rolling/sensor_msgs/msg/NavSatFix.msg) | Initial pose from GNSS driver. | +| GNSS-INS Orientation | | [autoware_sensing_msgs/GnssInsOrientationStamped](https://github.com/autowarefoundation/autoware_msgs/blob/main/autoware_sensing_msgs/msg/GnssInsOrientationStamped.msg) | Initial orientation from GNSS driver. | +| GNSS Velocity | | [geometry_msgs/TwistWithCovarianceStamped](https://github.com/ros2/common_interfaces/blob/rolling/geometry_msgs/msg/TwistWithCovarianceStamped.msg) | Initial velocity from GNSS driver. | +| GNSS Acceleration | | [geometry_msgs/AccelWithCovarianceStamped](https://github.com/ros2/common_interfaces/blob/rolling/geometry_msgs/msg/AccelWithCovarianceStamped.msg) | Initial acceleration from GNSS driver. | ## Output -### Ultrasonics - -Distance data from ultrasonic radar. Used by the Perception. - -- [sensor_msgs/Range](https://github.com/ros2/common_interfaces/blob/rolling/sensor_msgs/msg/Range.msg) - -### Camera Image - -Image data from camera. Used by the Perception. - -- [sensor_msgs/Image](https://github.com/ros2/common_interfaces/blob/rolling/sensor_msgs/msg/Image.msg) - -### Combined Radar Tracks - -Radar tracks from radar. Used by the Perception. - -- [radar_msgs/RadarTracks.msg](https://github.com/ros-perception/radar_msgs/blob/ros2/msg/RadarTracks.msg) - -### Radar Point Cloud - -Pointcloud from radar. Used by the Perception. - -- [radar_msgs/RadarScan.msg](https://github.com/ros-perception/radar_msgs/blob/ros2/msg/RadarScan.msg) - -### Combined Lidar Point Cloud - -Lidar pointcloud after preprocessing. Used by the Perception and Localization. - -- [sensor_msgs/PointCloud2](https://github.com/ros2/common_interfaces/blob/rolling/sensor_msgs/msg/PointCloud2.msg) - -### Lidar Point Cloud - -Lidar pointcloud after preprocessing. Used by the Localization. - -- [sensor_msgs/PointCloud2](https://github.com/ros2/common_interfaces/blob/rolling/sensor_msgs/msg/PointCloud2.msg) - -### GNSS-INS pose - -Initial pose of the ego vehicle from GNSS. Used by the Localization. - -- [geometry_msgs/PoseWithCovarianceStamped](https://github.com/ros2/common_interfaces/blob/rolling/geometry_msgs/msg/PoseWithCovarianceStamped.msg) - -### GNSS-INS Orientation - -Orientation info from GNSS. Used by the Localization. - -- [sensor_msgs/Imu](https://github.com/ros2/common_interfaces/blob/rolling/sensor_msgs/msg/Imu.msg) - -### GNSS velocity - -Velocity of the ego vehicle from GNSS. Used by the Localization. - -- [geometry_msgs/TwistWithCovarianceStamped](https://github.com/ros2/common_interfaces/blob/rolling/geometry_msgs/msg/TwistWithCovarianceStamped.msg) - -### GNSS Acceleration - -Acceleration of the ego vehicle from GNSS. Used by the Localization. - -- [geometry_msgs/AccelWithCovarianceStamped](https://github.com/ros2/common_interfaces/blob/rolling/geometry_msgs/msg/AccelWithCovarianceStamped.msg) +| Name | Topic | Type | Description | +| ---------- | ----------------- | ---------------------------------------------------------------------------------------------------------------------------------------------------- | ------------------------------------------------------ | +| Ultrasonics | | [sensor_msgs/Range](https://github.com/ros2/common_interfaces/blob/rolling/sensor_msgs/msg/Range.msg) | Distance data from ultrasonic radar. Used by the Perception. | +| Camera Image | | [sensor_msgs/Image](https://github.com/ros2/common_interfaces/blob/rolling/sensor_msgs/msg/Image.msg) | Image data from camera. Used by the Perception. | +| Combined Radar Tracks | | [radar_msgs/RadarTracks.msg](https://github.com/ros-perception/radar_msgs/blob/ros2/msg/RadarTracks.msg) | Radar tracks from radar. Used by the Perception. | +| Radar Point Cloud | | [radar_msgs/RadarScan.msg](https://github.com/ros-perception/radar_msgs/blob/ros2/msg/RadarScan.msg) | Pointcloud from radar. Used by the Perception. | +| Combined Lidar Point Cloud | | [sensor_msgs/PointCloud2](https://github.com/ros2/common_interfaces/blob/rolling/sensor_msgs/msg/PointCloud2.msg) | Lidar pointcloud after preprocessing. Used by the Perception and Localization. | +| Lidar Point Cloud | | [sensor_msgs/PointCloud2](https://github.com/ros2/common_interfaces/blob/rolling/sensor_msgs/msg/PointCloud2.msg) | Lidar pointcloud after preprocessing. Used by the Localization. | +| GNSS-INS pose | | [geometry_msgs/PoseWithCovarianceStamped](https://github.com/ros2/common_interfaces/blob/rolling/geometry_msgs/msg/PoseWithCovarianceStamped.msg) | Initial pose of the ego vehicle from GNSS. Used by the Localization. | +| GNSS-INS Orientation | | [sensor_msgs/Imu](https://github.com/ros2/common_interfaces/blob/rolling/sensor_msgs/msg/Imu.msg) | Orientation info from GNSS. Used by the Localization. | +| GNSS Velocity | | [geometry_msgs/TwistWithCovarianceStamped](https://github.com/ros2/common_interfaces/blob/rolling/geometry_msgs/msg/TwistWithCovarianceStamped.msg) | Velocity of the ego vehicle from GNSS. Used by the Localization. | +| GNSS Acceleration | | [geometry_msgs/AccelWithCovarianceStamped](https://github.com/ros2/common_interfaces/blob/rolling/geometry_msgs/msg/AccelWithCovarianceStamped.msg) | Acceleration of the ego vehicle from GNSS. Used by the Localization. | From 9c51e1c52622d5dffe7397e34447d0d0c4166edb Mon Sep 17 00:00:00 2001 From: "pre-commit-ci[bot]" <66853113+pre-commit-ci[bot]@users.noreply.github.com> Date: Tue, 5 Dec 2023 07:16:59 +0000 Subject: [PATCH 04/12] style(pre-commit): autofix --- .../autoware-interfaces/components/sensing.md | 46 +++++++++---------- 1 file changed, 23 insertions(+), 23 deletions(-) diff --git a/docs/design/autoware-interfaces/components/sensing.md b/docs/design/autoware-interfaces/components/sensing.md index cc65d14c17e..1b95b517301 100644 --- a/docs/design/autoware-interfaces/components/sensing.md +++ b/docs/design/autoware-interfaces/components/sensing.md @@ -84,29 +84,29 @@ classDef cls_sen fill:#FFE6CC,stroke:#999,stroke-width:1px; ## Inputs -| Name | Topic | Type | Description | -| ---------- | ----------------- | ---------------------------------------------------------------------------------------------------------------------------------------------------- | ------------------------------------------------------ | -| Ultrasonics | | [sensor_msgs/Range](https://github.com/ros2/common_interfaces/blob/rolling/sensor_msgs/msg/Range.msg) | Distance data from ultrasonic radar driver. | -| Camera Image | | [sensor_msgs/Image](https://github.com/ros2/common_interfaces/blob/rolling/sensor_msgs/msg/Image.msg) | Image data from camera driver. | -| Radar Tracks | | [radar_msgs/RadarTracks](https://github.com/ros-perception/radar_msgs/blob/ros2/msg/RadarTracks.msg) | Tracks from radar driver. | -| Radar Scan | | [radar_msgs/RadarScan](https://github.com/ros-perception/radar_msgs/blob/ros2/msg/RadarScan.msg) | Scan from radar driver. | -| Lidar Point Cloud | | [sensor_msgs/PointCloud2](https://github.com/ros2/common_interfaces/blob/rolling/sensor_msgs/msg/PointCloud2.msg) | Pointcloud from lidar driver. | -| GNSS-INS Position | | [geometry_msgs/NavSatFix](https://github.com/ros2/common_interfaces/blob/rolling/sensor_msgs/msg/NavSatFix.msg) | Initial pose from GNSS driver. | -| GNSS-INS Orientation | | [autoware_sensing_msgs/GnssInsOrientationStamped](https://github.com/autowarefoundation/autoware_msgs/blob/main/autoware_sensing_msgs/msg/GnssInsOrientationStamped.msg) | Initial orientation from GNSS driver. | -| GNSS Velocity | | [geometry_msgs/TwistWithCovarianceStamped](https://github.com/ros2/common_interfaces/blob/rolling/geometry_msgs/msg/TwistWithCovarianceStamped.msg) | Initial velocity from GNSS driver. | -| GNSS Acceleration | | [geometry_msgs/AccelWithCovarianceStamped](https://github.com/ros2/common_interfaces/blob/rolling/geometry_msgs/msg/AccelWithCovarianceStamped.msg) | Initial acceleration from GNSS driver. | +| Name | Topic | Type | Description | +| -------------------- | ----- | ------------------------------------------------------------------------------------------------------------------------------------------------------------------------ | ------------------------------------------- | +| Ultrasonics | | [sensor_msgs/Range](https://github.com/ros2/common_interfaces/blob/rolling/sensor_msgs/msg/Range.msg) | Distance data from ultrasonic radar driver. | +| Camera Image | | [sensor_msgs/Image](https://github.com/ros2/common_interfaces/blob/rolling/sensor_msgs/msg/Image.msg) | Image data from camera driver. | +| Radar Tracks | | [radar_msgs/RadarTracks](https://github.com/ros-perception/radar_msgs/blob/ros2/msg/RadarTracks.msg) | Tracks from radar driver. | +| Radar Scan | | [radar_msgs/RadarScan](https://github.com/ros-perception/radar_msgs/blob/ros2/msg/RadarScan.msg) | Scan from radar driver. | +| Lidar Point Cloud | | [sensor_msgs/PointCloud2](https://github.com/ros2/common_interfaces/blob/rolling/sensor_msgs/msg/PointCloud2.msg) | Pointcloud from lidar driver. | +| GNSS-INS Position | | [geometry_msgs/NavSatFix](https://github.com/ros2/common_interfaces/blob/rolling/sensor_msgs/msg/NavSatFix.msg) | Initial pose from GNSS driver. | +| GNSS-INS Orientation | | [autoware_sensing_msgs/GnssInsOrientationStamped](https://github.com/autowarefoundation/autoware_msgs/blob/main/autoware_sensing_msgs/msg/GnssInsOrientationStamped.msg) | Initial orientation from GNSS driver. | +| GNSS Velocity | | [geometry_msgs/TwistWithCovarianceStamped](https://github.com/ros2/common_interfaces/blob/rolling/geometry_msgs/msg/TwistWithCovarianceStamped.msg) | Initial velocity from GNSS driver. | +| GNSS Acceleration | | [geometry_msgs/AccelWithCovarianceStamped](https://github.com/ros2/common_interfaces/blob/rolling/geometry_msgs/msg/AccelWithCovarianceStamped.msg) | Initial acceleration from GNSS driver. | ## Output -| Name | Topic | Type | Description | -| ---------- | ----------------- | ---------------------------------------------------------------------------------------------------------------------------------------------------- | ------------------------------------------------------ | -| Ultrasonics | | [sensor_msgs/Range](https://github.com/ros2/common_interfaces/blob/rolling/sensor_msgs/msg/Range.msg) | Distance data from ultrasonic radar. Used by the Perception. | -| Camera Image | | [sensor_msgs/Image](https://github.com/ros2/common_interfaces/blob/rolling/sensor_msgs/msg/Image.msg) | Image data from camera. Used by the Perception. | -| Combined Radar Tracks | | [radar_msgs/RadarTracks.msg](https://github.com/ros-perception/radar_msgs/blob/ros2/msg/RadarTracks.msg) | Radar tracks from radar. Used by the Perception. | -| Radar Point Cloud | | [radar_msgs/RadarScan.msg](https://github.com/ros-perception/radar_msgs/blob/ros2/msg/RadarScan.msg) | Pointcloud from radar. Used by the Perception. | -| Combined Lidar Point Cloud | | [sensor_msgs/PointCloud2](https://github.com/ros2/common_interfaces/blob/rolling/sensor_msgs/msg/PointCloud2.msg) | Lidar pointcloud after preprocessing. Used by the Perception and Localization. | -| Lidar Point Cloud | | [sensor_msgs/PointCloud2](https://github.com/ros2/common_interfaces/blob/rolling/sensor_msgs/msg/PointCloud2.msg) | Lidar pointcloud after preprocessing. Used by the Localization. | -| GNSS-INS pose | | [geometry_msgs/PoseWithCovarianceStamped](https://github.com/ros2/common_interfaces/blob/rolling/geometry_msgs/msg/PoseWithCovarianceStamped.msg) | Initial pose of the ego vehicle from GNSS. Used by the Localization. | -| GNSS-INS Orientation | | [sensor_msgs/Imu](https://github.com/ros2/common_interfaces/blob/rolling/sensor_msgs/msg/Imu.msg) | Orientation info from GNSS. Used by the Localization. | -| GNSS Velocity | | [geometry_msgs/TwistWithCovarianceStamped](https://github.com/ros2/common_interfaces/blob/rolling/geometry_msgs/msg/TwistWithCovarianceStamped.msg) | Velocity of the ego vehicle from GNSS. Used by the Localization. | -| GNSS Acceleration | | [geometry_msgs/AccelWithCovarianceStamped](https://github.com/ros2/common_interfaces/blob/rolling/geometry_msgs/msg/AccelWithCovarianceStamped.msg) | Acceleration of the ego vehicle from GNSS. Used by the Localization. | +| Name | Topic | Type | Description | +| -------------------------- | ----- | --------------------------------------------------------------------------------------------------------------------------------------------------- | ------------------------------------------------------------------------------ | +| Ultrasonics | | [sensor_msgs/Range](https://github.com/ros2/common_interfaces/blob/rolling/sensor_msgs/msg/Range.msg) | Distance data from ultrasonic radar. Used by the Perception. | +| Camera Image | | [sensor_msgs/Image](https://github.com/ros2/common_interfaces/blob/rolling/sensor_msgs/msg/Image.msg) | Image data from camera. Used by the Perception. | +| Combined Radar Tracks | | [radar_msgs/RadarTracks.msg](https://github.com/ros-perception/radar_msgs/blob/ros2/msg/RadarTracks.msg) | Radar tracks from radar. Used by the Perception. | +| Radar Point Cloud | | [radar_msgs/RadarScan.msg](https://github.com/ros-perception/radar_msgs/blob/ros2/msg/RadarScan.msg) | Pointcloud from radar. Used by the Perception. | +| Combined Lidar Point Cloud | | [sensor_msgs/PointCloud2](https://github.com/ros2/common_interfaces/blob/rolling/sensor_msgs/msg/PointCloud2.msg) | Lidar pointcloud after preprocessing. Used by the Perception and Localization. | +| Lidar Point Cloud | | [sensor_msgs/PointCloud2](https://github.com/ros2/common_interfaces/blob/rolling/sensor_msgs/msg/PointCloud2.msg) | Lidar pointcloud after preprocessing. Used by the Localization. | +| GNSS-INS pose | | [geometry_msgs/PoseWithCovarianceStamped](https://github.com/ros2/common_interfaces/blob/rolling/geometry_msgs/msg/PoseWithCovarianceStamped.msg) | Initial pose of the ego vehicle from GNSS. Used by the Localization. | +| GNSS-INS Orientation | | [sensor_msgs/Imu](https://github.com/ros2/common_interfaces/blob/rolling/sensor_msgs/msg/Imu.msg) | Orientation info from GNSS. Used by the Localization. | +| GNSS Velocity | | [geometry_msgs/TwistWithCovarianceStamped](https://github.com/ros2/common_interfaces/blob/rolling/geometry_msgs/msg/TwistWithCovarianceStamped.msg) | Velocity of the ego vehicle from GNSS. Used by the Localization. | +| GNSS Acceleration | | [geometry_msgs/AccelWithCovarianceStamped](https://github.com/ros2/common_interfaces/blob/rolling/geometry_msgs/msg/AccelWithCovarianceStamped.msg) | Acceleration of the ego vehicle from GNSS. Used by the Localization. | From 6faf58d73ccb3ca7a47fd231dd8a411f9c7d6c9b Mon Sep 17 00:00:00 2001 From: yamato-ando Date: Tue, 5 Dec 2023 16:22:45 +0900 Subject: [PATCH 05/12] remove combined lidar pointcloud Signed-off-by: yamato-ando --- docs/design/autoware-interfaces/components/sensing.md | 9 ++------- 1 file changed, 2 insertions(+), 7 deletions(-) diff --git a/docs/design/autoware-interfaces/components/sensing.md b/docs/design/autoware-interfaces/components/sensing.md index 1b95b517301..0c55e6b6200 100644 --- a/docs/design/autoware-interfaces/components/sensing.md +++ b/docs/design/autoware-interfaces/components/sensing.md @@ -32,8 +32,6 @@ graph TD radar_msgs/RadarTracks"):::cls_sen msg_pc_rdr("Radar Pointcloud radar_msgs/RadarScan"):::cls_sen - msg_pc_combined_ldr("Combined Lidar Point Cloud - sensor_msgs/PointCloud2"):::cls_sen msg_pc_ldr("Lidar Point Cloud sensor_msgs/PointCloud2"):::cls_sen msg_pose_gnss("GNSS-INS Pose @@ -61,7 +59,6 @@ graph TD cmp_sen --> msg_gnssvel_sen cmp_sen --> msg_pc_combined_rdr cmp_sen --> msg_pc_rdr - cmp_sen --> msg_pc_combined_ldr cmp_sen --> msg_pc_ldr cmp_sen --> msg_pose_gnss cmp_sen --> msg_gnssacc_sen @@ -69,8 +66,7 @@ graph TD msg_img_sen --> cmp_per msg_pc_combined_rdr --> cmp_per msg_pc_rdr --> cmp_per - msg_pc_combined_ldr --> cmp_per - msg_pc_combined_ldr --> cmp_loc + msg_pc_ldr --> cmp_per msg_pc_ldr --> cmp_loc msg_pose_gnss --> cmp_loc msg_gnssori_sen --> cmp_loc @@ -104,8 +100,7 @@ classDef cls_sen fill:#FFE6CC,stroke:#999,stroke-width:1px; | Camera Image | | [sensor_msgs/Image](https://github.com/ros2/common_interfaces/blob/rolling/sensor_msgs/msg/Image.msg) | Image data from camera. Used by the Perception. | | Combined Radar Tracks | | [radar_msgs/RadarTracks.msg](https://github.com/ros-perception/radar_msgs/blob/ros2/msg/RadarTracks.msg) | Radar tracks from radar. Used by the Perception. | | Radar Point Cloud | | [radar_msgs/RadarScan.msg](https://github.com/ros-perception/radar_msgs/blob/ros2/msg/RadarScan.msg) | Pointcloud from radar. Used by the Perception. | -| Combined Lidar Point Cloud | | [sensor_msgs/PointCloud2](https://github.com/ros2/common_interfaces/blob/rolling/sensor_msgs/msg/PointCloud2.msg) | Lidar pointcloud after preprocessing. Used by the Perception and Localization. | -| Lidar Point Cloud | | [sensor_msgs/PointCloud2](https://github.com/ros2/common_interfaces/blob/rolling/sensor_msgs/msg/PointCloud2.msg) | Lidar pointcloud after preprocessing. Used by the Localization. | +| Lidar Point Cloud | | [sensor_msgs/PointCloud2](https://github.com/ros2/common_interfaces/blob/rolling/sensor_msgs/msg/PointCloud2.msg) | Lidar pointcloud after preprocessing. Used by the Perception and Localization. | | GNSS-INS pose | | [geometry_msgs/PoseWithCovarianceStamped](https://github.com/ros2/common_interfaces/blob/rolling/geometry_msgs/msg/PoseWithCovarianceStamped.msg) | Initial pose of the ego vehicle from GNSS. Used by the Localization. | | GNSS-INS Orientation | | [sensor_msgs/Imu](https://github.com/ros2/common_interfaces/blob/rolling/sensor_msgs/msg/Imu.msg) | Orientation info from GNSS. Used by the Localization. | | GNSS Velocity | | [geometry_msgs/TwistWithCovarianceStamped](https://github.com/ros2/common_interfaces/blob/rolling/geometry_msgs/msg/TwistWithCovarianceStamped.msg) | Velocity of the ego vehicle from GNSS. Used by the Localization. | From 74d7bb8c77070781c958ea58d5b12c2064d6549c Mon Sep 17 00:00:00 2001 From: "pre-commit-ci[bot]" <66853113+pre-commit-ci[bot]@users.noreply.github.com> Date: Tue, 5 Dec 2023 07:24:48 +0000 Subject: [PATCH 06/12] style(pre-commit): autofix --- .../autoware-interfaces/components/sensing.md | 22 +++++++++---------- 1 file changed, 11 insertions(+), 11 deletions(-) diff --git a/docs/design/autoware-interfaces/components/sensing.md b/docs/design/autoware-interfaces/components/sensing.md index 0c55e6b6200..3e0a242ece4 100644 --- a/docs/design/autoware-interfaces/components/sensing.md +++ b/docs/design/autoware-interfaces/components/sensing.md @@ -94,14 +94,14 @@ classDef cls_sen fill:#FFE6CC,stroke:#999,stroke-width:1px; ## Output -| Name | Topic | Type | Description | -| -------------------------- | ----- | --------------------------------------------------------------------------------------------------------------------------------------------------- | ------------------------------------------------------------------------------ | -| Ultrasonics | | [sensor_msgs/Range](https://github.com/ros2/common_interfaces/blob/rolling/sensor_msgs/msg/Range.msg) | Distance data from ultrasonic radar. Used by the Perception. | -| Camera Image | | [sensor_msgs/Image](https://github.com/ros2/common_interfaces/blob/rolling/sensor_msgs/msg/Image.msg) | Image data from camera. Used by the Perception. | -| Combined Radar Tracks | | [radar_msgs/RadarTracks.msg](https://github.com/ros-perception/radar_msgs/blob/ros2/msg/RadarTracks.msg) | Radar tracks from radar. Used by the Perception. | -| Radar Point Cloud | | [radar_msgs/RadarScan.msg](https://github.com/ros-perception/radar_msgs/blob/ros2/msg/RadarScan.msg) | Pointcloud from radar. Used by the Perception. | -| Lidar Point Cloud | | [sensor_msgs/PointCloud2](https://github.com/ros2/common_interfaces/blob/rolling/sensor_msgs/msg/PointCloud2.msg) | Lidar pointcloud after preprocessing. Used by the Perception and Localization. | -| GNSS-INS pose | | [geometry_msgs/PoseWithCovarianceStamped](https://github.com/ros2/common_interfaces/blob/rolling/geometry_msgs/msg/PoseWithCovarianceStamped.msg) | Initial pose of the ego vehicle from GNSS. Used by the Localization. | -| GNSS-INS Orientation | | [sensor_msgs/Imu](https://github.com/ros2/common_interfaces/blob/rolling/sensor_msgs/msg/Imu.msg) | Orientation info from GNSS. Used by the Localization. | -| GNSS Velocity | | [geometry_msgs/TwistWithCovarianceStamped](https://github.com/ros2/common_interfaces/blob/rolling/geometry_msgs/msg/TwistWithCovarianceStamped.msg) | Velocity of the ego vehicle from GNSS. Used by the Localization. | -| GNSS Acceleration | | [geometry_msgs/AccelWithCovarianceStamped](https://github.com/ros2/common_interfaces/blob/rolling/geometry_msgs/msg/AccelWithCovarianceStamped.msg) | Acceleration of the ego vehicle from GNSS. Used by the Localization. | +| Name | Topic | Type | Description | +| --------------------- | ----- | --------------------------------------------------------------------------------------------------------------------------------------------------- | ------------------------------------------------------------------------------ | +| Ultrasonics | | [sensor_msgs/Range](https://github.com/ros2/common_interfaces/blob/rolling/sensor_msgs/msg/Range.msg) | Distance data from ultrasonic radar. Used by the Perception. | +| Camera Image | | [sensor_msgs/Image](https://github.com/ros2/common_interfaces/blob/rolling/sensor_msgs/msg/Image.msg) | Image data from camera. Used by the Perception. | +| Combined Radar Tracks | | [radar_msgs/RadarTracks.msg](https://github.com/ros-perception/radar_msgs/blob/ros2/msg/RadarTracks.msg) | Radar tracks from radar. Used by the Perception. | +| Radar Point Cloud | | [radar_msgs/RadarScan.msg](https://github.com/ros-perception/radar_msgs/blob/ros2/msg/RadarScan.msg) | Pointcloud from radar. Used by the Perception. | +| Lidar Point Cloud | | [sensor_msgs/PointCloud2](https://github.com/ros2/common_interfaces/blob/rolling/sensor_msgs/msg/PointCloud2.msg) | Lidar pointcloud after preprocessing. Used by the Perception and Localization. | +| GNSS-INS pose | | [geometry_msgs/PoseWithCovarianceStamped](https://github.com/ros2/common_interfaces/blob/rolling/geometry_msgs/msg/PoseWithCovarianceStamped.msg) | Initial pose of the ego vehicle from GNSS. Used by the Localization. | +| GNSS-INS Orientation | | [sensor_msgs/Imu](https://github.com/ros2/common_interfaces/blob/rolling/sensor_msgs/msg/Imu.msg) | Orientation info from GNSS. Used by the Localization. | +| GNSS Velocity | | [geometry_msgs/TwistWithCovarianceStamped](https://github.com/ros2/common_interfaces/blob/rolling/geometry_msgs/msg/TwistWithCovarianceStamped.msg) | Velocity of the ego vehicle from GNSS. Used by the Localization. | +| GNSS Acceleration | | [geometry_msgs/AccelWithCovarianceStamped](https://github.com/ros2/common_interfaces/blob/rolling/geometry_msgs/msg/AccelWithCovarianceStamped.msg) | Acceleration of the ego vehicle from GNSS. Used by the Localization. | From e43a73375bf9b21c79c73eb448d06251ab97a590 Mon Sep 17 00:00:00 2001 From: yamato-ando Date: Tue, 5 Dec 2023 16:31:11 +0900 Subject: [PATCH 07/12] add lidar-point-cloud's topic name and description Signed-off-by: yamato-ando --- docs/design/autoware-interfaces/components/sensing.md | 4 ++-- 1 file changed, 2 insertions(+), 2 deletions(-) diff --git a/docs/design/autoware-interfaces/components/sensing.md b/docs/design/autoware-interfaces/components/sensing.md index 3e0a242ece4..63ba2076d7e 100644 --- a/docs/design/autoware-interfaces/components/sensing.md +++ b/docs/design/autoware-interfaces/components/sensing.md @@ -86,7 +86,7 @@ classDef cls_sen fill:#FFE6CC,stroke:#999,stroke-width:1px; | Camera Image | | [sensor_msgs/Image](https://github.com/ros2/common_interfaces/blob/rolling/sensor_msgs/msg/Image.msg) | Image data from camera driver. | | Radar Tracks | | [radar_msgs/RadarTracks](https://github.com/ros-perception/radar_msgs/blob/ros2/msg/RadarTracks.msg) | Tracks from radar driver. | | Radar Scan | | [radar_msgs/RadarScan](https://github.com/ros-perception/radar_msgs/blob/ros2/msg/RadarScan.msg) | Scan from radar driver. | -| Lidar Point Cloud | | [sensor_msgs/PointCloud2](https://github.com/ros2/common_interfaces/blob/rolling/sensor_msgs/msg/PointCloud2.msg) | Pointcloud from lidar driver. | +| Lidar Point Cloud | `/sensing/lidar//pointcloud_raw` | [sensor_msgs/PointCloud2](https://github.com/ros2/common_interfaces/blob/rolling/sensor_msgs/msg/PointCloud2.msg) | Pointcloud from lidar driver. | | GNSS-INS Position | | [geometry_msgs/NavSatFix](https://github.com/ros2/common_interfaces/blob/rolling/sensor_msgs/msg/NavSatFix.msg) | Initial pose from GNSS driver. | | GNSS-INS Orientation | | [autoware_sensing_msgs/GnssInsOrientationStamped](https://github.com/autowarefoundation/autoware_msgs/blob/main/autoware_sensing_msgs/msg/GnssInsOrientationStamped.msg) | Initial orientation from GNSS driver. | | GNSS Velocity | | [geometry_msgs/TwistWithCovarianceStamped](https://github.com/ros2/common_interfaces/blob/rolling/geometry_msgs/msg/TwistWithCovarianceStamped.msg) | Initial velocity from GNSS driver. | @@ -100,7 +100,7 @@ classDef cls_sen fill:#FFE6CC,stroke:#999,stroke-width:1px; | Camera Image | | [sensor_msgs/Image](https://github.com/ros2/common_interfaces/blob/rolling/sensor_msgs/msg/Image.msg) | Image data from camera. Used by the Perception. | | Combined Radar Tracks | | [radar_msgs/RadarTracks.msg](https://github.com/ros-perception/radar_msgs/blob/ros2/msg/RadarTracks.msg) | Radar tracks from radar. Used by the Perception. | | Radar Point Cloud | | [radar_msgs/RadarScan.msg](https://github.com/ros-perception/radar_msgs/blob/ros2/msg/RadarScan.msg) | Pointcloud from radar. Used by the Perception. | -| Lidar Point Cloud | | [sensor_msgs/PointCloud2](https://github.com/ros2/common_interfaces/blob/rolling/sensor_msgs/msg/PointCloud2.msg) | Lidar pointcloud after preprocessing. Used by the Perception and Localization. | +| Lidar Point Cloud | `/sensing/lidar//pointcloud` | [sensor_msgs/PointCloud2](https://github.com/ros2/common_interfaces/blob/rolling/sensor_msgs/msg/PointCloud2.msg) | Lidar pointcloud after preprocessing. Used by the Perception and Localization. `` is a unique name for identifying each LiDAR or the group name when multiple LiDARs are combined. Specifically, the concatenated point cloud of all LiDARs is assigned the `` name `concatenated`.| | GNSS-INS pose | | [geometry_msgs/PoseWithCovarianceStamped](https://github.com/ros2/common_interfaces/blob/rolling/geometry_msgs/msg/PoseWithCovarianceStamped.msg) | Initial pose of the ego vehicle from GNSS. Used by the Localization. | | GNSS-INS Orientation | | [sensor_msgs/Imu](https://github.com/ros2/common_interfaces/blob/rolling/sensor_msgs/msg/Imu.msg) | Orientation info from GNSS. Used by the Localization. | | GNSS Velocity | | [geometry_msgs/TwistWithCovarianceStamped](https://github.com/ros2/common_interfaces/blob/rolling/geometry_msgs/msg/TwistWithCovarianceStamped.msg) | Velocity of the ego vehicle from GNSS. Used by the Localization. | From ed4c8f9e3c5941478bec0189a2a681613819bb4e Mon Sep 17 00:00:00 2001 From: "pre-commit-ci[bot]" <66853113+pre-commit-ci[bot]@users.noreply.github.com> Date: Tue, 5 Dec 2023 07:31:46 +0000 Subject: [PATCH 08/12] style(pre-commit): autofix --- .../autoware-interfaces/components/sensing.md | 44 +++++++++---------- 1 file changed, 22 insertions(+), 22 deletions(-) diff --git a/docs/design/autoware-interfaces/components/sensing.md b/docs/design/autoware-interfaces/components/sensing.md index 63ba2076d7e..ff63638b434 100644 --- a/docs/design/autoware-interfaces/components/sensing.md +++ b/docs/design/autoware-interfaces/components/sensing.md @@ -80,28 +80,28 @@ classDef cls_sen fill:#FFE6CC,stroke:#999,stroke-width:1px; ## Inputs -| Name | Topic | Type | Description | -| -------------------- | ----- | ------------------------------------------------------------------------------------------------------------------------------------------------------------------------ | ------------------------------------------- | -| Ultrasonics | | [sensor_msgs/Range](https://github.com/ros2/common_interfaces/blob/rolling/sensor_msgs/msg/Range.msg) | Distance data from ultrasonic radar driver. | -| Camera Image | | [sensor_msgs/Image](https://github.com/ros2/common_interfaces/blob/rolling/sensor_msgs/msg/Image.msg) | Image data from camera driver. | -| Radar Tracks | | [radar_msgs/RadarTracks](https://github.com/ros-perception/radar_msgs/blob/ros2/msg/RadarTracks.msg) | Tracks from radar driver. | -| Radar Scan | | [radar_msgs/RadarScan](https://github.com/ros-perception/radar_msgs/blob/ros2/msg/RadarScan.msg) | Scan from radar driver. | -| Lidar Point Cloud | `/sensing/lidar//pointcloud_raw` | [sensor_msgs/PointCloud2](https://github.com/ros2/common_interfaces/blob/rolling/sensor_msgs/msg/PointCloud2.msg) | Pointcloud from lidar driver. | -| GNSS-INS Position | | [geometry_msgs/NavSatFix](https://github.com/ros2/common_interfaces/blob/rolling/sensor_msgs/msg/NavSatFix.msg) | Initial pose from GNSS driver. | -| GNSS-INS Orientation | | [autoware_sensing_msgs/GnssInsOrientationStamped](https://github.com/autowarefoundation/autoware_msgs/blob/main/autoware_sensing_msgs/msg/GnssInsOrientationStamped.msg) | Initial orientation from GNSS driver. | -| GNSS Velocity | | [geometry_msgs/TwistWithCovarianceStamped](https://github.com/ros2/common_interfaces/blob/rolling/geometry_msgs/msg/TwistWithCovarianceStamped.msg) | Initial velocity from GNSS driver. | -| GNSS Acceleration | | [geometry_msgs/AccelWithCovarianceStamped](https://github.com/ros2/common_interfaces/blob/rolling/geometry_msgs/msg/AccelWithCovarianceStamped.msg) | Initial acceleration from GNSS driver. | +| Name | Topic | Type | Description | +| -------------------- | -------------------------------------------- | ------------------------------------------------------------------------------------------------------------------------------------------------------------------------ | ------------------------------------------- | +| Ultrasonics | | [sensor_msgs/Range](https://github.com/ros2/common_interfaces/blob/rolling/sensor_msgs/msg/Range.msg) | Distance data from ultrasonic radar driver. | +| Camera Image | | [sensor_msgs/Image](https://github.com/ros2/common_interfaces/blob/rolling/sensor_msgs/msg/Image.msg) | Image data from camera driver. | +| Radar Tracks | | [radar_msgs/RadarTracks](https://github.com/ros-perception/radar_msgs/blob/ros2/msg/RadarTracks.msg) | Tracks from radar driver. | +| Radar Scan | | [radar_msgs/RadarScan](https://github.com/ros-perception/radar_msgs/blob/ros2/msg/RadarScan.msg) | Scan from radar driver. | +| Lidar Point Cloud | `/sensing/lidar//pointcloud_raw` | [sensor_msgs/PointCloud2](https://github.com/ros2/common_interfaces/blob/rolling/sensor_msgs/msg/PointCloud2.msg) | Pointcloud from lidar driver. | +| GNSS-INS Position | | [geometry_msgs/NavSatFix](https://github.com/ros2/common_interfaces/blob/rolling/sensor_msgs/msg/NavSatFix.msg) | Initial pose from GNSS driver. | +| GNSS-INS Orientation | | [autoware_sensing_msgs/GnssInsOrientationStamped](https://github.com/autowarefoundation/autoware_msgs/blob/main/autoware_sensing_msgs/msg/GnssInsOrientationStamped.msg) | Initial orientation from GNSS driver. | +| GNSS Velocity | | [geometry_msgs/TwistWithCovarianceStamped](https://github.com/ros2/common_interfaces/blob/rolling/geometry_msgs/msg/TwistWithCovarianceStamped.msg) | Initial velocity from GNSS driver. | +| GNSS Acceleration | | [geometry_msgs/AccelWithCovarianceStamped](https://github.com/ros2/common_interfaces/blob/rolling/geometry_msgs/msg/AccelWithCovarianceStamped.msg) | Initial acceleration from GNSS driver. | ## Output -| Name | Topic | Type | Description | -| --------------------- | ----- | --------------------------------------------------------------------------------------------------------------------------------------------------- | ------------------------------------------------------------------------------ | -| Ultrasonics | | [sensor_msgs/Range](https://github.com/ros2/common_interfaces/blob/rolling/sensor_msgs/msg/Range.msg) | Distance data from ultrasonic radar. Used by the Perception. | -| Camera Image | | [sensor_msgs/Image](https://github.com/ros2/common_interfaces/blob/rolling/sensor_msgs/msg/Image.msg) | Image data from camera. Used by the Perception. | -| Combined Radar Tracks | | [radar_msgs/RadarTracks.msg](https://github.com/ros-perception/radar_msgs/blob/ros2/msg/RadarTracks.msg) | Radar tracks from radar. Used by the Perception. | -| Radar Point Cloud | | [radar_msgs/RadarScan.msg](https://github.com/ros-perception/radar_msgs/blob/ros2/msg/RadarScan.msg) | Pointcloud from radar. Used by the Perception. | -| Lidar Point Cloud | `/sensing/lidar//pointcloud` | [sensor_msgs/PointCloud2](https://github.com/ros2/common_interfaces/blob/rolling/sensor_msgs/msg/PointCloud2.msg) | Lidar pointcloud after preprocessing. Used by the Perception and Localization. `` is a unique name for identifying each LiDAR or the group name when multiple LiDARs are combined. Specifically, the concatenated point cloud of all LiDARs is assigned the `` name `concatenated`.| -| GNSS-INS pose | | [geometry_msgs/PoseWithCovarianceStamped](https://github.com/ros2/common_interfaces/blob/rolling/geometry_msgs/msg/PoseWithCovarianceStamped.msg) | Initial pose of the ego vehicle from GNSS. Used by the Localization. | -| GNSS-INS Orientation | | [sensor_msgs/Imu](https://github.com/ros2/common_interfaces/blob/rolling/sensor_msgs/msg/Imu.msg) | Orientation info from GNSS. Used by the Localization. | -| GNSS Velocity | | [geometry_msgs/TwistWithCovarianceStamped](https://github.com/ros2/common_interfaces/blob/rolling/geometry_msgs/msg/TwistWithCovarianceStamped.msg) | Velocity of the ego vehicle from GNSS. Used by the Localization. | -| GNSS Acceleration | | [geometry_msgs/AccelWithCovarianceStamped](https://github.com/ros2/common_interfaces/blob/rolling/geometry_msgs/msg/AccelWithCovarianceStamped.msg) | Acceleration of the ego vehicle from GNSS. Used by the Localization. | +| Name | Topic | Type | Description | +| --------------------- | ----------------------------------------- | --------------------------------------------------------------------------------------------------------------------------------------------------- | ------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------- | +| Ultrasonics | | [sensor_msgs/Range](https://github.com/ros2/common_interfaces/blob/rolling/sensor_msgs/msg/Range.msg) | Distance data from ultrasonic radar. Used by the Perception. | +| Camera Image | | [sensor_msgs/Image](https://github.com/ros2/common_interfaces/blob/rolling/sensor_msgs/msg/Image.msg) | Image data from camera. Used by the Perception. | +| Combined Radar Tracks | | [radar_msgs/RadarTracks.msg](https://github.com/ros-perception/radar_msgs/blob/ros2/msg/RadarTracks.msg) | Radar tracks from radar. Used by the Perception. | +| Radar Point Cloud | | [radar_msgs/RadarScan.msg](https://github.com/ros-perception/radar_msgs/blob/ros2/msg/RadarScan.msg) | Pointcloud from radar. Used by the Perception. | +| Lidar Point Cloud | `/sensing/lidar//pointcloud` | [sensor_msgs/PointCloud2](https://github.com/ros2/common_interfaces/blob/rolling/sensor_msgs/msg/PointCloud2.msg) | Lidar pointcloud after preprocessing. Used by the Perception and Localization. `` is a unique name for identifying each LiDAR or the group name when multiple LiDARs are combined. Specifically, the concatenated point cloud of all LiDARs is assigned the `` name `concatenated`. | +| GNSS-INS pose | | [geometry_msgs/PoseWithCovarianceStamped](https://github.com/ros2/common_interfaces/blob/rolling/geometry_msgs/msg/PoseWithCovarianceStamped.msg) | Initial pose of the ego vehicle from GNSS. Used by the Localization. | +| GNSS-INS Orientation | | [sensor_msgs/Imu](https://github.com/ros2/common_interfaces/blob/rolling/sensor_msgs/msg/Imu.msg) | Orientation info from GNSS. Used by the Localization. | +| GNSS Velocity | | [geometry_msgs/TwistWithCovarianceStamped](https://github.com/ros2/common_interfaces/blob/rolling/geometry_msgs/msg/TwistWithCovarianceStamped.msg) | Velocity of the ego vehicle from GNSS. Used by the Localization. | +| GNSS Acceleration | | [geometry_msgs/AccelWithCovarianceStamped](https://github.com/ros2/common_interfaces/blob/rolling/geometry_msgs/msg/AccelWithCovarianceStamped.msg) | Acceleration of the ego vehicle from GNSS. Used by the Localization. | From 9d0bdacf4144aef94af7ffa930568dbe4ab8200d Mon Sep 17 00:00:00 2001 From: yamato-ando Date: Tue, 5 Dec 2023 16:34:44 +0900 Subject: [PATCH 09/12] rename lidar topic Signed-off-by: yamato-ando --- .../overall-node-diagram-autoware-universe.drawio.svg | 8 +++----- 1 file changed, 3 insertions(+), 5 deletions(-) diff --git a/docs/design/autoware-architecture/node-diagram/overall-node-diagram-autoware-universe.drawio.svg b/docs/design/autoware-architecture/node-diagram/overall-node-diagram-autoware-universe.drawio.svg index 87ba1e2a1e5..c6fa06e8ced 100644 --- a/docs/design/autoware-architecture/node-diagram/overall-node-diagram-autoware-universe.drawio.svg +++ b/docs/design/autoware-architecture/node-diagram/overall-node-diagram-autoware-universe.drawio.svg @@ -1,4 +1,4 @@ - + @@ -4781,15 +4781,13 @@
- /sensing/lidar/top/ -
- outlier_filtered/pointcloud + /sensing/lidar/top/pointcloud
- /sensing/lidar/top/... + /sensing/lidar/top/pointcloud From 6c5016041ed678fe2356d902adf3fa3c4e2e2cd6 Mon Sep 17 00:00:00 2001 From: yamato-ando Date: Tue, 5 Dec 2023 18:14:33 +0900 Subject: [PATCH 10/12] rename lidar topic Signed-off-by: yamato-ando --- .../calibrating-sensors/lidar-lidar-calibration/index.md | 6 +++--- .../creating-sensor-model/index.md | 2 +- 2 files changed, 4 insertions(+), 4 deletions(-) diff --git a/docs/how-to-guides/integrating-autoware/creating-vehicle-and-sensor-model/calibrating-sensors/lidar-lidar-calibration/index.md b/docs/how-to-guides/integrating-autoware/creating-vehicle-and-sensor-model/calibrating-sensors/lidar-lidar-calibration/index.md index 87eb4ee99b4..fb07772f6ca 100644 --- a/docs/how-to-guides/integrating-autoware/creating-vehicle-and-sensor-model/calibrating-sensors/lidar-lidar-calibration/index.md +++ b/docs/how-to-guides/integrating-autoware/creating-vehicle-and-sensor-model/calibrating-sensors/lidar-lidar-calibration/index.md @@ -37,7 +37,7 @@ The following shows an example of a bag file used for this calibration: End: Sep 5 2023 11:25:43.808 (1693902343.808) Messages: 2256 Topic information: Topic: /sensing/lidar/front/pointcloud_raw | Type: sensor_msgs/msg/PointCloud2 | Count: 1128 | Serialization Format: cdr - Topic: /sensing/lidar/top/outlier_filtered/pointcloud | Type: sensor_msgs/msg/PointCloud2 | Count: 1128 | Serialization Format: cdr + Topic: /sensing/lidar/top/pointcloud | Type: sensor_msgs/msg/PointCloud2 | Count: 1128 | Serialization Format: cdr ``` ## Mapping-based lidar-lidar calibration @@ -190,13 +190,13 @@ calibration_lidar_base_frames and calibration_lidar_frames for calibrator: After that, we will add the sensor topics and sensor frames in order to do that, we will continue filling the `mapping_based_sensor_kit.launch.xml` with (we recommend -using the /sensing/lidar/top/outlier_filtered/pointcloud topic as the mapping pointcloud +using the /sensing/lidar/top/pointcloud topic as the mapping pointcloud because the vehicle cloud is cropped at this topic by pointcloud preprocessing): ```diff - -- +- + + diff --git a/docs/how-to-guides/integrating-autoware/creating-vehicle-and-sensor-model/creating-sensor-model/index.md b/docs/how-to-guides/integrating-autoware/creating-vehicle-and-sensor-model/creating-sensor-model/index.md index 0bce61def59..56a70829a28 100644 --- a/docs/how-to-guides/integrating-autoware/creating-vehicle-and-sensor-model/creating-sensor-model/index.md +++ b/docs/how-to-guides/integrating-autoware/creating-vehicle-and-sensor-model/creating-sensor-model/index.md @@ -524,7 +524,7 @@ you can modify the pipeline components like this way: + name="dual_return_outlier_filter", remappings=[ ("input", "rectified/pointcloud_ex"), - ("output", "outlier_filtered/pointcloud"), + ("output", "pointcloud"), ], extra_arguments=[{"use_intra_process_comms": LaunchConfiguration("use_intra_process")}], ) From 6eaf77d918cd7d8c80ed4748b4e84cec2e88a6d5 Mon Sep 17 00:00:00 2001 From: yamato-ando Date: Wed, 6 Dec 2023 14:41:48 +0900 Subject: [PATCH 11/12] add T.B.D Signed-off-by: yamato-ando --- .../autoware-interfaces/components/sensing.md | 32 +++++++++---------- 1 file changed, 16 insertions(+), 16 deletions(-) diff --git a/docs/design/autoware-interfaces/components/sensing.md b/docs/design/autoware-interfaces/components/sensing.md index ff63638b434..e4a42288f2a 100644 --- a/docs/design/autoware-interfaces/components/sensing.md +++ b/docs/design/autoware-interfaces/components/sensing.md @@ -82,26 +82,26 @@ classDef cls_sen fill:#FFE6CC,stroke:#999,stroke-width:1px; | Name | Topic | Type | Description | | -------------------- | -------------------------------------------- | ------------------------------------------------------------------------------------------------------------------------------------------------------------------------ | ------------------------------------------- | -| Ultrasonics | | [sensor_msgs/Range](https://github.com/ros2/common_interfaces/blob/rolling/sensor_msgs/msg/Range.msg) | Distance data from ultrasonic radar driver. | -| Camera Image | | [sensor_msgs/Image](https://github.com/ros2/common_interfaces/blob/rolling/sensor_msgs/msg/Image.msg) | Image data from camera driver. | -| Radar Tracks | | [radar_msgs/RadarTracks](https://github.com/ros-perception/radar_msgs/blob/ros2/msg/RadarTracks.msg) | Tracks from radar driver. | -| Radar Scan | | [radar_msgs/RadarScan](https://github.com/ros-perception/radar_msgs/blob/ros2/msg/RadarScan.msg) | Scan from radar driver. | +| Ultrasonics | T.B.D | [sensor_msgs/Range](https://github.com/ros2/common_interfaces/blob/rolling/sensor_msgs/msg/Range.msg) | Distance data from ultrasonic radar driver. | +| Camera Image | T.B.D | [sensor_msgs/Image](https://github.com/ros2/common_interfaces/blob/rolling/sensor_msgs/msg/Image.msg) | Image data from camera driver. | +| Radar Tracks | T.B.D | [radar_msgs/RadarTracks](https://github.com/ros-perception/radar_msgs/blob/ros2/msg/RadarTracks.msg) | Tracks from radar driver. | +| Radar Scan | T.B.D | [radar_msgs/RadarScan](https://github.com/ros-perception/radar_msgs/blob/ros2/msg/RadarScan.msg) | Scan from radar driver. | | Lidar Point Cloud | `/sensing/lidar//pointcloud_raw` | [sensor_msgs/PointCloud2](https://github.com/ros2/common_interfaces/blob/rolling/sensor_msgs/msg/PointCloud2.msg) | Pointcloud from lidar driver. | -| GNSS-INS Position | | [geometry_msgs/NavSatFix](https://github.com/ros2/common_interfaces/blob/rolling/sensor_msgs/msg/NavSatFix.msg) | Initial pose from GNSS driver. | -| GNSS-INS Orientation | | [autoware_sensing_msgs/GnssInsOrientationStamped](https://github.com/autowarefoundation/autoware_msgs/blob/main/autoware_sensing_msgs/msg/GnssInsOrientationStamped.msg) | Initial orientation from GNSS driver. | -| GNSS Velocity | | [geometry_msgs/TwistWithCovarianceStamped](https://github.com/ros2/common_interfaces/blob/rolling/geometry_msgs/msg/TwistWithCovarianceStamped.msg) | Initial velocity from GNSS driver. | -| GNSS Acceleration | | [geometry_msgs/AccelWithCovarianceStamped](https://github.com/ros2/common_interfaces/blob/rolling/geometry_msgs/msg/AccelWithCovarianceStamped.msg) | Initial acceleration from GNSS driver. | +| GNSS-INS Position | T.B.D | [geometry_msgs/NavSatFix](https://github.com/ros2/common_interfaces/blob/rolling/sensor_msgs/msg/NavSatFix.msg) | Initial pose from GNSS driver. | +| GNSS-INS Orientation | T.B.D | [autoware_sensing_msgs/GnssInsOrientationStamped](https://github.com/autowarefoundation/autoware_msgs/blob/main/autoware_sensing_msgs/msg/GnssInsOrientationStamped.msg) | Initial orientation from GNSS driver. | +| GNSS Velocity | T.B.D | [geometry_msgs/TwistWithCovarianceStamped](https://github.com/ros2/common_interfaces/blob/rolling/geometry_msgs/msg/TwistWithCovarianceStamped.msg) | Initial velocity from GNSS driver. | +| GNSS Acceleration | T.B.D | [geometry_msgs/AccelWithCovarianceStamped](https://github.com/ros2/common_interfaces/blob/rolling/geometry_msgs/msg/AccelWithCovarianceStamped.msg) | Initial acceleration from GNSS driver. | ## Output | Name | Topic | Type | Description | | --------------------- | ----------------------------------------- | --------------------------------------------------------------------------------------------------------------------------------------------------- | ------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------- | -| Ultrasonics | | [sensor_msgs/Range](https://github.com/ros2/common_interfaces/blob/rolling/sensor_msgs/msg/Range.msg) | Distance data from ultrasonic radar. Used by the Perception. | -| Camera Image | | [sensor_msgs/Image](https://github.com/ros2/common_interfaces/blob/rolling/sensor_msgs/msg/Image.msg) | Image data from camera. Used by the Perception. | -| Combined Radar Tracks | | [radar_msgs/RadarTracks.msg](https://github.com/ros-perception/radar_msgs/blob/ros2/msg/RadarTracks.msg) | Radar tracks from radar. Used by the Perception. | -| Radar Point Cloud | | [radar_msgs/RadarScan.msg](https://github.com/ros-perception/radar_msgs/blob/ros2/msg/RadarScan.msg) | Pointcloud from radar. Used by the Perception. | +| Ultrasonics | T.B.D | [sensor_msgs/Range](https://github.com/ros2/common_interfaces/blob/rolling/sensor_msgs/msg/Range.msg) | Distance data from ultrasonic radar. Used by the Perception. | +| Camera Image | T.B.D | [sensor_msgs/Image](https://github.com/ros2/common_interfaces/blob/rolling/sensor_msgs/msg/Image.msg) | Image data from camera. Used by the Perception. | +| Combined Radar Tracks | T.B.D | [radar_msgs/RadarTracks.msg](https://github.com/ros-perception/radar_msgs/blob/ros2/msg/RadarTracks.msg) | Radar tracks from radar. Used by the Perception. | +| Radar Point Cloud | T.B.D | [radar_msgs/RadarScan.msg](https://github.com/ros-perception/radar_msgs/blob/ros2/msg/RadarScan.msg) | Pointcloud from radar. Used by the Perception. | | Lidar Point Cloud | `/sensing/lidar//pointcloud` | [sensor_msgs/PointCloud2](https://github.com/ros2/common_interfaces/blob/rolling/sensor_msgs/msg/PointCloud2.msg) | Lidar pointcloud after preprocessing. Used by the Perception and Localization. `` is a unique name for identifying each LiDAR or the group name when multiple LiDARs are combined. Specifically, the concatenated point cloud of all LiDARs is assigned the `` name `concatenated`. | -| GNSS-INS pose | | [geometry_msgs/PoseWithCovarianceStamped](https://github.com/ros2/common_interfaces/blob/rolling/geometry_msgs/msg/PoseWithCovarianceStamped.msg) | Initial pose of the ego vehicle from GNSS. Used by the Localization. | -| GNSS-INS Orientation | | [sensor_msgs/Imu](https://github.com/ros2/common_interfaces/blob/rolling/sensor_msgs/msg/Imu.msg) | Orientation info from GNSS. Used by the Localization. | -| GNSS Velocity | | [geometry_msgs/TwistWithCovarianceStamped](https://github.com/ros2/common_interfaces/blob/rolling/geometry_msgs/msg/TwistWithCovarianceStamped.msg) | Velocity of the ego vehicle from GNSS. Used by the Localization. | -| GNSS Acceleration | | [geometry_msgs/AccelWithCovarianceStamped](https://github.com/ros2/common_interfaces/blob/rolling/geometry_msgs/msg/AccelWithCovarianceStamped.msg) | Acceleration of the ego vehicle from GNSS. Used by the Localization. | +| GNSS-INS pose | T.B.D | [geometry_msgs/PoseWithCovarianceStamped](https://github.com/ros2/common_interfaces/blob/rolling/geometry_msgs/msg/PoseWithCovarianceStamped.msg) | Initial pose of the ego vehicle from GNSS. Used by the Localization. | +| GNSS-INS Orientation | T.B.D | [sensor_msgs/Imu](https://github.com/ros2/common_interfaces/blob/rolling/sensor_msgs/msg/Imu.msg) | Orientation info from GNSS. Used by the Localization. | +| GNSS Velocity | T.B.D | [geometry_msgs/TwistWithCovarianceStamped](https://github.com/ros2/common_interfaces/blob/rolling/geometry_msgs/msg/TwistWithCovarianceStamped.msg) | Velocity of the ego vehicle from GNSS. Used by the Localization. | +| GNSS Acceleration | T.B.D | [geometry_msgs/AccelWithCovarianceStamped](https://github.com/ros2/common_interfaces/blob/rolling/geometry_msgs/msg/AccelWithCovarianceStamped.msg) | Acceleration of the ego vehicle from GNSS. Used by the Localization. | From baab28a52451ec2baf680ccbb6d69acef8288a1a Mon Sep 17 00:00:00 2001 From: "pre-commit-ci[bot]" <66853113+pre-commit-ci[bot]@users.noreply.github.com> Date: Wed, 6 Dec 2023 05:43:06 +0000 Subject: [PATCH 12/12] style(pre-commit): autofix --- .../autoware-interfaces/components/sensing.md | 32 +++++++++---------- 1 file changed, 16 insertions(+), 16 deletions(-) diff --git a/docs/design/autoware-interfaces/components/sensing.md b/docs/design/autoware-interfaces/components/sensing.md index e4a42288f2a..5461cc44316 100644 --- a/docs/design/autoware-interfaces/components/sensing.md +++ b/docs/design/autoware-interfaces/components/sensing.md @@ -82,26 +82,26 @@ classDef cls_sen fill:#FFE6CC,stroke:#999,stroke-width:1px; | Name | Topic | Type | Description | | -------------------- | -------------------------------------------- | ------------------------------------------------------------------------------------------------------------------------------------------------------------------------ | ------------------------------------------- | -| Ultrasonics | T.B.D | [sensor_msgs/Range](https://github.com/ros2/common_interfaces/blob/rolling/sensor_msgs/msg/Range.msg) | Distance data from ultrasonic radar driver. | -| Camera Image | T.B.D | [sensor_msgs/Image](https://github.com/ros2/common_interfaces/blob/rolling/sensor_msgs/msg/Image.msg) | Image data from camera driver. | -| Radar Tracks | T.B.D | [radar_msgs/RadarTracks](https://github.com/ros-perception/radar_msgs/blob/ros2/msg/RadarTracks.msg) | Tracks from radar driver. | -| Radar Scan | T.B.D | [radar_msgs/RadarScan](https://github.com/ros-perception/radar_msgs/blob/ros2/msg/RadarScan.msg) | Scan from radar driver. | +| Ultrasonics | T.B.D | [sensor_msgs/Range](https://github.com/ros2/common_interfaces/blob/rolling/sensor_msgs/msg/Range.msg) | Distance data from ultrasonic radar driver. | +| Camera Image | T.B.D | [sensor_msgs/Image](https://github.com/ros2/common_interfaces/blob/rolling/sensor_msgs/msg/Image.msg) | Image data from camera driver. | +| Radar Tracks | T.B.D | [radar_msgs/RadarTracks](https://github.com/ros-perception/radar_msgs/blob/ros2/msg/RadarTracks.msg) | Tracks from radar driver. | +| Radar Scan | T.B.D | [radar_msgs/RadarScan](https://github.com/ros-perception/radar_msgs/blob/ros2/msg/RadarScan.msg) | Scan from radar driver. | | Lidar Point Cloud | `/sensing/lidar//pointcloud_raw` | [sensor_msgs/PointCloud2](https://github.com/ros2/common_interfaces/blob/rolling/sensor_msgs/msg/PointCloud2.msg) | Pointcloud from lidar driver. | -| GNSS-INS Position | T.B.D | [geometry_msgs/NavSatFix](https://github.com/ros2/common_interfaces/blob/rolling/sensor_msgs/msg/NavSatFix.msg) | Initial pose from GNSS driver. | -| GNSS-INS Orientation | T.B.D | [autoware_sensing_msgs/GnssInsOrientationStamped](https://github.com/autowarefoundation/autoware_msgs/blob/main/autoware_sensing_msgs/msg/GnssInsOrientationStamped.msg) | Initial orientation from GNSS driver. | -| GNSS Velocity | T.B.D | [geometry_msgs/TwistWithCovarianceStamped](https://github.com/ros2/common_interfaces/blob/rolling/geometry_msgs/msg/TwistWithCovarianceStamped.msg) | Initial velocity from GNSS driver. | -| GNSS Acceleration | T.B.D | [geometry_msgs/AccelWithCovarianceStamped](https://github.com/ros2/common_interfaces/blob/rolling/geometry_msgs/msg/AccelWithCovarianceStamped.msg) | Initial acceleration from GNSS driver. | +| GNSS-INS Position | T.B.D | [geometry_msgs/NavSatFix](https://github.com/ros2/common_interfaces/blob/rolling/sensor_msgs/msg/NavSatFix.msg) | Initial pose from GNSS driver. | +| GNSS-INS Orientation | T.B.D | [autoware_sensing_msgs/GnssInsOrientationStamped](https://github.com/autowarefoundation/autoware_msgs/blob/main/autoware_sensing_msgs/msg/GnssInsOrientationStamped.msg) | Initial orientation from GNSS driver. | +| GNSS Velocity | T.B.D | [geometry_msgs/TwistWithCovarianceStamped](https://github.com/ros2/common_interfaces/blob/rolling/geometry_msgs/msg/TwistWithCovarianceStamped.msg) | Initial velocity from GNSS driver. | +| GNSS Acceleration | T.B.D | [geometry_msgs/AccelWithCovarianceStamped](https://github.com/ros2/common_interfaces/blob/rolling/geometry_msgs/msg/AccelWithCovarianceStamped.msg) | Initial acceleration from GNSS driver. | ## Output | Name | Topic | Type | Description | | --------------------- | ----------------------------------------- | --------------------------------------------------------------------------------------------------------------------------------------------------- | ------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------- | -| Ultrasonics | T.B.D | [sensor_msgs/Range](https://github.com/ros2/common_interfaces/blob/rolling/sensor_msgs/msg/Range.msg) | Distance data from ultrasonic radar. Used by the Perception. | -| Camera Image | T.B.D | [sensor_msgs/Image](https://github.com/ros2/common_interfaces/blob/rolling/sensor_msgs/msg/Image.msg) | Image data from camera. Used by the Perception. | -| Combined Radar Tracks | T.B.D | [radar_msgs/RadarTracks.msg](https://github.com/ros-perception/radar_msgs/blob/ros2/msg/RadarTracks.msg) | Radar tracks from radar. Used by the Perception. | -| Radar Point Cloud | T.B.D | [radar_msgs/RadarScan.msg](https://github.com/ros-perception/radar_msgs/blob/ros2/msg/RadarScan.msg) | Pointcloud from radar. Used by the Perception. | +| Ultrasonics | T.B.D | [sensor_msgs/Range](https://github.com/ros2/common_interfaces/blob/rolling/sensor_msgs/msg/Range.msg) | Distance data from ultrasonic radar. Used by the Perception. | +| Camera Image | T.B.D | [sensor_msgs/Image](https://github.com/ros2/common_interfaces/blob/rolling/sensor_msgs/msg/Image.msg) | Image data from camera. Used by the Perception. | +| Combined Radar Tracks | T.B.D | [radar_msgs/RadarTracks.msg](https://github.com/ros-perception/radar_msgs/blob/ros2/msg/RadarTracks.msg) | Radar tracks from radar. Used by the Perception. | +| Radar Point Cloud | T.B.D | [radar_msgs/RadarScan.msg](https://github.com/ros-perception/radar_msgs/blob/ros2/msg/RadarScan.msg) | Pointcloud from radar. Used by the Perception. | | Lidar Point Cloud | `/sensing/lidar//pointcloud` | [sensor_msgs/PointCloud2](https://github.com/ros2/common_interfaces/blob/rolling/sensor_msgs/msg/PointCloud2.msg) | Lidar pointcloud after preprocessing. Used by the Perception and Localization. `` is a unique name for identifying each LiDAR or the group name when multiple LiDARs are combined. Specifically, the concatenated point cloud of all LiDARs is assigned the `` name `concatenated`. | -| GNSS-INS pose | T.B.D | [geometry_msgs/PoseWithCovarianceStamped](https://github.com/ros2/common_interfaces/blob/rolling/geometry_msgs/msg/PoseWithCovarianceStamped.msg) | Initial pose of the ego vehicle from GNSS. Used by the Localization. | -| GNSS-INS Orientation | T.B.D | [sensor_msgs/Imu](https://github.com/ros2/common_interfaces/blob/rolling/sensor_msgs/msg/Imu.msg) | Orientation info from GNSS. Used by the Localization. | -| GNSS Velocity | T.B.D | [geometry_msgs/TwistWithCovarianceStamped](https://github.com/ros2/common_interfaces/blob/rolling/geometry_msgs/msg/TwistWithCovarianceStamped.msg) | Velocity of the ego vehicle from GNSS. Used by the Localization. | -| GNSS Acceleration | T.B.D | [geometry_msgs/AccelWithCovarianceStamped](https://github.com/ros2/common_interfaces/blob/rolling/geometry_msgs/msg/AccelWithCovarianceStamped.msg) | Acceleration of the ego vehicle from GNSS. Used by the Localization. | +| GNSS-INS pose | T.B.D | [geometry_msgs/PoseWithCovarianceStamped](https://github.com/ros2/common_interfaces/blob/rolling/geometry_msgs/msg/PoseWithCovarianceStamped.msg) | Initial pose of the ego vehicle from GNSS. Used by the Localization. | +| GNSS-INS Orientation | T.B.D | [sensor_msgs/Imu](https://github.com/ros2/common_interfaces/blob/rolling/sensor_msgs/msg/Imu.msg) | Orientation info from GNSS. Used by the Localization. | +| GNSS Velocity | T.B.D | [geometry_msgs/TwistWithCovarianceStamped](https://github.com/ros2/common_interfaces/blob/rolling/geometry_msgs/msg/TwistWithCovarianceStamped.msg) | Velocity of the ego vehicle from GNSS. Used by the Localization. | +| GNSS Acceleration | T.B.D | [geometry_msgs/AccelWithCovarianceStamped](https://github.com/ros2/common_interfaces/blob/rolling/geometry_msgs/msg/AccelWithCovarianceStamped.msg) | Acceleration of the ego vehicle from GNSS. Used by the Localization. |