From 5de43b9acdfc556bc4f22bca6a2fca272a3f5324 Mon Sep 17 00:00:00 2001 From: Ryohsuke Mitsudome Date: Tue, 19 Nov 2024 00:11:17 +0900 Subject: [PATCH 1/3] docs: replace autoware_auto_msgs with autoware_msgs in autoware-interfaces page Signed-off-by: Ryohsuke Mitsudome --- .../autoware-interfaces/components/control.md | 6 ++--- .../components/localization.md | 4 ++-- .../autoware-interfaces/components/map.md | 6 ++--- .../components/perception-interface.md | 16 ++++++------- .../components/perception.md | 10 ++++---- .../components/planning.md | 18 +++++++-------- .../components/vehicle-interface.md | 23 +++++++++---------- 7 files changed, 41 insertions(+), 42 deletions(-) diff --git a/docs/design/autoware-interfaces/components/control.md b/docs/design/autoware-interfaces/components/control.md index 0f2ee2ebbda..73822f02d9b 100644 --- a/docs/design/autoware-interfaces/components/control.md +++ b/docs/design/autoware-interfaces/components/control.md @@ -43,13 +43,13 @@ TODO This represents the reported physical efforts exerted by the vehicle actuat A motion signal to drive the vehicle, achieved by the low-level controller in the vehicle layer. Used by the Vehicle Interface. -- [autoware_auto_control_msgs/AckermannControlCommand](https://gitlab.com/autowarefoundation/autoware.auto/autoware_auto_msgs/-/blob/master/autoware_auto_control_msgs/msg/AckermannControlCommand.idl) +- [autoware_control_msgs/Control](https://github.com/autowarefoundation/autoware_msgs/blob/main/autoware_control_msgs/msg/Control.msg) - builtin_interfaces::msg::Time stamp - - [autoware_auto_control_msgs/AckermannLateralCommand](https://gitlab.com/autowarefoundation/autoware.auto/autoware_auto_msgs/-/blob/master/autoware_auto_control_msgs/msg/AckermannLateralCommand.idl) lateral + - [autoware_control_msgs/Lateral](https://github.com/autowarefoundation/autoware_msgs/blob/main/autoware_control_msgs/msg/Lateral.msg) lateral - builtin_interfaces::msg::Time stamp - float steering_tire_angle - float steering_tire_rotation_rate - - [autoware_auto_control_msgs/LongitudinalCommand](https://gitlab.com/autowarefoundation/autoware.auto/autoware_auto_msgs/-/blob/master/autoware_auto_control_msgs/msg/LongitudinalCommand.idl) longitudinal + - [autoware_control_msgs/Longitudinal](https://github.com/autowarefoundation/autoware_msgs/blob/main/autoware_control_msgs/msg/Lateral.msg) longitudinal - builtin_interfaces::msg::Time stamp - builtin_interfaces::msg::Duration duration - builtin_interfaces::msg::Duration time_step diff --git a/docs/design/autoware-interfaces/components/localization.md b/docs/design/autoware-interfaces/components/localization.md index 3c50e2b1eb2..5d0e9c61213 100644 --- a/docs/design/autoware-interfaces/components/localization.md +++ b/docs/design/autoware-interfaces/components/localization.md @@ -84,13 +84,13 @@ Current orientation, angular velocity and linear acceleration of ego, calculated Current velocity of the ego vehicle, published by the vehicle interface. -- autoware_auto_vehicle_msgs/msg/VelocityReport +- autoware_vehicle_msgs/msg/VelocityReport - std_msgs/msg/Header header; - float longitudinal_velocity; - float lateral_velocity; - float heading_rate; -Before the velocity input localization interface, module `vehicle_velocity_converter` converts message type `autoware_auto_vehicle_msgs/msg/VelocityReport` to `geometry_msgs/msg/TwistWithCovarianceStamped`. +Before the velocity input localization interface, module `vehicle_velocity_converter` converts message type `autoware_vehicle_msgs/msg/VelocityReport` to `geometry_msgs/msg/TwistWithCovarianceStamped`. ## Outputs diff --git a/docs/design/autoware-interfaces/components/map.md b/docs/design/autoware-interfaces/components/map.md index 578981ad963..d484db1af13 100644 --- a/docs/design/autoware-interfaces/components/map.md +++ b/docs/design/autoware-interfaces/components/map.md @@ -26,9 +26,9 @@ It loads point cloud files and publishes the maps to the other Autoware nodes in ### Lanelet2 map -It loads a Lanelet2 file and publishes the map data as `autoware_auto_mapping_msgs/msg/HADMapBin` message. The lan/lon coordinates are projected onto the MGRS coordinates. +It loads a Lanelet2 file and publishes the map data as `autoware_map_msgs/msg/LaneletMapBin` message. The lan/lon coordinates are projected onto the MGRS coordinates. -- autoware_auto_mapping_msgs/msg/HADMapBin +- autoware_map_msgs/msg/LaneletMapBin - std_msgs/Header header - string version_map_format - string version_map @@ -37,6 +37,6 @@ It loads a Lanelet2 file and publishes the map data as `autoware_auto_mapping_ms ### Lanelet2 map visualization -Visualize `autoware_auto_mapping_msgs/HADMapBin` messages in `Rviz`. +Visualize `autoware_map_msgs/msg/LaneletMapBin` messages in `Rviz`. - visualization_msgs/msg/MarkerArray diff --git a/docs/design/autoware-interfaces/components/perception-interface.md b/docs/design/autoware-interfaces/components/perception-interface.md index a618241ebd7..3c72c809882 100644 --- a/docs/design/autoware-interfaces/components/perception-interface.md +++ b/docs/design/autoware-interfaces/components/perception-interface.md @@ -14,13 +14,13 @@ graph TD sensor_msgs/PointCloud2"):::cls_sen msg_lanenet("Lanelet2 Map - autoware_auto_mapping_msgs/HADMapBin"):::cls_loc + autoware_map_msgs/LaneletMapBin"):::cls_loc msg_vks("Vehicle Kinematic State nav_msgs/Odometry"):::cls_loc msg_obj("3D Object Predictions - autoware_auto_perception_msgs/PredictedObjects"):::cls_per + autoware_perception_msgs/PredictedObjects"):::cls_per msg_tl("Traffic Light Response autoware_perception_msgs/TrafficSignalArray"):::cls_per @@ -72,23 +72,23 @@ map of the environment. See [outputs of Map](https://autowarefoundation.github.i 3D Objects detected, tracked and predicted by sensor fusing. -- [autoware_auto_perception_msgs/msg/PredictedObjects](https://gitlab.com/autowarefoundation/autoware.auto/autoware_auto_msgs/-/blob/master/autoware_auto_perception_msgs/msg/PredictedObjects.idl) +- [autoware_perception_msgs/msg/PredictedObjects](https://github.com/autowarefoundation/autoware_msgs/blob/main/autoware_perception_msgs/msg/PredictedObjects.msg) - [std_msgs/Header](https://docs.ros.org/en/noetic/api/std_msgs/html/msg/Header.html) header - - sequence<[autoware_auto_perception_msgs::msg::PredictedObject](https://gitlab.com/autowarefoundation/autoware.auto/autoware_auto_msgs/-/blob/master/autoware_auto_perception_msgs/msg/PredictedObject.idl)> objects + - sequence<[autoware_perception_msgs::msg::PredictedObject](https://github.com/autowarefoundation/autoware_msgs/blob/main/autoware_perception_msgs/msg/PredictedObject.msg)> objects - unique_identifier_msgs::msg::UUID uuid - float existence_probability - - sequence<[autoware_auto_perception_msgs::msg::ObjectClassification](https://gitlab.com/autowarefoundation/autoware.auto/autoware_auto_msgs/-/blob/master/autoware_auto_perception_msgs/msg/ObjectClassification.idl)> classification + - sequence<[autoware_perception_msgs::msg::ObjectClassification](https://github.com/autowarefoundation/autoware_msgs/blob/main/autoware_perception_msgs/msg/ObjectClassification.msg)> classification - uint8 classification - float probability - - [autoware_auto_perception_msgs::msg::PredictedObjectKinematics](https://gitlab.com/autowarefoundation/autoware.auto/autoware_auto_msgs/-/blob/master/autoware_auto_perception_msgs/msg/PredictedObjectKinematics.idl) kinematics + - [autoware_perception_msgs::msg::PredictedObjectKinematics](https://github.com/autowarefoundation/autoware_msgs/blob/main/autoware_perception_msgs/msg/PredictedObjectKinematics.msg) kinematics - [geometry_msgs::msg::PoseWithCovariance](https://docs.ros.org/en/noetic/api/geometry_msgs/html/msg/PoseWithCovariance.html) initial_pose - [geometry_msgs::msg::TwistWithCovariance](https://docs.ros.org/en/noetic/api/geometry_msgs/html/msg/TwistWithCovariance.html) - [geometry_msgs::msg::AccelWithCovariance](https://docs.ros.org/en/noetic/api/geometry_msgs/html/msg/AccelWithCovariance.html) initial_acceleration - - sequence<[autoware_auto_perception_msgs::msg::PredictedPath](https://gitlab.com/autowarefoundation/autoware.auto/autoware_auto_msgs/-/blob/master/autoware_auto_perception_msgs/msg/PredictedPath.idl), 10> predicted_paths + - sequence<[autoware_perception_msgs::msg::PredictedPath](https://github.com/autowarefoundation/autoware_msgs/blob/main/autoware_perception_msgs/msg/PredictedPath.msg), 10> predicted_paths - sequence<[geometry_msgs::msg::Pose](https://docs.ros.org/en/lunar/api/geometry_msgs/html/msg/Pose.html), 100> path - builtin_interfaces::msg::Duration time_step - float confidence - - sequence<[autoware_auto_perception_msgs::msg::Shape](https://gitlab.com/autowarefoundation/autoware.auto/autoware_auto_msgs/-/blob/master/autoware_auto_perception_msgs/msg/Shape.idl), 5> shape + - sequence<[autoware_perception_msgs::msg::Shape](https://github.com/autowarefoundation/autoware_msgs/blob/main/autoware_perception_msgs/msg/Shape.msg), 5> shape - [geometry_msgs::msg::Polygon](https://docs.ros.org/en/noetic/api/geometry_msgs/html/msg/Polygon.html) polygon - float height diff --git a/docs/design/autoware-interfaces/components/perception.md b/docs/design/autoware-interfaces/components/perception.md index 032be3a477f..b5b42f21812 100644 --- a/docs/design/autoware-interfaces/components/perception.md +++ b/docs/design/autoware-interfaces/components/perception.md @@ -1,6 +1,6 @@ # Perception -This page provides specific specifications about the Interface of the Perception Component. +This page provides specific specifications about the Interface of the Perception Component. Please refer to [the perception architecture reference implementation design](../../autoware-architecture/perception/reference_implementation.md) for concepts and data flow. ## Input @@ -9,7 +9,7 @@ Please refer to [the perception architecture reference implementation design](.. | Name | Topic / Service | Type | Description | | --------------- | ----------------------------------- | -------------------------------------------------------------------------------------------------------------------------------------------------------------------------- | -------------------------------------------- | -| Vector Map | `/map/vector_map` | [autoware_auto_mapping_msgs/msg/HADMapBin](https://github.com/tier4/autoware_auto_msgs/blob/tier4/main/autoware_auto_mapping_msgs/msg/HADMapBin.idl) | HD Map including the information about lanes | +| Vector Map | `/map/vector_map` | [autoware_map_msgs/msg/LaneletMapBin](https://github.com/autowarefoundation/autoware_msgs/blob/main/autoware_map_msgs/msg/LaneletMapBin.msg) | HD Map including the information about lanes | | Point Cloud Map | `/service/get_differential_pcd_map` | [autoware_map_msgs/srv/GetDifferentialPointCloudMap](https://github.com/autowarefoundation/autoware_msgs/blob/main/autoware_map_msgs/srv/GetDifferentialPointCloudMap.srv) | Point Cloud Map | Notes: @@ -24,7 +24,7 @@ Notes: | Camera Image | `/sensing/camera/camera*/image_rect_color` | [sensor_msgs/Image](https://github.com/ros2/common_interfaces/blob/humble/sensor_msgs/msg/Image.msg) | Camera image data, processed with Lens Distortion Correction (LDC) | | Camera Image | `/sensing/camera/camera*/image_raw` | [sensor_msgs/Image](https://github.com/ros2/common_interfaces/blob/humble/sensor_msgs/msg/Image.msg) | Camera image data, not processed with Lens Distortion Correction (LDC) | | Point Cloud | `/sensing/lidar/concatenated/pointcloud` | [sensor_msgs/PointCloud2](https://github.com/ros2/common_interfaces/blob/humble/sensor_msgs/msg/PointCloud2.msg) | Concatenated point cloud from multiple LiDAR sources | -| Radar Object | `/sensing/radar/detected_objects` | [autoware_auto_perception_msgs/msg/DetectedObject](https://gitlab.com/autowarefoundation/autoware.auto/autoware_auto_msgs/-/blob/master/autoware_auto_perception_msgs/msg/DetectedObject.idl) | Radar objects | +| Radar Object | `/sensing/radar/detected_objects` | [autoware_perception_msgs/msg/DetectedObject](https://github.com/autowarefoundation/autoware_msgs/blob/main/autoware_perception_msgs/msg/DetectedObjects.msg) | Radar objects | ### From Localization Component @@ -46,7 +46,7 @@ Please refer to [the perception component design](../../autoware-architecture/pe | Name | Topic | Type | Description | | ------------------ | ------------------------------------------------------- | ------------------------------------------------------------------------------------------------------------------------------------------------------------------------ | --------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------- | -| Dynamic Objects | `/perception/object_recognition/objects` | [autoware_auto_perception_msgs/msg/PredictedObjects](https://github.com/tier4/autoware_auto_msgs/blob/tier4/main/autoware_auto_perception_msgs/msg/PredictedObjects.idl) | Set of dynamic objects with information such as a object class and a shape of the objects. These objects did not exist when the map was generated and are not contained within the map. | +| Dynamic Objects | `/perception/object_recognition/objects` | [autoware_perception_msgs/msg/PredictedObjects](https://github.com/autowarefoundation/autoware_msgs/blob/main/autoware_perception_msgs/msg/PredictedObjects.msg) | Set of dynamic objects with information such as a object class and a shape of the objects. These objects did not exist when the map was generated and are not contained within the map. | | Obstacles | `/perception/obstacle_segmentation/pointcloud` | [sensor_msgs/PointCloud2](https://github.com/ros2/common_interfaces/blob/humble/sensor_msgs/msg/PointCloud2.msg) | Obstacles, including both dynamic objects and static obstacles that requires the ego vehicle either steer clear of them or come to a stop in front of the obstacles. | | Occupancy Grid Map | `/perception/occupancy_grid_map/map` | [nav_msgs/msg/OccupancyGrid](https://docs.ros.org/en/latest/api/nav_msgs/html/msg/OccupancyGrid.html) | The map with the information about the presence of obstacles and blind spot | -| Traffic Signal | `/perception/traffic_light_recognition/traffic_signals` | [autoware_perception_msgs::msg::TrafficSignalArray](https://github.com/autowarefoundation/autoware_msgs/blob/main/autoware_perception_msgs/msg/TrafficSignalArray.msg) | The traffic signal information such as a color (green, yellow, read) and an arrow (right, left, straight) | +| Traffic Signal | `/perception/traffic_light_recognition/traffic_signals` | [autoware_perception_msgs::msg::TrafficLightGroupArray](https://github.com/autowarefoundation/autoware_msgs/blob/main/autoware_perception_msgs/msg/TrafficLightGroupArray.msg) | The traffic signal information such as a color (green, yellow, read) and an arrow (right, left, straight) | diff --git a/docs/design/autoware-interfaces/components/planning.md b/docs/design/autoware-interfaces/components/planning.md index 8b4ba097934..7676e0cb1ea 100644 --- a/docs/design/autoware-interfaces/components/planning.md +++ b/docs/design/autoware-interfaces/components/planning.md @@ -12,7 +12,7 @@ This page provides specific specifications about the Interface of the Planning C | Name | Topic | Type | Description | | ---------- | ----------------- | ---------------------------------------------------------------------------------------------------------------------------------------------------- | ------------------------------------------------------ | -| Vector Map | `/map/vector_map` | [autoware_auto_mapping_msgs/msg/HADMapBin](https://github.com/tier4/autoware_auto_msgs/blob/tier4/main/autoware_auto_mapping_msgs/msg/HADMapBin.idl) | Map of the environment where the planning takes place. | +| Vector Map | `/map/vector_map` | [autoware_map_msgs/msg/LaneletMapBin](https://github.com/autowarefoundation/autoware_msgs/blob/main/autoware_map_msgs/msg/LaneletMapBin.msg) | Map of the environment where the planning takes place. | ### From Localization Component @@ -27,10 +27,10 @@ This page provides specific specifications about the Interface of the Planning C | Name | Topic | Type | Description | | ------------------ | ------------------------------------------------------- | ---------------------------------------------------------------------------------------------------------------------------------------------------------------------------- | ------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------- | -| Objects | `/perception/object_recognition/objects` | [autoware_auto_perception_msgs/msg/PredictedObjects](https://github.com/tier4/autoware_auto_msgs/blob/tier4/main/autoware_auto_perception_msgs/msg/PredictedObjects.idl) | Set of perceived objects around ego that need to be avoided or followed when planning a trajectory. This contains semantics information such as a object class (e.g. vehicle, pedestrian, etc) or a shape of the objects. | +| Objects | `/perception/object_recognition/objects` | [autoware_perception_msgs/msg/PredictedObjects](https://github.com/autowarefoundation/autoware_msgs/blob/main/autoware_perception_msgs/msg/PredictedObjects.msg) | Set of perceived objects around ego that need to be avoided or followed when planning a trajectory. This contains semantics information such as a object class (e.g. vehicle, pedestrian, etc) or a shape of the objects. | | Obstacles | `/perception/obstacle_segmentation/pointcloud` | [sensor_msgs/msg/PointCloud2](https://docs.ros.org/en/latest/api/sensor_msgs/html/msg/PointCloud2.html) | Set of perceived obstacles around ego that need to be avoided or followed when planning a trajectory. This only contains a primitive information of the obstacle. No shape nor velocity information. | | Occupancy Grid Map | `/perception/occupancy_grid_map/map` | [nav_msgs/msg/OccupancyGrid](https://docs.ros.org/en/latest/api/nav_msgs/html/msg/OccupancyGrid.html) | Contains the presence of obstacles and blind spot information (represented as UNKNOWN). | -| Traffic Signal | `/perception/traffic_light_recognition/traffic_signals` | [autoware_auto_perception_msgs/msg/TrafficSignalArray](https://github.com/tier4/autoware_auto_msgs/blob/tier4/main/autoware_auto_perception_msgs/msg/TrafficSignalArray.idl) | Contains the traffic signal information such as a color (green, yellow, read) and an arrow (right, left, straight). | +| Traffic Signal | `/perception/traffic_light_recognition/traffic_signals` | [autoware_perception_msgs::msg::TrafficLightGroupArray](https://github.com/autowarefoundation/autoware_msgs/blob/main/autoware_perception_msgs/msg/TrafficLightGroupArray.msg) | Contains the traffic signal information such as a color (green, yellow, read) and an arrow (right, left, straight). | **TODO**: The type of the `Obstacles` information should not depend on the specific sensor message type (now `PointCloud`). It needs to be fixed. @@ -56,9 +56,9 @@ This page provides specific specifications about the Interface of the Planning C | Name | Topic | Type | Description | | -------------- | ------------------------------- | ---------------------------------------------------------------------------------------------------------------------------------------------------------------------------- | ------------------------------------------------------------------------------------------ | -| Trajectory | `/planning/trajectory` | [autoware_auto_planning_msgs/msg/Trajectory](https://github.com/tier4/autoware_auto_msgs/blob/tier4/main/autoware_auto_planning_msgs/msg/Trajectory.idl) | A sequence of space and velocity and acceleration points to be followed by the controller. | -| Turn Indicator | `/planning/turn_indicators_cmd` | [autoware_auto_vehicle_msgs/msg/TurnIndicatorsCommand](https://github.com/tier4/autoware_auto_msgs/blob/tier4/main/autoware_auto_vehicle_msgs/msg/TurnIndicatorsCommand.idl) | Turn indicator signal to be followed by the vehicle. | -| Hazard Light | `/planning/hazard_lights_cmd` | [autoware_auto_vehicle_msgs/msg/HazardLightsCommand](https://github.com/tier4/autoware_auto_msgs/blob/tier4/main/autoware_auto_vehicle_msgs/msg/HazardLightsCommand.idl) | Hazard light signal to be followed by the vehicle. | +| Trajectory | `/planning/trajectory` | [autoware_planning_msgs/msg/Trajectory](https://github.com/autowarefoundation/autoware_msgs/blob/main/autoware_planning_msgs/msg/Trajectory.msg) | A sequence of space and velocity and acceleration points to be followed by the controller. | +| Turn Indicator | `/planning/turn_indicators_cmd` | [autoware_vehicle_msgs/msg/TurnIndicatorsCommand](https://github.com/autowarefoundation/autoware_msgs/blob/main/autoware_vehicle_msgs/msg/TurnIndicatorsCommand.msg) | Turn indicator signal to be followed by the vehicle. | +| Hazard Light | `/planning/hazard_lights_cmd` | [autoware_vehicle_msgs/msg/HazardLightsCommand](https://github.com/autowarefoundation/autoware_msgs/blob/main/autoware_vehicle_msgs/msg/HazardLightsCommand.msg) | Hazard light signal to be followed by the vehicle. | ### To System @@ -70,7 +70,7 @@ This page provides specific specifications about the Interface of the Planning C | Name | Topic | Type | Description | | --------------- | ------------------------------ | --------------------------------------------------------------------------------------------------------------------------------------------------------------------------------- | ------------------------------------------------------------------------------------------------------------------- | -| Path Candidate | `/planning/path_candidate/*` | [autoware_auto_planning_msgs/msg/Path](https://github.com/tier4/autoware_auto_msgs/blob/tier4/main/autoware_auto_planning_msgs/msg/Path.idl) | The path Autoware is about to take. Users can interrupt the operation based on the path candidate information. | +| Path Candidate | `/planning/path_candidate/*` | [autoware_planning_msgs/msg/Path](https://github.com/autowarefoundation/autoware_msgs/blob/main/autoware_planning_msgs/msg/Path.msg) | The path Autoware is about to take. Users can interrupt the operation based on the path candidate information. | | Steering Factor | `/planning/steering_factor/*` | [autoware_adapi_v1_msgs/msg/SteeringFactorArray](https://github.com/autowarefoundation/autoware_adapi_msgs/blob/main/autoware_adapi_v1_msgs/planning/msg/SteeringFactorArray.msg) | Information about the steering maneuvers performed by Autoware (e.g., steering to the right for a right turn, etc.) | | Velocity Factor | `/planning/velocity_factors/*` | [autoware_adapi_v1_msgs/msg/VelocityFactorArray](https://github.com/autowarefoundation/autoware_adapi_msgs/blob/main/autoware_adapi_v1_msgs/planning/msg/VelocityFactorArray.msg) | Information about the velocity maneuvers performed by Autoware (e.g., stop for an obstacle, etc.) | @@ -90,10 +90,10 @@ This section explains the communication between the different planning modules s | Name | Topic | Type | Description | | ---- | ----------------------------------------------------------------- | -------------------------------------------------------------------------------------------------------------------------------------------- | ----------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------- | -| Path | `/planning/scenario_planning/lane_driving/behavior_planning/path` | [autoware_auto_planning_msgs/msg/Path](https://github.com/tier4/autoware_auto_msgs/blob/tier4/main/autoware_auto_planning_msgs/msg/Path.idl) | A sequence of approximate vehicle positions for driving, along with information on the maximum speed and the drivable areas. Modules receiving this message are expected to make changes to the path within the constraints of the drivable areas and the maximum speed, generating the desired final trajectory. | +| Path | `/planning/scenario_planning/lane_driving/behavior_planning/path` | [autoware_planning_msgs/msg/Path](https://github.com/autowarefoundation/autoware_msgs/blob/main/autoware_planning_msgs/msg/Path.msg) | A sequence of approximate vehicle positions for driving, along with information on the maximum speed and the drivable areas. Modules receiving this message are expected to make changes to the path within the constraints of the drivable areas and the maximum speed, generating the desired final trajectory. | ### From Scenario Planning to Validation | Name | Topic | Type | Description | | ---------- | ---------------------------------------- | -------------------------------------------------------------------------------------------------------------------------------------------------------- | ----------------------------------------------------------------------------------------------------------------------------------------------------- | -| Trajectory | `/planning/scenario_planning/trajectory` | [autoware_auto_planning_msgs/msg/Trajectory](https://github.com/tier4/autoware_auto_msgs/blob/tier4/main/autoware_auto_planning_msgs/msg/Trajectory.idl) | A sequence of precise vehicle positions, speeds, and accelerations required for driving. It is expected that the vehicle will follow this trajectory. | +| Trajectory | `/planning/scenario_planning/trajectory` | [autoware_planning_msgs/msg/Trajectory](https://github.com/autowarefoundation/autoware_msgs/blob/main/autoware_planning_msgs/msg/Trajectory.msg) | A sequence of precise vehicle positions, speeds, and accelerations required for driving. It is expected that the vehicle will follow this trajectory. | diff --git a/docs/design/autoware-interfaces/components/vehicle-interface.md b/docs/design/autoware-interfaces/components/vehicle-interface.md index d503d093f1b..6720dcef39a 100644 --- a/docs/design/autoware-interfaces/components/vehicle-interface.md +++ b/docs/design/autoware-interfaces/components/vehicle-interface.md @@ -32,22 +32,21 @@ which converts the target speed and steering angle to acceleration, steering, an | Name | Topic | Type | Description | | ---------------------- | -------------------------------------- | -------------------------------------------------------------------------------------------------------------------------------------------------------------------------------- | -------------------------------------------------------------- | -| Control command | `/control/command/control_cmd` | [autoware_auto_control_msgs/msg/AckermannControlCommand](https://github.com/tier4/autoware_auto_msgs/blob/tier4/main/autoware_auto_control_msgs/msg/AckermannControlCommand.idl) | Target controls of the vehicle (steering angle, velocity, ...) | -| Control mode command | `/control/control_mode_request` | [ControlModeCommand](https://github.com/tier4/autoware_auto_msgs/blob/tier4/main/autoware_auto_vehicle_msgs/srv/ControlModeCommand.srv) | Request to switch between manual and autonomous driving | -| Gear command | `/control/command/gear_cmd` | [autoware_auto_vehicle_msgs/msg/GearCommand](https://github.com/tier4/autoware_auto_msgs/blob/tier4/main/autoware_auto_vehicle_msgs/msg/GearCommand.idl) | Target gear of the vehicle | -| Hazard lights command | `/control/command/hazard_lights_cmd` | [autoware_auto_vehicle_msgs/msg/HazardLightsCommand](https://github.com/tier4/autoware_auto_msgs/blob/tier4/main/autoware_auto_vehicle_msgs/msg/HazardLightsCommand.idl) | Target values of the hazard lights | -| Turn indicator command | `/control/command/turn_indicators_cmd` | [autoware_auto_vehicle_msgs/msg/TurnIndicatorsCommand](https://github.com/tier4/autoware_auto_msgs/blob/tier4/main/autoware_auto_vehicle_msgs/msg/TurnIndicatorsCommand.idl) | Target values of the turn signals | +| Control command | `/control/command/control_cmd` | [autoware_control_msgs/msg/Control](https://github.com/autowarefoundation/autoware_msgs/blob/main/autoware_control_msgs/msg/Control.msg) | Target controls of the vehicle (steering angle, velocity, ...) | +| Control mode command | `/control/control_mode_request` | [autoware_vehicle_msgs/srv/ControlModeCommand](https://github.com/autowarefoundation/autoware_msgs/blob/main/autoware_vehicle_msgs/srv/ControlModeCommand.srv) | Request to switch between manual and autonomous driving | +| Gear command | `/control/command/gear_cmd` | [autoware_vehicle_msgs/msg/GearCommand](https://github.com/autowarefoundation/autoware_msgs/blob/main/autoware_vehicle_msgs/msg/GearCommand.msg) | Target gear of the vehicle | +| Hazard lights command | `/control/command/hazard_lights_cmd` | [autoware_vehicle_msgs/msg/HazardLightsCommand](https://github.com/autowarefoundation/autoware_msgs/blob/main/autoware_vehicle_msgs/msg/HazardLightsCommand.msg) | Target values of the hazard lights | +| Turn indicator command | `/control/command/turn_indicators_cmd` | [autoware_vehicle_msgs/msg/TurnIndicatorsCommand](https://github.com/autowarefoundation/autoware_msgs/blob/main/autoware_vehicle_msgs/msg/TurnIndicatorsCommand.msg) | Target values of the turn signals | ## Outputs to Autoware | Name | Topic | Type | Optional ? | Description | | ---------------------- | ---------------------------------------- | --------------------------------------------------------------------------------------------------------------------------------------------------------------------------- | ------------------------------------ | ----------------------------------------------------------------------- | | Actuation status | `/vehicle/status/actuation_status` | [tier4_vehicle_msgs/msg/ActuationStatusStamped](https://github.com/tier4/tier4_autoware_msgs/blob/tier4/universe/tier4_vehicle_msgs/msg/ActuationStatusStamped.msg) | Yes (vehicle with mechanical inputs) | Current acceleration, brake, and steer values reported by the vehicle | -| Control mode | `/vehicle/status/control_mode` | [autoware_auto_vehicle_msgs/msg/ControlModeReport](https://github.com/tier4/autoware_auto_msgs/blob/tier4/main/autoware_auto_vehicle_msgs/msg/ControlModeReport.idl) | | Current control mode (manual, autonomous, ...) | +| Control mode | `/vehicle/status/control_mode` | [autoware_vehicle_msgs/msg/ControlModeReport](https://github.com/autowarefoundation/autoware_msgs/blob/main/autoware_vehicle_msgs/msg/ControlModeReport.msg) | | Current control mode (manual, autonomous, ...) | | Door status | `/vehicle/status/door_status` | [tier4_api_msgs/msg/DoorStatus](https://github.com/tier4/tier4_autoware_msgs/blob/tier4/universe/tier4_api_msgs/msg/DoorStatus.msg) | Yes | Current door status | -| Gear report | `/vehicle/status/gear_status` | [autoware_auto_vehicle_msgs/msg/GearReport](https://github.com/tier4/autoware_auto_msgs/blob/tier4/main/autoware_auto_vehicle_msgs/msg/GearReport.idl) | | Current gear of the vehicle | -| Hazard light status | `/vehicle/status/hazard_lights_status` | [autoware_auto_vehicle_msgs/msg/HazardLightsReport](https://github.com/tier4/autoware_auto_msgs/blob/tier4/main/autoware_auto_vehicle_msgs/msg/HazardLightsReport.idl) | | Current hazard lights status | -| Steering status | `/vehicle/status/steering_status` | [autoware_auto_vehicle_msgs/msg/SteeringReport](https://github.com/tier4/autoware_auto_msgs/blob/tier4/main/autoware_auto_vehicle_msgs/msg/SteeringReport.idl) | | Current steering angle of the steering tire | -| Steering wheel status | `/vehicle/status/steering_wheel_status` | [tier4_vehicle_msgs/msg/SteeringWheelStatusStamped](https://github.com/tier4/tier4_autoware_msgs/blob/tier4/universe/tier4_vehicle_msgs/msg/SteeringWheelStatusStamped.msg) | Yes | Current steering wheel angle | -| Turn indicators status | `/vehicle/status/turn_indicators_status` | [autoware_auto_vehicle_msgs/msg/TurnIndicatorsReport](https://github.com/tier4/autoware_auto_msgs/blob/tier4/main/autoware_auto_vehicle_msgs/msg/TurnIndicatorsReport.idl) | | Current state of the left and right turn indicators | -| Velocity status | `/vehicle/status/velocity_status` | [autoware_auto_vehicle_msgs/msg/VelocityReport](https://github.com/tier4/autoware_auto_msgs/blob/tier4/main/autoware_auto_vehicle_msgs/msg/VelocityReport.idl) | | Current velocities of the vehicle (longitudinal, lateral, heading rate) | +| Gear report | `/vehicle/status/gear_status` | [autoware_vehicle_msgs/msg/GearReport](https://github.com/autowarefoundation/autoware_msgs/blob/main/autoware_vehicle_msgs/msg/GearReport.msg) | | Current gear of the vehicle | +| Hazard light status | `/vehicle/status/hazard_lights_status` | [autoware_vehicle_msgs/msg/HazardLightsReport](https://github.com/autowarefoundation/autoware_msgs/blob/main/autoware_vehicle_msgs/msg/HazardLightsReport.msg) | | Current hazard lights status | +| Steering status | `/vehicle/status/steering_status` | [autoware_vehicle_msgs/msg/SteeringReport](https://github.com/autowarefoundation/autoware_msgs/blob/main/autoware_vehicle_msgs/msg/SteeringReport.msg) | | Current steering angle of the steering tire | +| Turn indicators status | `/vehicle/status/turn_indicators_status` | [autoware_vehicle_msgs/msg/TurnIndicatorsReport](https://github.com/autowarefoundation/autoware_msgs/blob/main/autoware_vehicle_msgs/msg/TurnIndicatorsReport.msg) | | Current state of the left and right turn indicators | +| Velocity status | `/vehicle/status/velocity_status` | [autoware_vehicle_msgs/msg/VelocityReport](https://github.com/autowarefoundation/autoware_msgs/blob/main/autoware_vehicle_msgs/msg/VelocityReport.msg) | | Current velocities of the vehicle (longitudinal, lateral, heading rate) | From 8b77f539fd2a6320eec207cce2b11ccea7f942a5 Mon Sep 17 00:00:00 2001 From: Ryohsuke Mitsudome Date: Tue, 19 Nov 2024 17:30:40 +0900 Subject: [PATCH 2/3] docs: replace autoware_auto_msgs with autoware_msgs in images Signed-off-by: Ryohsuke Mitsudome --- .../Control-Bus-ODD-Architecture.drawio.svg | 2 +- ...calization-Bus-ODD-Architecture.drawio.svg | 2 +- .../Map-Bus-ODD-Architecture.drawio.svg | 2 +- .../images/Perception-Architecture.drawio.svg | 1482 +++++------------ .../Planning-Bus-ODD-Architecture.drawio.svg | 2 +- ...-Interface-Bus-ODD-Architecture.drawio.svg | 2 +- 6 files changed, 431 insertions(+), 1061 deletions(-) diff --git a/docs/design/autoware-interfaces/components/images/Control-Bus-ODD-Architecture.drawio.svg b/docs/design/autoware-interfaces/components/images/Control-Bus-ODD-Architecture.drawio.svg index 4f406971910..17283fba80a 100644 --- a/docs/design/autoware-interfaces/components/images/Control-Bus-ODD-Architecture.drawio.svg +++ b/docs/design/autoware-interfaces/components/images/Control-Bus-ODD-Architecture.drawio.svg @@ -1,4 +1,4 @@ -
Planning
Planning
Localization
Localization
Control
Control
Vehicle Interface
Vehicle Interface
Vehicle Kinematic Statenav_msgs/OdometryTrajectoryautoware_auto_planning_msgs/TrajectoryVehicle Signal Commandsautoware_auto_vehicle_msgs/- HandBrakeCommand- HazardLightsCommand- HeadlightsCommand- HornCommand- StationaryLockingCommand- TurnIndicatorsCommand- WipersCommandVehicle Control Commandautoware_auto_vehicle_msgs/AckermannControlCommandActuation Status
acceleration, brake, steering
acceleration, brake, steering
Steering Status
steering_angle
steering_angle
Text is not SVG - cannot display
\ No newline at end of file +
Planning
Planning
Localization
Localization
Control
Control
Vehicle Interface
Vehicle Interface
Vehicle Kinematic Statenav_msgs/OdometryTrajectoryautoware_planning_msgs/TrajectoryVehicle Signal Commandsautoware_vehicle_msgs/- HandBrakeCommand- HazardLightsCommand- HeadlightsCommand- HornCommand- StationaryLockingCommand- TurnIndicatorsCommand- WipersCommandVehicle Control Commandautoware_vehicle_msgs/AckermannControlCommandActuation Status
acceleration, brake, steering
acceleration, brake, steering
Steering Status
steering_angle
steering_angle
Text is not SVG - cannot display
\ No newline at end of file diff --git a/docs/design/autoware-interfaces/components/images/Localization-Bus-ODD-Architecture.drawio.svg b/docs/design/autoware-interfaces/components/images/Localization-Bus-ODD-Architecture.drawio.svg index d51e205fa97..abec9a0f29f 100644 --- a/docs/design/autoware-interfaces/components/images/Localization-Bus-ODD-Architecture.drawio.svg +++ b/docs/design/autoware-interfaces/components/images/Localization-Bus-ODD-Architecture.drawio.svg @@ -1,4 +1,4 @@ -
Manual Inital Pose
Manual Inital Pose
geometry_msgs/msg/
PoseWithCovarianceStamped
geometry_msgs/msg/...
Localization
Localization
User Interface
User Interface
Planning
Planning
Map Server
Map Server
Pointcloud Map
Pointcloud Map
sensor_msgs/msg/PointCloud2
sensor_msgs/msg/PointCloud2
Control
Control
Sensing
Sensing
 Automatic Initial Pose
 Automatic Initial Pose
geometry_msgs/msg/
PoseWithCovarianceStamped
geometry_msgs/msg/...
IMU Data
IMU Data
sensor_msgs/msg/Imu
sensor_msgs/msg/Imu
Vehicle Interface
Vehicle Interface
Velocity Status
Velocity Status
autoware_auto_vehicle_msgs/
msg/VelocityReport
autoware_auto_vehicle_msgs/...
LiDAR Scanning
LiDAR Scanning
sensor_msgs/msg/PointCloud2
sensor_msgs/msg/PointCloud2
Vehicle Control Command
Vehicle Control Command
autoware_auto_vehicle_msgs/
msg/AckermannControlCommand
autoware_auto_vehicle_msgs/...
Trajectory
Trajectory
autoware_auto_planning_msgs/
msg/Trajectory
autoware_auto_planning_msgs/...
Vehicle Acceleration
Vehicle Acceleration
geometry_msgs/msg/
AccelWithCovarianceStamped
geometry_msgs/msg/...
Vehicle Kinematic State
Vehicle Kinematic State
autoware_msgs/autoware_localization_msgs/
msg/KinematicState
autoware_msgs/autoware_localization_msgs/...
Diagnostic Manager
Diagnostic Manager
LocalizationAccuracy
LocalizationAccuracy
Vehicle Twist
Vehicle Twist
geoTwistmetry_msgs/msg/
WithCovarianceStamped
geoTwistmetry_msgs/msg/...
Vehicle Pose
Vehicle Pose
geometry_msgs/msg/
PoseWithCovarianceStamped
geometry_msgs/msg/...
Text is not SVG - cannot display
\ No newline at end of file +
Manual Inital Pose
Manual Inital Pose
geometry_msgs/msg/
PoseWithCovarianceStamped
geometry_msgs/msg/...
Localization
Localization
User Interface
User Interface
Planning
Planning
Map Server
Map Server
Pointcloud Map
Pointcloud Map
sensor_msgs/msg/PointCloud2
sensor_msgs/msg/PointCloud2
Control
Control
Sensing
Sensing
 Automatic Initial Pose
 Automatic Initial Pose
geometry_msgs/msg/
PoseWithCovarianceStamped
geometry_msgs/msg/...
IMU Data
IMU Data
sensor_msgs/msg/Imu
sensor_msgs/msg/Imu
Vehicle Interface
Vehicle Interface
Velocity Status
Velocity Status
autoware_vehicle_msgs/
msg/VelocityReport
autoware_vehicle_msgs/...
LiDAR Scanning
LiDAR Scanning
sensor_msgs/msg/PointCloud2
sensor_msgs/msg/PointCloud2
Vehicle Control Command
Vehicle Control Command
autoware_vehicle_msgs/
msg/AckermannControlCommand
autoware_vehicle_msgs/...
Trajectory
Trajectory
autoware_planning_msgs/
msg/Trajectory
autoware_planning_msgs/...
Vehicle Acceleration
Vehicle Acceleration
geometry_msgs/msg/
AccelWithCovarianceStamped
geometry_msgs/msg/...
Vehicle Kinematic State
Vehicle Kinematic State
autoware_msgs/autoware_localization_msgs/
msg/KinematicState
autoware_msgs/autoware_localization_msgs/...
Diagnostic Manager
Diagnostic Manager
LocalizationAccuracy
LocalizationAccuracy
Vehicle Twist
Vehicle Twist
geoTwistmetry_msgs/msg/
WithCovarianceStamped
geoTwistmetry_msgs/msg/...
Vehicle Pose
Vehicle Pose
geometry_msgs/msg/
PoseWithCovarianceStamped
geometry_msgs/msg/...
Text is not SVG - cannot display
\ No newline at end of file diff --git a/docs/design/autoware-interfaces/components/images/Map-Bus-ODD-Architecture.drawio.svg b/docs/design/autoware-interfaces/components/images/Map-Bus-ODD-Architecture.drawio.svg index c6d679c4802..0cdf6224bda 100644 --- a/docs/design/autoware-interfaces/components/images/Map-Bus-ODD-Architecture.drawio.svg +++ b/docs/design/autoware-interfaces/components/images/Map-Bus-ODD-Architecture.drawio.svg @@ -1,4 +1,4 @@ -
Map Server
Map Server
Lanelet2 Map Marker
Lanelet2 Map Marker
visualization_msgs/msg/MarkerArray
visualization_msgs/msg/MarkerArray
Pointcloud Map
Pointcloud Map
sensor_msgs/msg/PointCloud2
sensor_msgs/msg/PointCloud2
Lanelet2 Map
Lanelet2 Map
autoware_auto_mapping_msgs/msg/
HADMapBin
autoware_auto_mapping_msgs/msg/...
Localization
Localization
Planning
Planning
Vehicle Kinematic State
Vehicle Kinematic State
nav_msg/msg/Odometry
nav_msg/msg/Odometry
Trajectory
Trajectory
autoware_auto_planning_msgs/msg/
Trajectory
autoware_auto_planning_msgs/msg/...
3D object Predictions
3D object Predictions
autoware_auto_perception_msgs/msg/
PredictedObjects
autoware_auto_perception_msgs/msg/...
Perception
Perception
Traffic Light Response
Traffic Light Response
Text is not SVG - cannot display
\ No newline at end of file +
Map Server
Map Server
Lanelet2 Map Marker
Lanelet2 Map Marker
visualization_msgs/msg/MarkerArray
visualization_msgs/msg/MarkerArray
Pointcloud Map
Pointcloud Map
sensor_msgs/msg/PointCloud2
sensor_msgs/msg/PointCloud2
Lanelet2 Map
Lanelet2 Map
autoware_map_msgs/msg/
LaneletMapBin
autoware_map_msgs/msg/...
Localization
Localization
Planning
Planning
Vehicle Kinematic State
Vehicle Kinematic State
nav_msg/msg/Odometry
nav_msg/msg/Odometry
Trajectory
Trajectory
autoware_planning_msgs/msg/
Trajectory
autoware_planning_msgs/msg/...
3D object Predictions
3D object Predictions
autoware_perception_msgs/msg/
PredictedObjects
autoware_perception_msgs/msg/...
Perception
Perception
Traffic Light Response
Traffic Light Response
Text is not SVG - cannot display
\ No newline at end of file diff --git a/docs/design/autoware-interfaces/components/images/Perception-Architecture.drawio.svg b/docs/design/autoware-interfaces/components/images/Perception-Architecture.drawio.svg index ad575df3274..f1faad2ee5e 100644 --- a/docs/design/autoware-interfaces/components/images/Perception-Architecture.drawio.svg +++ b/docs/design/autoware-interfaces/components/images/Perception-Architecture.drawio.svg @@ -1,1064 +1,434 @@ - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - Planning - - - - Planning - - - - - - - - - - - - - Perception - - - - - - Perception - - - - - - - - - - 3D Object Predictions + + + + + + + + + + + + + + + + + +
+
+
+ Planning +
+
+
+
+ + Planning + +
- - autoware_auto_perception_msgs/ - PredictedObjects + + + + + + + + +
+
+
+ Perception +
+
+
+
+ + Perception + +
-
-
-
- - - - - - - - - - - - - Localization - - - - Localization - - - - - - - Vehicle Kinematic State - - - nav_msgs/Odometry - - - - - - - - - - - - - - - - Traffic Light Query + + + + + + +
+
+
+ Localization +
+
+
+
+ + Localization + +
-
- - 🚦 - -
-
- - - - - - - - - - Map Server - - - - Map Server - - - - - - - Lanelet2 Map - - - autoware_auto_mapping_msgs/ - HADMapBin - - - - - Camera - - - - - - - - - Image + + + + + + +
+
+
+ Control +
+
+
+
+ + Control + +
- - - sensor_msgs/Image + + + + + + +
+
+
+ Map Server +
+
+
+
+ + Map Server + +
-
-
-
- - - - - - - Lidar - - - - - - - - - - PointCloud - - sensor_msgs/PointCloud2 + + + + + + +
+
+
+ Vehicle Interface +
+
+
+
+ + Vehicle Interface + +
-
-
- -
- - - - Text is not SVG - cannot display - - - - - - - - - - - - Traffic Light Response - - - - - - + + + + + + 3D Object Predictions + - - - - 🚦 + + + autoware_perception_msgs/ + + + PredictedObjects + + + + + + + + Traffic Light Response + + + + + 🚦 + + + + + + + + + + Vehicle Kinematic State + + + + + nav_msgs/Odometry + + + + + + + + Trajectory + + + + + autoware_planning_msgs/ + + + Trajectory + + + + + + + + Vehicle Signal Commands + + + + + autoware_vehicle_msgs/ + + + - HandBrakeCommand + + + - HazardLightsCommand + + + - HeadlightsCommand + + + - HornCommand + + + - StationaryLockingCommand + + + - TurnIndicatorsCommand + + + - WipersCommand + + + + + + + + + + + + + + Lanelet2 Map + + + + + autoware_map_msgs/ + + + LaneletMapBin + + + + + + + + + + Vehicle Control Command + + + + + autoware_vehicle_msgs/ + + + AckermannControlCommand + + + + + + + + + + + + Vehicle Signal Reports + + + + + autoware_vehicle_msgs/ + + + - GearReport + + + - HandBrakeReport + + + - HazardLightsReport + + + - HeadlightsReport + + + - HornReport + + + - TurnIndicatorsReport + + + - WipersReport + + + + + + + + +
+
+
+ Diagnostics Manager +
+
+
+
+ + Diagnostics Manager + +
+
+ + + + + + Traffic Light Query + + + + + 🚦 + + + + + + + + + + + + +
+
+
+ User Interface +
+
+
+
+ + User Interface + +
+
+ + + + + + Engagement Request + + + + + - + + + + + + + + Goal Pose + + + + + geometry_msgs/PoseStamped + + + + + + + + Engagement Response + + + + + - + + + + + + + + + + + + Mission Status + + + + + ⏳ + + + + + + + + + + + + Error Status + + + +
-
- - -
+ + + + + Text is not SVG - cannot display + + + + \ No newline at end of file diff --git a/docs/design/autoware-interfaces/components/images/Planning-Bus-ODD-Architecture.drawio.svg b/docs/design/autoware-interfaces/components/images/Planning-Bus-ODD-Architecture.drawio.svg index e3ca8777d80..64932d62baf 100644 --- a/docs/design/autoware-interfaces/components/images/Planning-Bus-ODD-Architecture.drawio.svg +++ b/docs/design/autoware-interfaces/components/images/Planning-Bus-ODD-Architecture.drawio.svg @@ -1,4 +1,4 @@ -
Planning
Planning
Perception
Perception
Localization
Localization
Control
Control
Map Server
Map Server
Vehicle Interface
Vehicle Interface
3D Object Predictionsautoware_auto_perception_msgs/PredictedObjectsTraffic Light Response🚦Vehicle Kinematic Statenav_msgs/OdometryTrajectoryautoware_auto_planning_msgs/TrajectoryVehicle Signal Commandsautoware_auto_vehicle_msgs/- HandBrakeCommand- HazardLightsCommand- HeadlightsCommand- HornCommand- StationaryLockingCommand- TurnIndicatorsCommand- WipersCommandLanelet2 Mapautoware_auto_mapping_msgs/HADMapBinVehicle Control Commandautoware_auto_vehicle_msgs/AckermannControlCommandVehicle Signal Reportsautoware_auto_vehicle_msgs/- GearReport- HandBrakeReport- HazardLightsReport- HeadlightsReport- HornReport- TurnIndicatorsReport- WipersReport
Diagnostics Manager
Diagnostics Manager
Traffic Light Query🚦
User Interface
User Interface
Engagement RequestGoal Posegeometry_msgs/PoseStampedEngagement ResponseMission StatusError Status
Text is not SVG - cannot display
\ No newline at end of file +
Planning
Planning
Perception
Perception
Localization
Localization
Control
Control
Map Server
Map Server
Vehicle Interface
Vehicle Interface
3D Object Predictionsautoware_perception_msgs/PredictedObjectsTraffic Light Response🚦Vehicle Kinematic Statenav_msgs/OdometryTrajectoryautoware_planning_msgs/TrajectoryVehicle Signal Commandsautoware_vehicle_msgs/- HandBrakeCommand- HazardLightsCommand- HeadlightsCommand- HornCommand- StationaryLockingCommand- TurnIndicatorsCommand- WipersCommandLanelet2 Mapautoware_map_msgs/LaneletMapBinVehicle Control Commandautoware_vehicle_msgs/AckermannControlCommandVehicle Signal Reportsautoware_vehicle_msgs/- GearReport- HandBrakeReport- HazardLightsReport- HeadlightsReport- HornReport- TurnIndicatorsReport- WipersReport
Diagnostics Manager
Diagnostics Manager
Traffic Light Query🚦
User Interface
User Interface
Engagement RequestGoal Posegeometry_msgs/PoseStampedEngagement ResponseMission StatusError Status
Text is not SVG - cannot display
\ No newline at end of file diff --git a/docs/design/autoware-interfaces/components/images/Vehicle-Interface-Bus-ODD-Architecture.drawio.svg b/docs/design/autoware-interfaces/components/images/Vehicle-Interface-Bus-ODD-Architecture.drawio.svg index ab30e1c47c0..b35aa788621 100644 --- a/docs/design/autoware-interfaces/components/images/Vehicle-Interface-Bus-ODD-Architecture.drawio.svg +++ b/docs/design/autoware-interfaces/components/images/Vehicle-Interface-Bus-ODD-Architecture.drawio.svg @@ -1,4 +1,4 @@ -
Planning
Planning
Localization
Localization
Control
Control
Vehicle Interface
Vehicle Interface
Trajectoryautoware_auto_planning_msgs/TrajectoryVehicle Signal Commandsautoware_auto_vehicle_msgs/- HandBrakeCommand- HazardLightsCommand- HeadlightsCommand- HornCommand- StationaryLockingCommand- TurnIndicatorsCommand- WipersCommandVehicle Control Commandautoware_auto_vehicle_msgs/AckermannControlCommandVehicle Signal Reportsautoware_auto_vehicle_msgs/- GearReport- HandBrakeReport- HazardLightsReport- HeadlightsReport- HornReport- TurnIndicatorsReport- WipersReportVehicle Odometrygeometry_msgs/TwistWithCovarianceStamped
Diagnostics Manager
Diagnostics Manager
Error StatusActuation Status
acceleration, brake, steering
acceleration, brake, steering
Vehicle CommunicationVehicle Specific Protocol
Adapter
Adapter
Steering Status
steering_angle
steering_angle
Gate
Gate
Other Controls
(emergency, external, joystick, ...)
Other Controls...
Actuation Command
acceleration, brake, steering
acceleration, brake, steering
Text is not SVG - cannot display
\ No newline at end of file +
Planning
Planning
Localization
Localization
Control
Control
Vehicle Interface
Vehicle Interface
Trajectoryautoware_planning_msgs/TrajectoryVehicle Signal Commandsautoware_vehicle_msgs/- HandBrakeCommand- HazardLightsCommand- HeadlightsCommand- HornCommand- StationaryLockingCommand- TurnIndicatorsCommand- WipersCommandVehicle Control Commandautoware_vehicle_msgs/AckermannControlCommandVehicle Signal Reportsautoware_vehicle_msgs/- GearReport- HandBrakeReport- HazardLightsReport- HeadlightsReport- HornReport- TurnIndicatorsReport- WipersReportVehicle Odometrygeometry_msgs/TwistWithCovarianceStamped
Diagnostics Manager
Diagnostics Manager
Error StatusActuation Status
acceleration, brake, steering
acceleration, brake, steering
Vehicle CommunicationVehicle Specific Protocol
Adapter
Adapter
Steering Status
steering_angle
steering_angle
Gate
Gate
Other Controls
(emergency, external, joystick, ...)
Other Controls...
Actuation Command
acceleration, brake, steering
acceleration, brake, steering
Text is not SVG - cannot display
\ No newline at end of file From c660ffa5589ae7a2b4ffc2824e1a91f41dc97c53 Mon Sep 17 00:00:00 2001 From: "pre-commit-ci[bot]" <66853113+pre-commit-ci[bot]@users.noreply.github.com> Date: Tue, 19 Nov 2024 08:32:58 +0000 Subject: [PATCH 3/3] style(pre-commit): autofix --- .../components/perception-interface.md | 6 ++-- .../components/perception.md | 24 ++++++++-------- .../components/planning.md | 28 +++++++++---------- .../components/vehicle-interface.md | 22 +++++++-------- 4 files changed, 40 insertions(+), 40 deletions(-) diff --git a/docs/design/autoware-interfaces/components/perception-interface.md b/docs/design/autoware-interfaces/components/perception-interface.md index 3c72c809882..fc663b63402 100644 --- a/docs/design/autoware-interfaces/components/perception-interface.md +++ b/docs/design/autoware-interfaces/components/perception-interface.md @@ -85,9 +85,9 @@ map of the environment. See [outputs of Map](https://autowarefoundation.github.i - [geometry_msgs::msg::TwistWithCovariance](https://docs.ros.org/en/noetic/api/geometry_msgs/html/msg/TwistWithCovariance.html) - [geometry_msgs::msg::AccelWithCovariance](https://docs.ros.org/en/noetic/api/geometry_msgs/html/msg/AccelWithCovariance.html) initial_acceleration - sequence<[autoware_perception_msgs::msg::PredictedPath](https://github.com/autowarefoundation/autoware_msgs/blob/main/autoware_perception_msgs/msg/PredictedPath.msg), 10> predicted_paths - - sequence<[geometry_msgs::msg::Pose](https://docs.ros.org/en/lunar/api/geometry_msgs/html/msg/Pose.html), 100> path - - builtin_interfaces::msg::Duration time_step - - float confidence + - sequence<[geometry_msgs::msg::Pose](https://docs.ros.org/en/lunar/api/geometry_msgs/html/msg/Pose.html), 100> path + - builtin_interfaces::msg::Duration time_step + - float confidence - sequence<[autoware_perception_msgs::msg::Shape](https://github.com/autowarefoundation/autoware_msgs/blob/main/autoware_perception_msgs/msg/Shape.msg), 5> shape - [geometry_msgs::msg::Polygon](https://docs.ros.org/en/noetic/api/geometry_msgs/html/msg/Polygon.html) polygon - float height diff --git a/docs/design/autoware-interfaces/components/perception.md b/docs/design/autoware-interfaces/components/perception.md index b5b42f21812..6309eac4950 100644 --- a/docs/design/autoware-interfaces/components/perception.md +++ b/docs/design/autoware-interfaces/components/perception.md @@ -9,7 +9,7 @@ Please refer to [the perception architecture reference implementation design](.. | Name | Topic / Service | Type | Description | | --------------- | ----------------------------------- | -------------------------------------------------------------------------------------------------------------------------------------------------------------------------- | -------------------------------------------- | -| Vector Map | `/map/vector_map` | [autoware_map_msgs/msg/LaneletMapBin](https://github.com/autowarefoundation/autoware_msgs/blob/main/autoware_map_msgs/msg/LaneletMapBin.msg) | HD Map including the information about lanes | +| Vector Map | `/map/vector_map` | [autoware_map_msgs/msg/LaneletMapBin](https://github.com/autowarefoundation/autoware_msgs/blob/main/autoware_map_msgs/msg/LaneletMapBin.msg) | HD Map including the information about lanes | | Point Cloud Map | `/service/get_differential_pcd_map` | [autoware_map_msgs/srv/GetDifferentialPointCloudMap](https://github.com/autowarefoundation/autoware_msgs/blob/main/autoware_map_msgs/srv/GetDifferentialPointCloudMap.srv) | Point Cloud Map | Notes: @@ -19,11 +19,11 @@ Notes: ### From Sensing Component -| Name | Topic | Type | Description | -| ------------ | ------------------------------------------ | --------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------- | ---------------------------------------------------------------------- | -| Camera Image | `/sensing/camera/camera*/image_rect_color` | [sensor_msgs/Image](https://github.com/ros2/common_interfaces/blob/humble/sensor_msgs/msg/Image.msg) | Camera image data, processed with Lens Distortion Correction (LDC) | -| Camera Image | `/sensing/camera/camera*/image_raw` | [sensor_msgs/Image](https://github.com/ros2/common_interfaces/blob/humble/sensor_msgs/msg/Image.msg) | Camera image data, not processed with Lens Distortion Correction (LDC) | -| Point Cloud | `/sensing/lidar/concatenated/pointcloud` | [sensor_msgs/PointCloud2](https://github.com/ros2/common_interfaces/blob/humble/sensor_msgs/msg/PointCloud2.msg) | Concatenated point cloud from multiple LiDAR sources | +| Name | Topic | Type | Description | +| ------------ | ------------------------------------------ | ------------------------------------------------------------------------------------------------------------------------------------------------------------- | ---------------------------------------------------------------------- | +| Camera Image | `/sensing/camera/camera*/image_rect_color` | [sensor_msgs/Image](https://github.com/ros2/common_interfaces/blob/humble/sensor_msgs/msg/Image.msg) | Camera image data, processed with Lens Distortion Correction (LDC) | +| Camera Image | `/sensing/camera/camera*/image_raw` | [sensor_msgs/Image](https://github.com/ros2/common_interfaces/blob/humble/sensor_msgs/msg/Image.msg) | Camera image data, not processed with Lens Distortion Correction (LDC) | +| Point Cloud | `/sensing/lidar/concatenated/pointcloud` | [sensor_msgs/PointCloud2](https://github.com/ros2/common_interfaces/blob/humble/sensor_msgs/msg/PointCloud2.msg) | Concatenated point cloud from multiple LiDAR sources | | Radar Object | `/sensing/radar/detected_objects` | [autoware_perception_msgs/msg/DetectedObject](https://github.com/autowarefoundation/autoware_msgs/blob/main/autoware_perception_msgs/msg/DetectedObjects.msg) | Radar objects | ### From Localization Component @@ -44,9 +44,9 @@ Notes: Please refer to [the perception component design](../../autoware-architecture/perception/index.md#high-level-architecture) for detailed definitions of each output." -| Name | Topic | Type | Description | -| ------------------ | ------------------------------------------------------- | ------------------------------------------------------------------------------------------------------------------------------------------------------------------------ | --------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------- | -| Dynamic Objects | `/perception/object_recognition/objects` | [autoware_perception_msgs/msg/PredictedObjects](https://github.com/autowarefoundation/autoware_msgs/blob/main/autoware_perception_msgs/msg/PredictedObjects.msg) | Set of dynamic objects with information such as a object class and a shape of the objects. These objects did not exist when the map was generated and are not contained within the map. | -| Obstacles | `/perception/obstacle_segmentation/pointcloud` | [sensor_msgs/PointCloud2](https://github.com/ros2/common_interfaces/blob/humble/sensor_msgs/msg/PointCloud2.msg) | Obstacles, including both dynamic objects and static obstacles that requires the ego vehicle either steer clear of them or come to a stop in front of the obstacles. | -| Occupancy Grid Map | `/perception/occupancy_grid_map/map` | [nav_msgs/msg/OccupancyGrid](https://docs.ros.org/en/latest/api/nav_msgs/html/msg/OccupancyGrid.html) | The map with the information about the presence of obstacles and blind spot | -| Traffic Signal | `/perception/traffic_light_recognition/traffic_signals` | [autoware_perception_msgs::msg::TrafficLightGroupArray](https://github.com/autowarefoundation/autoware_msgs/blob/main/autoware_perception_msgs/msg/TrafficLightGroupArray.msg) | The traffic signal information such as a color (green, yellow, read) and an arrow (right, left, straight) | +| Name | Topic | Type | Description | +| ------------------ | ------------------------------------------------------- | ------------------------------------------------------------------------------------------------------------------------------------------------------------------------------ | --------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------- | +| Dynamic Objects | `/perception/object_recognition/objects` | [autoware_perception_msgs/msg/PredictedObjects](https://github.com/autowarefoundation/autoware_msgs/blob/main/autoware_perception_msgs/msg/PredictedObjects.msg) | Set of dynamic objects with information such as a object class and a shape of the objects. These objects did not exist when the map was generated and are not contained within the map. | +| Obstacles | `/perception/obstacle_segmentation/pointcloud` | [sensor_msgs/PointCloud2](https://github.com/ros2/common_interfaces/blob/humble/sensor_msgs/msg/PointCloud2.msg) | Obstacles, including both dynamic objects and static obstacles that requires the ego vehicle either steer clear of them or come to a stop in front of the obstacles. | +| Occupancy Grid Map | `/perception/occupancy_grid_map/map` | [nav_msgs/msg/OccupancyGrid](https://docs.ros.org/en/latest/api/nav_msgs/html/msg/OccupancyGrid.html) | The map with the information about the presence of obstacles and blind spot | +| Traffic Signal | `/perception/traffic_light_recognition/traffic_signals` | [autoware_perception_msgs::msg::TrafficLightGroupArray](https://github.com/autowarefoundation/autoware_msgs/blob/main/autoware_perception_msgs/msg/TrafficLightGroupArray.msg) | The traffic signal information such as a color (green, yellow, read) and an arrow (right, left, straight) | diff --git a/docs/design/autoware-interfaces/components/planning.md b/docs/design/autoware-interfaces/components/planning.md index 7676e0cb1ea..ebb02453c1e 100644 --- a/docs/design/autoware-interfaces/components/planning.md +++ b/docs/design/autoware-interfaces/components/planning.md @@ -10,8 +10,8 @@ This page provides specific specifications about the Interface of the Planning C ### From Map Component -| Name | Topic | Type | Description | -| ---------- | ----------------- | ---------------------------------------------------------------------------------------------------------------------------------------------------- | ------------------------------------------------------ | +| Name | Topic | Type | Description | +| ---------- | ----------------- | -------------------------------------------------------------------------------------------------------------------------------------------- | ------------------------------------------------------ | | Vector Map | `/map/vector_map` | [autoware_map_msgs/msg/LaneletMapBin](https://github.com/autowarefoundation/autoware_msgs/blob/main/autoware_map_msgs/msg/LaneletMapBin.msg) | Map of the environment where the planning takes place. | ### From Localization Component @@ -25,11 +25,11 @@ This page provides specific specifications about the Interface of the Planning C ### From Perception Component -| Name | Topic | Type | Description | -| ------------------ | ------------------------------------------------------- | ---------------------------------------------------------------------------------------------------------------------------------------------------------------------------- | ------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------- | -| Objects | `/perception/object_recognition/objects` | [autoware_perception_msgs/msg/PredictedObjects](https://github.com/autowarefoundation/autoware_msgs/blob/main/autoware_perception_msgs/msg/PredictedObjects.msg) | Set of perceived objects around ego that need to be avoided or followed when planning a trajectory. This contains semantics information such as a object class (e.g. vehicle, pedestrian, etc) or a shape of the objects. | -| Obstacles | `/perception/obstacle_segmentation/pointcloud` | [sensor_msgs/msg/PointCloud2](https://docs.ros.org/en/latest/api/sensor_msgs/html/msg/PointCloud2.html) | Set of perceived obstacles around ego that need to be avoided or followed when planning a trajectory. This only contains a primitive information of the obstacle. No shape nor velocity information. | -| Occupancy Grid Map | `/perception/occupancy_grid_map/map` | [nav_msgs/msg/OccupancyGrid](https://docs.ros.org/en/latest/api/nav_msgs/html/msg/OccupancyGrid.html) | Contains the presence of obstacles and blind spot information (represented as UNKNOWN). | +| Name | Topic | Type | Description | +| ------------------ | ------------------------------------------------------- | ------------------------------------------------------------------------------------------------------------------------------------------------------------------------------ | ------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------- | +| Objects | `/perception/object_recognition/objects` | [autoware_perception_msgs/msg/PredictedObjects](https://github.com/autowarefoundation/autoware_msgs/blob/main/autoware_perception_msgs/msg/PredictedObjects.msg) | Set of perceived objects around ego that need to be avoided or followed when planning a trajectory. This contains semantics information such as a object class (e.g. vehicle, pedestrian, etc) or a shape of the objects. | +| Obstacles | `/perception/obstacle_segmentation/pointcloud` | [sensor_msgs/msg/PointCloud2](https://docs.ros.org/en/latest/api/sensor_msgs/html/msg/PointCloud2.html) | Set of perceived obstacles around ego that need to be avoided or followed when planning a trajectory. This only contains a primitive information of the obstacle. No shape nor velocity information. | +| Occupancy Grid Map | `/perception/occupancy_grid_map/map` | [nav_msgs/msg/OccupancyGrid](https://docs.ros.org/en/latest/api/nav_msgs/html/msg/OccupancyGrid.html) | Contains the presence of obstacles and blind spot information (represented as UNKNOWN). | | Traffic Signal | `/perception/traffic_light_recognition/traffic_signals` | [autoware_perception_msgs::msg::TrafficLightGroupArray](https://github.com/autowarefoundation/autoware_msgs/blob/main/autoware_perception_msgs/msg/TrafficLightGroupArray.msg) | Contains the traffic signal information such as a color (green, yellow, read) and an arrow (right, left, straight). | **TODO**: The type of the `Obstacles` information should not depend on the specific sensor message type (now `PointCloud`). It needs to be fixed. @@ -54,8 +54,8 @@ This page provides specific specifications about the Interface of the Planning C ### To Control -| Name | Topic | Type | Description | -| -------------- | ------------------------------- | ---------------------------------------------------------------------------------------------------------------------------------------------------------------------------- | ------------------------------------------------------------------------------------------ | +| Name | Topic | Type | Description | +| -------------- | ------------------------------- | -------------------------------------------------------------------------------------------------------------------------------------------------------------------- | ------------------------------------------------------------------------------------------ | | Trajectory | `/planning/trajectory` | [autoware_planning_msgs/msg/Trajectory](https://github.com/autowarefoundation/autoware_msgs/blob/main/autoware_planning_msgs/msg/Trajectory.msg) | A sequence of space and velocity and acceleration points to be followed by the controller. | | Turn Indicator | `/planning/turn_indicators_cmd` | [autoware_vehicle_msgs/msg/TurnIndicatorsCommand](https://github.com/autowarefoundation/autoware_msgs/blob/main/autoware_vehicle_msgs/msg/TurnIndicatorsCommand.msg) | Turn indicator signal to be followed by the vehicle. | | Hazard Light | `/planning/hazard_lights_cmd` | [autoware_vehicle_msgs/msg/HazardLightsCommand](https://github.com/autowarefoundation/autoware_msgs/blob/main/autoware_vehicle_msgs/msg/HazardLightsCommand.msg) | Hazard light signal to be followed by the vehicle. | @@ -70,7 +70,7 @@ This page provides specific specifications about the Interface of the Planning C | Name | Topic | Type | Description | | --------------- | ------------------------------ | --------------------------------------------------------------------------------------------------------------------------------------------------------------------------------- | ------------------------------------------------------------------------------------------------------------------- | -| Path Candidate | `/planning/path_candidate/*` | [autoware_planning_msgs/msg/Path](https://github.com/autowarefoundation/autoware_msgs/blob/main/autoware_planning_msgs/msg/Path.msg) | The path Autoware is about to take. Users can interrupt the operation based on the path candidate information. | +| Path Candidate | `/planning/path_candidate/*` | [autoware_planning_msgs/msg/Path](https://github.com/autowarefoundation/autoware_msgs/blob/main/autoware_planning_msgs/msg/Path.msg) | The path Autoware is about to take. Users can interrupt the operation based on the path candidate information. | | Steering Factor | `/planning/steering_factor/*` | [autoware_adapi_v1_msgs/msg/SteeringFactorArray](https://github.com/autowarefoundation/autoware_adapi_msgs/blob/main/autoware_adapi_v1_msgs/planning/msg/SteeringFactorArray.msg) | Information about the steering maneuvers performed by Autoware (e.g., steering to the right for a right turn, etc.) | | Velocity Factor | `/planning/velocity_factors/*` | [autoware_adapi_v1_msgs/msg/VelocityFactorArray](https://github.com/autowarefoundation/autoware_adapi_msgs/blob/main/autoware_adapi_v1_msgs/planning/msg/VelocityFactorArray.msg) | Information about the velocity maneuvers performed by Autoware (e.g., stop for an obstacle, etc.) | @@ -88,12 +88,12 @@ This section explains the communication between the different planning modules s ### From Behavior Planning to Motion Planning -| Name | Topic | Type | Description | -| ---- | ----------------------------------------------------------------- | -------------------------------------------------------------------------------------------------------------------------------------------- | ----------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------- | +| Name | Topic | Type | Description | +| ---- | ----------------------------------------------------------------- | ------------------------------------------------------------------------------------------------------------------------------------ | ----------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------- | | Path | `/planning/scenario_planning/lane_driving/behavior_planning/path` | [autoware_planning_msgs/msg/Path](https://github.com/autowarefoundation/autoware_msgs/blob/main/autoware_planning_msgs/msg/Path.msg) | A sequence of approximate vehicle positions for driving, along with information on the maximum speed and the drivable areas. Modules receiving this message are expected to make changes to the path within the constraints of the drivable areas and the maximum speed, generating the desired final trajectory. | ### From Scenario Planning to Validation -| Name | Topic | Type | Description | -| ---------- | ---------------------------------------- | -------------------------------------------------------------------------------------------------------------------------------------------------------- | ----------------------------------------------------------------------------------------------------------------------------------------------------- | +| Name | Topic | Type | Description | +| ---------- | ---------------------------------------- | ------------------------------------------------------------------------------------------------------------------------------------------------ | ----------------------------------------------------------------------------------------------------------------------------------------------------- | | Trajectory | `/planning/scenario_planning/trajectory` | [autoware_planning_msgs/msg/Trajectory](https://github.com/autowarefoundation/autoware_msgs/blob/main/autoware_planning_msgs/msg/Trajectory.msg) | A sequence of precise vehicle positions, speeds, and accelerations required for driving. It is expected that the vehicle will follow this trajectory. | diff --git a/docs/design/autoware-interfaces/components/vehicle-interface.md b/docs/design/autoware-interfaces/components/vehicle-interface.md index 6720dcef39a..a5e88df435f 100644 --- a/docs/design/autoware-interfaces/components/vehicle-interface.md +++ b/docs/design/autoware-interfaces/components/vehicle-interface.md @@ -30,21 +30,21 @@ which converts the target speed and steering angle to acceleration, steering, an ## Inputs from Autoware -| Name | Topic | Type | Description | -| ---------------------- | -------------------------------------- | -------------------------------------------------------------------------------------------------------------------------------------------------------------------------------- | -------------------------------------------------------------- | -| Control command | `/control/command/control_cmd` | [autoware_control_msgs/msg/Control](https://github.com/autowarefoundation/autoware_msgs/blob/main/autoware_control_msgs/msg/Control.msg) | Target controls of the vehicle (steering angle, velocity, ...) | -| Control mode command | `/control/control_mode_request` | [autoware_vehicle_msgs/srv/ControlModeCommand](https://github.com/autowarefoundation/autoware_msgs/blob/main/autoware_vehicle_msgs/srv/ControlModeCommand.srv) | Request to switch between manual and autonomous driving | -| Gear command | `/control/command/gear_cmd` | [autoware_vehicle_msgs/msg/GearCommand](https://github.com/autowarefoundation/autoware_msgs/blob/main/autoware_vehicle_msgs/msg/GearCommand.msg) | Target gear of the vehicle | -| Hazard lights command | `/control/command/hazard_lights_cmd` | [autoware_vehicle_msgs/msg/HazardLightsCommand](https://github.com/autowarefoundation/autoware_msgs/blob/main/autoware_vehicle_msgs/msg/HazardLightsCommand.msg) | Target values of the hazard lights | -| Turn indicator command | `/control/command/turn_indicators_cmd` | [autoware_vehicle_msgs/msg/TurnIndicatorsCommand](https://github.com/autowarefoundation/autoware_msgs/blob/main/autoware_vehicle_msgs/msg/TurnIndicatorsCommand.msg) | Target values of the turn signals | +| Name | Topic | Type | Description | +| ---------------------- | -------------------------------------- | -------------------------------------------------------------------------------------------------------------------------------------------------------------------- | -------------------------------------------------------------- | +| Control command | `/control/command/control_cmd` | [autoware_control_msgs/msg/Control](https://github.com/autowarefoundation/autoware_msgs/blob/main/autoware_control_msgs/msg/Control.msg) | Target controls of the vehicle (steering angle, velocity, ...) | +| Control mode command | `/control/control_mode_request` | [autoware_vehicle_msgs/srv/ControlModeCommand](https://github.com/autowarefoundation/autoware_msgs/blob/main/autoware_vehicle_msgs/srv/ControlModeCommand.srv) | Request to switch between manual and autonomous driving | +| Gear command | `/control/command/gear_cmd` | [autoware_vehicle_msgs/msg/GearCommand](https://github.com/autowarefoundation/autoware_msgs/blob/main/autoware_vehicle_msgs/msg/GearCommand.msg) | Target gear of the vehicle | +| Hazard lights command | `/control/command/hazard_lights_cmd` | [autoware_vehicle_msgs/msg/HazardLightsCommand](https://github.com/autowarefoundation/autoware_msgs/blob/main/autoware_vehicle_msgs/msg/HazardLightsCommand.msg) | Target values of the hazard lights | +| Turn indicator command | `/control/command/turn_indicators_cmd` | [autoware_vehicle_msgs/msg/TurnIndicatorsCommand](https://github.com/autowarefoundation/autoware_msgs/blob/main/autoware_vehicle_msgs/msg/TurnIndicatorsCommand.msg) | Target values of the turn signals | ## Outputs to Autoware -| Name | Topic | Type | Optional ? | Description | -| ---------------------- | ---------------------------------------- | --------------------------------------------------------------------------------------------------------------------------------------------------------------------------- | ------------------------------------ | ----------------------------------------------------------------------- | -| Actuation status | `/vehicle/status/actuation_status` | [tier4_vehicle_msgs/msg/ActuationStatusStamped](https://github.com/tier4/tier4_autoware_msgs/blob/tier4/universe/tier4_vehicle_msgs/msg/ActuationStatusStamped.msg) | Yes (vehicle with mechanical inputs) | Current acceleration, brake, and steer values reported by the vehicle | +| Name | Topic | Type | Optional ? | Description | +| ---------------------- | ---------------------------------------- | ------------------------------------------------------------------------------------------------------------------------------------------------------------------- | ------------------------------------ | ----------------------------------------------------------------------- | +| Actuation status | `/vehicle/status/actuation_status` | [tier4_vehicle_msgs/msg/ActuationStatusStamped](https://github.com/tier4/tier4_autoware_msgs/blob/tier4/universe/tier4_vehicle_msgs/msg/ActuationStatusStamped.msg) | Yes (vehicle with mechanical inputs) | Current acceleration, brake, and steer values reported by the vehicle | | Control mode | `/vehicle/status/control_mode` | [autoware_vehicle_msgs/msg/ControlModeReport](https://github.com/autowarefoundation/autoware_msgs/blob/main/autoware_vehicle_msgs/msg/ControlModeReport.msg) | | Current control mode (manual, autonomous, ...) | -| Door status | `/vehicle/status/door_status` | [tier4_api_msgs/msg/DoorStatus](https://github.com/tier4/tier4_autoware_msgs/blob/tier4/universe/tier4_api_msgs/msg/DoorStatus.msg) | Yes | Current door status | +| Door status | `/vehicle/status/door_status` | [tier4_api_msgs/msg/DoorStatus](https://github.com/tier4/tier4_autoware_msgs/blob/tier4/universe/tier4_api_msgs/msg/DoorStatus.msg) | Yes | Current door status | | Gear report | `/vehicle/status/gear_status` | [autoware_vehicle_msgs/msg/GearReport](https://github.com/autowarefoundation/autoware_msgs/blob/main/autoware_vehicle_msgs/msg/GearReport.msg) | | Current gear of the vehicle | | Hazard light status | `/vehicle/status/hazard_lights_status` | [autoware_vehicle_msgs/msg/HazardLightsReport](https://github.com/autowarefoundation/autoware_msgs/blob/main/autoware_vehicle_msgs/msg/HazardLightsReport.msg) | | Current hazard lights status | | Steering status | `/vehicle/status/steering_status` | [autoware_vehicle_msgs/msg/SteeringReport](https://github.com/autowarefoundation/autoware_msgs/blob/main/autoware_vehicle_msgs/msg/SteeringReport.msg) | | Current steering angle of the steering tire |