├── .github ├── CODEOWNERS-manual ├── pull_request_template.md ├── workflows │ ├── semantic-pull-request.yaml │ ├── pre-commit-optional.yaml │ ├── spell-check-differential.yaml │ ├── release-new-version-when-merged.yaml │ ├── spell-check-daily.yaml │ ├── pre-commit.yaml │ ├── sync-files.yaml │ ├── update-codeowners-from-packages.yaml │ ├── comment-on-pr.yaml │ ├── bump-new-version.yaml │ ├── github-release.yaml │ ├── build-and-test.yaml │ └── build-and-test-differential.yaml ├── dependabot.yaml ├── stale.yml ├── ISSUE_TEMPLATE │ ├── config.yml │ ├── task.yaml │ └── bug.yaml ├── CODEOWNERS └── sync-files.yaml ├── autoware_planning_msgs ├── msg │ ├── LaneletPrimitive.msg │ ├── Trajectory.msg │ ├── PoseWithUuidStamped.msg │ ├── LaneletSegment.msg │ ├── Path.msg │ ├── PathPoint.msg │ ├── LaneletRoute.msg │ ├── RouteState.msg │ └── TrajectoryPoint.msg ├── srv │ ├── ClearRoute.srv │ ├── SetWaypointRoute.srv │ ├── SetLaneletRoute.srv │ └── SetPreferredPrimitive.srv ├── README.md ├── CMakeLists.txt ├── package.xml └── CHANGELOG.rst ├── autoware_vehicle_msgs ├── msg │ ├── Engage.msg │ ├── HazardLightsReport.msg │ ├── HazardLightsCommand.msg │ ├── SteeringReport.msg │ ├── TurnIndicatorsReport.msg │ ├── TurnIndicatorsCommand.msg │ ├── ControlModeReport.msg │ ├── VelocityReport.msg │ ├── GearReport.msg │ └── GearCommand.msg ├── srv │ └── ControlModeCommand.srv ├── CMakeLists.txt ├── package.xml └── CHANGELOG.rst ├── autoware_sensing_msgs ├── msg │ ├── RadarObjects.msg │ ├── RadarFieldInfo.msg │ ├── RadarInfo.msg │ ├── GnssInsOrientationStamped.msg │ ├── GnssInsOrientation.msg │ ├── RadarClassification.msg │ ├── SourcePointCloudInfo.msg │ ├── RadarObject.msg │ └── ConcatenatedPointCloudInfo.msg ├── CMakeLists.txt ├── package.xml ├── CHANGELOG.rst └── README.md ├── autoware_v2x_msgs ├── msg │ ├── VirtualGateStatus.msg │ ├── VirtualGateCommand.msg │ ├── VirtualGateAreaCommand.msg │ └── VirtualGateAreaStatus.msg ├── CMakeLists.txt ├── package.xml ├── CHANGELOG.rst ├── README.md └── doc │ └── virtual-gate-nodes.drawio.svg ├── autoware_perception_msgs ├── msg │ ├── TrackedObjects.msg │ ├── DetectedObjects.msg │ ├── PredictedObjects.msg │ ├── PredictedPath.msg │ ├── TrafficLightGroupArray.msg │ ├── DetectedObject.msg │ ├── Shape.msg │ ├── TrafficSignal.msg │ ├── TrafficSignalArray.msg │ ├── TrafficLightGroup.msg │ ├── PredictedObject.msg │ ├── TrackedObject.msg │ ├── PredictedObjectKinematics.msg │ ├── ObjectClassification.msg │ ├── TrafficSignalElement.msg │ ├── TrafficLightElement.msg │ ├── TrackedObjectKinematics.msg │ ├── DetectedObjectKinematics.msg │ └── PredictedTrafficLightState.msg ├── README.md ├── CMakeLists.txt ├── package.xml └── CHANGELOG.rst ├── autoware_system_msgs ├── msg │ ├── HazardStatusStamped.msg │ ├── AutowareState.msg │ └── HazardStatus.msg ├── srv │ ├── ChangeAutowareControl.srv │ └── ChangeOperationMode.srv ├── CMakeLists.txt ├── package.xml └── CHANGELOG.rst ├── CONTRIBUTING.md ├── autoware_map_msgs ├── msg │ ├── LaneletMapMetaData.msg │ ├── PointCloudMapMetaData.msg │ ├── PointCloudMapCellMetaDataWithID.msg │ ├── PointCloudMapCellMetaData.msg │ ├── LaneletMapCellMetaData.msg │ ├── PointCloudMapCellWithID.msg │ ├── AreaInfo.msg │ ├── LaneletMapBin.msg │ └── MapProjectorInfo.msg ├── media │ ├── partial_area_loading.png │ └── differential_area_loading.gif ├── srv │ ├── GetSelectedPointCloudMap.srv │ ├── GetSelectedLanelet2Map.srv │ ├── GetPartialPointCloudMap.srv │ └── GetDifferentialPointCloudMap.srv ├── CMakeLists.txt ├── package.xml ├── README.md └── CHANGELOG.rst ├── autoware_msgs ├── CMakeLists.txt ├── CHANGELOG.rst └── package.xml ├── NOTICE ├── README.md ├── .prettierignore ├── autoware_common_msgs ├── CMakeLists.txt ├── msg │ └── ResponseStatus.msg ├── package.xml └── CHANGELOG.rst ├── .markdown-link-check.json ├── autoware_control_msgs ├── msg │ ├── Control.msg │ ├── ControlHorizon.msg │ ├── Longitudinal.msg │ └── Lateral.msg ├── CMakeLists.txt ├── package.xml ├── CHANGELOG.rst └── README.md ├── .gitignore ├── .markdownlint.yaml ├── autoware_localization_msgs ├── CMakeLists.txt ├── srv │ └── InitializeLocalization.srv ├── msg │ └── KinematicState.msg ├── package.xml └── CHANGELOG.rst ├── .prettierrc.yaml ├── .pre-commit-config-optional.yaml ├── .yamllint.yaml ├── DISCLAIMER.md ├── .pre-commit-config.yaml ├── CODE_OF_CONDUCT.md └── LICENSE /.github/CODEOWNERS-manual: -------------------------------------------------------------------------------- 1 | -------------------------------------------------------------------------------- /autoware_planning_msgs/msg/LaneletPrimitive.msg: -------------------------------------------------------------------------------- 1 | int64 id 2 | string primitive_type 3 | -------------------------------------------------------------------------------- /autoware_vehicle_msgs/msg/Engage.msg: -------------------------------------------------------------------------------- 1 | builtin_interfaces/Time stamp 2 | bool engage 3 | -------------------------------------------------------------------------------- /autoware_planning_msgs/srv/ClearRoute.srv: -------------------------------------------------------------------------------- 1 | --- 2 | autoware_common_msgs/ResponseStatus status 3 | -------------------------------------------------------------------------------- /autoware_sensing_msgs/msg/RadarObjects.msg: -------------------------------------------------------------------------------- 1 | std_msgs/Header header 2 | RadarObject[] objects 3 | -------------------------------------------------------------------------------- /autoware_v2x_msgs/msg/VirtualGateStatus.msg: -------------------------------------------------------------------------------- 1 | autoware_v2x_msgs/VirtualGateAreaStatus[] areas 2 | -------------------------------------------------------------------------------- /autoware_perception_msgs/msg/TrackedObjects.msg: -------------------------------------------------------------------------------- 1 | std_msgs/Header header 2 | TrackedObject[] objects 3 | -------------------------------------------------------------------------------- /autoware_perception_msgs/msg/DetectedObjects.msg: -------------------------------------------------------------------------------- 1 | std_msgs/Header header 2 | DetectedObject[] objects 3 | -------------------------------------------------------------------------------- /autoware_perception_msgs/msg/PredictedObjects.msg: -------------------------------------------------------------------------------- 1 | std_msgs/Header header 2 | PredictedObject[] objects 3 | -------------------------------------------------------------------------------- /autoware_planning_msgs/msg/Trajectory.msg: -------------------------------------------------------------------------------- 1 | std_msgs/Header header 2 | autoware_planning_msgs/TrajectoryPoint[] points 3 | -------------------------------------------------------------------------------- /autoware_system_msgs/msg/HazardStatusStamped.msg: -------------------------------------------------------------------------------- 1 | builtin_interfaces/Time stamp 2 | autoware_system_msgs/HazardStatus status 3 | -------------------------------------------------------------------------------- /CONTRIBUTING.md: -------------------------------------------------------------------------------- 1 | # Contributing 2 | 3 | See . 4 | -------------------------------------------------------------------------------- /autoware_map_msgs/msg/LaneletMapMetaData.msg: -------------------------------------------------------------------------------- 1 | # Header 2 | std_msgs/Header header 3 | 4 | LaneletMapCellMetaData[] metadata_list 5 | -------------------------------------------------------------------------------- /autoware_system_msgs/srv/ChangeAutowareControl.srv: -------------------------------------------------------------------------------- 1 | bool autoware_control 2 | --- 3 | autoware_common_msgs/ResponseStatus status 4 | -------------------------------------------------------------------------------- /autoware_v2x_msgs/msg/VirtualGateCommand.msg: -------------------------------------------------------------------------------- 1 | builtin_interfaces/Time stamp 2 | autoware_v2x_msgs/VirtualGateAreaCommand[] areas 3 | -------------------------------------------------------------------------------- /autoware_perception_msgs/msg/PredictedPath.msg: -------------------------------------------------------------------------------- 1 | geometry_msgs/Pose[] path 2 | builtin_interfaces/Duration time_step 3 | float32 confidence 4 | -------------------------------------------------------------------------------- /autoware_planning_msgs/msg/PoseWithUuidStamped.msg: -------------------------------------------------------------------------------- 1 | std_msgs/Header header 2 | geometry_msgs/Pose pose 3 | unique_identifier_msgs/UUID uuid 4 | -------------------------------------------------------------------------------- /autoware_map_msgs/msg/PointCloudMapMetaData.msg: -------------------------------------------------------------------------------- 1 | # Header 2 | std_msgs/Header header 3 | 4 | PointCloudMapCellMetaDataWithID[] metadata_list 5 | -------------------------------------------------------------------------------- /autoware_vehicle_msgs/msg/HazardLightsReport.msg: -------------------------------------------------------------------------------- 1 | uint8 DISABLE = 1 2 | uint8 ENABLE = 2 3 | 4 | builtin_interfaces/Time stamp 5 | uint8 report 6 | -------------------------------------------------------------------------------- /autoware_map_msgs/msg/PointCloudMapCellMetaDataWithID.msg: -------------------------------------------------------------------------------- 1 | # Pointcloud metadata with ID 2 | 3 | string cell_id 4 | PointCloudMapCellMetaData metadata 5 | -------------------------------------------------------------------------------- /autoware_perception_msgs/msg/TrafficLightGroupArray.msg: -------------------------------------------------------------------------------- 1 | builtin_interfaces/Time stamp 2 | autoware_perception_msgs/TrafficLightGroup[] traffic_light_groups 3 | -------------------------------------------------------------------------------- /autoware_map_msgs/media/partial_area_loading.png: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/autowarefoundation/autoware_msgs/HEAD/autoware_map_msgs/media/partial_area_loading.png -------------------------------------------------------------------------------- /autoware_map_msgs/msg/PointCloudMapCellMetaData.msg: -------------------------------------------------------------------------------- 1 | # Metadata of pointcloud map cell 2 | 3 | float32 min_x 4 | float32 min_y 5 | float32 max_x 6 | float32 max_y 7 | -------------------------------------------------------------------------------- /autoware_msgs/CMakeLists.txt: -------------------------------------------------------------------------------- 1 | cmake_minimum_required(VERSION 3.14) 2 | project(autoware_msgs) 3 | 4 | find_package(ament_cmake REQUIRED) 5 | 6 | ament_package() 7 | -------------------------------------------------------------------------------- /autoware_planning_msgs/msg/LaneletSegment.msg: -------------------------------------------------------------------------------- 1 | autoware_planning_msgs/LaneletPrimitive preferred_primitive 2 | autoware_planning_msgs/LaneletPrimitive[] primitives 3 | -------------------------------------------------------------------------------- /autoware_map_msgs/media/differential_area_loading.gif: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/autowarefoundation/autoware_msgs/HEAD/autoware_map_msgs/media/differential_area_loading.gif -------------------------------------------------------------------------------- /autoware_vehicle_msgs/msg/HazardLightsCommand.msg: -------------------------------------------------------------------------------- 1 | uint8 NO_COMMAND = 0 2 | uint8 DISABLE = 1 3 | uint8 ENABLE = 2 4 | 5 | builtin_interfaces/Time stamp 6 | uint8 command 7 | -------------------------------------------------------------------------------- /autoware_vehicle_msgs/msg/SteeringReport.msg: -------------------------------------------------------------------------------- 1 | builtin_interfaces/Time stamp 2 | # Steering tire angle [rad]. Positive: left, Negative: right 3 | float32 steering_tire_angle 4 | -------------------------------------------------------------------------------- /autoware_map_msgs/msg/LaneletMapCellMetaData.msg: -------------------------------------------------------------------------------- 1 | # Metadata of lanelet map cell 2 | 3 | string cell_id 4 | float64 min_x 5 | float64 max_x 6 | float64 min_y 7 | float64 max_y 8 | -------------------------------------------------------------------------------- /autoware_map_msgs/msg/PointCloudMapCellWithID.msg: -------------------------------------------------------------------------------- 1 | # Pointcloud data with ID 2 | 3 | string cell_id 4 | sensor_msgs/PointCloud2 pointcloud 5 | PointCloudMapCellMetaData metadata 6 | -------------------------------------------------------------------------------- /autoware_perception_msgs/msg/DetectedObject.msg: -------------------------------------------------------------------------------- 1 | float32 existence_probability 2 | ObjectClassification[] classification 3 | DetectedObjectKinematics kinematics 4 | Shape shape 5 | -------------------------------------------------------------------------------- /autoware_planning_msgs/msg/Path.msg: -------------------------------------------------------------------------------- 1 | std_msgs/Header header 2 | autoware_planning_msgs/PathPoint[] points 3 | geometry_msgs/Point[] left_bound 4 | geometry_msgs/Point[] right_bound 5 | -------------------------------------------------------------------------------- /autoware_vehicle_msgs/msg/TurnIndicatorsReport.msg: -------------------------------------------------------------------------------- 1 | uint8 DISABLE = 1 2 | uint8 ENABLE_LEFT = 2 3 | uint8 ENABLE_RIGHT = 3 4 | 5 | builtin_interfaces/Time stamp 6 | uint8 report 7 | -------------------------------------------------------------------------------- /autoware_planning_msgs/msg/PathPoint.msg: -------------------------------------------------------------------------------- 1 | geometry_msgs/Pose pose 2 | float32 longitudinal_velocity_mps 3 | float32 lateral_velocity_mps 4 | float32 heading_rate_rps 5 | bool is_final 6 | -------------------------------------------------------------------------------- /NOTICE: -------------------------------------------------------------------------------- 1 | Copyright 2022 The Autoware Foundation 2 | 3 | Some of the messages within this repository are based on autoware_auto_msgs messages that were developed in cooperation with Apex.AI, Inc. 4 | -------------------------------------------------------------------------------- /autoware_perception_msgs/msg/Shape.msg: -------------------------------------------------------------------------------- 1 | uint8 BOUNDING_BOX=0 2 | uint8 CYLINDER=1 3 | uint8 POLYGON=2 4 | 5 | uint8 type 6 | geometry_msgs/Polygon footprint 7 | geometry_msgs/Vector3 dimensions 8 | -------------------------------------------------------------------------------- /.github/pull_request_template.md: -------------------------------------------------------------------------------- 1 | ## Description 2 | 3 | ## How was this PR tested? 4 | 5 | ## Notes for reviewers 6 | 7 | None. 8 | 9 | ## Effects on system behavior 10 | 11 | None. 12 | -------------------------------------------------------------------------------- /autoware_perception_msgs/msg/TrafficSignal.msg: -------------------------------------------------------------------------------- 1 | # TODO(youtalk): Remove this after migration to TrafficLight 2 | int64 traffic_signal_id 3 | autoware_perception_msgs/TrafficSignalElement[] elements 4 | -------------------------------------------------------------------------------- /autoware_perception_msgs/msg/TrafficSignalArray.msg: -------------------------------------------------------------------------------- 1 | # TODO(youtalk): Remove this after migration to TrafficLight 2 | builtin_interfaces/Time stamp 3 | autoware_perception_msgs/TrafficSignal[] signals 4 | -------------------------------------------------------------------------------- /autoware_system_msgs/srv/ChangeOperationMode.srv: -------------------------------------------------------------------------------- 1 | uint16 STOP = 1 2 | uint16 AUTONOMOUS = 2 3 | uint16 LOCAL = 3 4 | uint16 REMOTE = 4 5 | uint16 mode 6 | --- 7 | autoware_common_msgs/ResponseStatus status 8 | -------------------------------------------------------------------------------- /autoware_vehicle_msgs/msg/TurnIndicatorsCommand.msg: -------------------------------------------------------------------------------- 1 | uint8 NO_COMMAND = 0 2 | uint8 DISABLE = 1 3 | uint8 ENABLE_LEFT = 2 4 | uint8 ENABLE_RIGHT = 3 5 | 6 | builtin_interfaces/Time stamp 7 | uint8 command 8 | -------------------------------------------------------------------------------- /autoware_perception_msgs/msg/TrafficLightGroup.msg: -------------------------------------------------------------------------------- 1 | int64 traffic_light_group_id 2 | autoware_perception_msgs/TrafficLightElement[] elements 3 | autoware_perception_msgs/PredictedTrafficLightState[] predictions 4 | -------------------------------------------------------------------------------- /README.md: -------------------------------------------------------------------------------- 1 | # autoware_msgs 2 | 3 | Before contributing, review [the message guidelines](https://autowarefoundation.github.io/autoware-documentation/main/contributing/coding-guidelines/ros-nodes/message-guidelines/). 4 | -------------------------------------------------------------------------------- /autoware_map_msgs/msg/AreaInfo.msg: -------------------------------------------------------------------------------- 1 | # Area info used as a query in map loading service 2 | # Note: this only supports cylindrical area message for now 3 | 4 | float32 center_x 5 | float32 center_y 6 | float32 radius 7 | -------------------------------------------------------------------------------- /autoware_perception_msgs/msg/PredictedObject.msg: -------------------------------------------------------------------------------- 1 | unique_identifier_msgs/UUID object_id 2 | float32 existence_probability 3 | ObjectClassification[] classification 4 | PredictedObjectKinematics kinematics 5 | Shape shape 6 | -------------------------------------------------------------------------------- /autoware_perception_msgs/msg/TrackedObject.msg: -------------------------------------------------------------------------------- 1 | unique_identifier_msgs/UUID object_id 2 | float32 existence_probability 3 | ObjectClassification[] classification 4 | TrackedObjectKinematics kinematics 5 | Shape shape 6 | -------------------------------------------------------------------------------- /autoware_sensing_msgs/msg/RadarFieldInfo.msg: -------------------------------------------------------------------------------- 1 | std_msgs/String field_name 2 | bool min_value_available 3 | bool max_value_available 4 | bool resolution_available 5 | 6 | float32 min_value 7 | float32 max_value 8 | float32 resolution 9 | -------------------------------------------------------------------------------- /autoware_sensing_msgs/msg/RadarInfo.msg: -------------------------------------------------------------------------------- 1 | std_msgs/Header header 2 | RadarFieldInfo[] object_fields_info 3 | RadarFieldInfo[] detection_fields_info 4 | 5 | uint32[] available_classes 6 | bool absolute_dynamics # absolute or relative dynamics 7 | -------------------------------------------------------------------------------- /.prettierignore: -------------------------------------------------------------------------------- 1 | # This file is automatically synced from: 2 | # https://github.com/autowarefoundation/sync-file-templates 3 | # To make changes, update the source repository and follow the guidelines in its README. 4 | 5 | *.param.yaml 6 | *.rviz 7 | -------------------------------------------------------------------------------- /autoware_planning_msgs/msg/LaneletRoute.msg: -------------------------------------------------------------------------------- 1 | std_msgs/Header header 2 | geometry_msgs/Pose start_pose 3 | geometry_msgs/Pose goal_pose 4 | autoware_planning_msgs/LaneletSegment[] segments 5 | unique_identifier_msgs/UUID uuid 6 | bool allow_modification 7 | -------------------------------------------------------------------------------- /autoware_map_msgs/srv/GetSelectedPointCloudMap.srv: -------------------------------------------------------------------------------- 1 | # ID query for map loading 2 | string[] cell_ids 3 | 4 | --- 5 | # Header 6 | std_msgs/Header header 7 | 8 | # Newly loaded PCD maps with ID 9 | PointCloudMapCellWithID[] new_pointcloud_with_ids 10 | -------------------------------------------------------------------------------- /autoware_planning_msgs/srv/SetWaypointRoute.srv: -------------------------------------------------------------------------------- 1 | std_msgs/Header header 2 | geometry_msgs/Pose goal_pose 3 | geometry_msgs/Pose[] waypoints 4 | unique_identifier_msgs/UUID uuid 5 | bool allow_modification 6 | --- 7 | autoware_common_msgs/ResponseStatus status 8 | -------------------------------------------------------------------------------- /autoware_map_msgs/srv/GetSelectedLanelet2Map.srv: -------------------------------------------------------------------------------- 1 | # Osm file ids which are selected to be loaded 2 | string[] cell_ids 3 | 4 | --- 5 | # Header 6 | std_msgs/Header header 7 | 8 | # Newly loaded Lanelet map 9 | autoware_map_msgs/LaneletMapBin lanelet2_cells 10 | -------------------------------------------------------------------------------- /autoware_planning_msgs/README.md: -------------------------------------------------------------------------------- 1 | # autoware_planning_msgs 2 | 3 | ## PoseWithUuidStamped.msg 4 | 5 | The message contains a pose data attached with an uuid and header. 6 | Use case example is [goal modification](https://github.com/orgs/autowarefoundation/discussions/2983) 7 | -------------------------------------------------------------------------------- /autoware_planning_msgs/srv/SetLaneletRoute.srv: -------------------------------------------------------------------------------- 1 | std_msgs/Header header 2 | geometry_msgs/Pose goal_pose 3 | autoware_planning_msgs/LaneletSegment[] segments 4 | unique_identifier_msgs/UUID uuid 5 | bool allow_modification 6 | --- 7 | autoware_common_msgs/ResponseStatus status 8 | -------------------------------------------------------------------------------- /autoware_system_msgs/msg/AutowareState.msg: -------------------------------------------------------------------------------- 1 | uint8 INITIALIZING = 1 2 | uint8 WAITING_FOR_ROUTE = 2 3 | uint8 PLANNING = 3 4 | uint8 WAITING_FOR_ENGAGE = 4 5 | uint8 DRIVING = 5 6 | uint8 ARRIVED_GOAL = 6 7 | uint8 FINALIZING = 7 8 | builtin_interfaces/Time stamp 9 | uint8 state 10 | -------------------------------------------------------------------------------- /autoware_vehicle_msgs/srv/ControlModeCommand.srv: -------------------------------------------------------------------------------- 1 | uint8 NO_COMMAND = 0 2 | uint8 AUTONOMOUS = 1 3 | uint8 AUTONOMOUS_STEER_ONLY = 2 4 | uint8 AUTONOMOUS_VELOCITY_ONLY = 3 5 | uint8 MANUAL = 4 6 | 7 | builtin_interfaces/Time stamp 8 | uint8 mode 9 | 10 | --- 11 | 12 | bool success 13 | -------------------------------------------------------------------------------- /autoware_perception_msgs/msg/PredictedObjectKinematics.msg: -------------------------------------------------------------------------------- 1 | geometry_msgs/PoseWithCovariance initial_pose_with_covariance 2 | geometry_msgs/TwistWithCovariance initial_twist_with_covariance 3 | geometry_msgs/AccelWithCovariance initial_acceleration_with_covariance 4 | PredictedPath[] predicted_paths 5 | -------------------------------------------------------------------------------- /autoware_vehicle_msgs/msg/ControlModeReport.msg: -------------------------------------------------------------------------------- 1 | uint8 NO_COMMAND = 0 2 | uint8 AUTONOMOUS = 1 3 | uint8 AUTONOMOUS_STEER_ONLY = 2 4 | uint8 AUTONOMOUS_VELOCITY_ONLY = 3 5 | uint8 MANUAL = 4 6 | uint8 DISENGAGED = 5 7 | uint8 NOT_READY = 6 8 | 9 | builtin_interfaces/Time stamp 10 | uint8 mode 11 | -------------------------------------------------------------------------------- /autoware_planning_msgs/msg/RouteState.msg: -------------------------------------------------------------------------------- 1 | uint8 UNKNOWN = 0 2 | uint8 INITIALIZING = 1 3 | uint8 UNSET = 2 4 | uint8 ROUTING = 3 5 | uint8 SET = 4 6 | uint8 REROUTING = 5 7 | uint8 ARRIVED = 6 8 | uint8 ABORTED = 7 9 | uint8 INTERRUPTED = 8 10 | 11 | builtin_interfaces/Time stamp 12 | uint8 state 13 | -------------------------------------------------------------------------------- /autoware_map_msgs/srv/GetPartialPointCloudMap.srv: -------------------------------------------------------------------------------- 1 | # Area query for map loading 2 | # (PCD grids that overlaps with the area is going to be loaded) 3 | AreaInfo area 4 | 5 | --- 6 | # Header 7 | std_msgs/Header header 8 | 9 | # Newly loaded PCD maps with ID 10 | PointCloudMapCellWithID[] new_pointcloud_with_ids 11 | -------------------------------------------------------------------------------- /autoware_common_msgs/CMakeLists.txt: -------------------------------------------------------------------------------- 1 | cmake_minimum_required(VERSION 3.14) 2 | project(autoware_common_msgs) 3 | 4 | find_package(ament_cmake_auto REQUIRED) 5 | ament_auto_find_build_dependencies() 6 | 7 | rosidl_generate_interfaces(${PROJECT_NAME} 8 | "msg/ResponseStatus.msg" 9 | ADD_LINTER_TESTS 10 | ) 11 | 12 | ament_auto_package() 13 | -------------------------------------------------------------------------------- /autoware_vehicle_msgs/msg/VelocityReport.msg: -------------------------------------------------------------------------------- 1 | std_msgs/Header header 2 | # Longitudinal velocity [m/s]. Positive: forward, Negative: backward 3 | float32 longitudinal_velocity 4 | # Lateral velocity [m/s]. Positive: left, Negative: right 5 | float32 lateral_velocity 6 | # Heading rate (yaw rate) [rad/s]. Positive: counter-clockwise 7 | float32 heading_rate 8 | -------------------------------------------------------------------------------- /.markdown-link-check.json: -------------------------------------------------------------------------------- 1 | { 2 | "aliveStatusCodes": [200, 206, 403], 3 | "ignorePatterns": [ 4 | { 5 | "pattern": "^http://localhost" 6 | }, 7 | { 8 | "pattern": "^http://127\\.0\\.0\\.1" 9 | }, 10 | { 11 | "pattern": "^https://github.com/.*/discussions/new" 12 | } 13 | ], 14 | "retryOn429": true, 15 | "retryCount": 10 16 | } 17 | -------------------------------------------------------------------------------- /autoware_common_msgs/msg/ResponseStatus.msg: -------------------------------------------------------------------------------- 1 | # error code 2 | uint16 UNKNOWN = 50000 3 | uint16 SERVICE_UNREADY = 50001 4 | uint16 SERVICE_TIMEOUT = 50002 5 | uint16 TRANSFORM_ERROR = 50003 6 | uint16 PARAMETER_ERROR = 50004 7 | 8 | # warning code 9 | uint16 DEPRECATED = 60000 10 | uint16 NO_EFFECT = 60001 11 | 12 | # variables 13 | bool success 14 | uint16 code 15 | string message 16 | -------------------------------------------------------------------------------- /autoware_control_msgs/msg/Control.msg: -------------------------------------------------------------------------------- 1 | # Control message with lateral and longitudinal components 2 | 3 | # Time this message was created 4 | builtin_interfaces/Time stamp 5 | 6 | # Time this configuration state is expected to be achieved in (optional) 7 | builtin_interfaces/Time control_time 8 | 9 | # Lateral control command 10 | Lateral lateral 11 | 12 | # Longitudinal control command 13 | Longitudinal longitudinal 14 | -------------------------------------------------------------------------------- /.gitignore: -------------------------------------------------------------------------------- 1 | # Prerequisites 2 | *.d 3 | 4 | # Compiled Object files 5 | *.slo 6 | *.lo 7 | *.o 8 | *.obj 9 | 10 | # Precompiled Headers 11 | *.gch 12 | *.pch 13 | 14 | # Compiled Dynamic libraries 15 | *.so 16 | *.dylib 17 | *.dll 18 | 19 | # Fortran module files 20 | *.mod 21 | *.smod 22 | 23 | # Compiled Static libraries 24 | *.lai 25 | *.la 26 | *.a 27 | *.lib 28 | 29 | # Executables 30 | *.exe 31 | *.out 32 | *.app 33 | -------------------------------------------------------------------------------- /autoware_sensing_msgs/msg/GnssInsOrientationStamped.msg: -------------------------------------------------------------------------------- 1 | # GNSS(Global Navigation Satellite System) INS(Inertial Navigation System) orientation message 2 | # 3 | # Represents a 3D orientation in a global coordinate system with coordinate frame and timestamp. 4 | 5 | # Timestamp this reading was received by the INS sensor 6 | # Frame is expected to be of the INS device 7 | std_msgs/Header header 8 | 9 | GnssInsOrientation orientation 10 | -------------------------------------------------------------------------------- /autoware_system_msgs/msg/HazardStatus.msg: -------------------------------------------------------------------------------- 1 | uint8 NO_FAULT = 0 2 | uint8 SAFE_FAULT = 1 3 | uint8 LATENT_FAULT = 2 4 | uint8 SINGLE_POINT_FAULT = 3 5 | uint8 level 6 | bool emergency 7 | bool emergency_holding 8 | diagnostic_msgs/DiagnosticStatus[] diag_no_fault 9 | diagnostic_msgs/DiagnosticStatus[] diag_safe_fault 10 | diagnostic_msgs/DiagnosticStatus[] diag_latent_fault 11 | diagnostic_msgs/DiagnosticStatus[] diag_single_point_fault 12 | -------------------------------------------------------------------------------- /autoware_v2x_msgs/msg/VirtualGateAreaCommand.msg: -------------------------------------------------------------------------------- 1 | # constants for command 2 | uint16 ACQUIRE = 1 3 | uint16 RELEASE = 2 4 | 5 | # variables for lock 6 | uint16 command 7 | uint16 sequence_id # Used to check correspondence with status messages. 8 | string area_id # Target area ID. 9 | string[] gate_ids # Entry and exit gate ID. 10 | 11 | # variables for scheduling 12 | builtin_interfaces/Time[<=1] expected_time_arrival 13 | -------------------------------------------------------------------------------- /autoware_planning_msgs/msg/TrajectoryPoint.msg: -------------------------------------------------------------------------------- 1 | builtin_interfaces/Duration time_from_start 2 | geometry_msgs/Pose pose 3 | float32 longitudinal_velocity_mps 4 | float32 lateral_velocity_mps 5 | # acceleration_mps2 increases/decreases based on absolute vehicle motion and does not consider vehicle direction (forward/backward) 6 | float32 acceleration_mps2 7 | float32 heading_rate_rps 8 | float32 front_wheel_angle_rad 9 | float32 rear_wheel_angle_rad 10 | -------------------------------------------------------------------------------- /autoware_map_msgs/srv/GetDifferentialPointCloudMap.srv: -------------------------------------------------------------------------------- 1 | # Area query for map loading 2 | # (PCD grids that overlaps with the area is going to be loaded) 3 | AreaInfo area 4 | 5 | # The IDs of PCD maps that the node already has 6 | string[] cached_ids 7 | 8 | --- 9 | # Header 10 | std_msgs/Header header 11 | 12 | # Newly loaded PCD maps with ID 13 | PointCloudMapCellWithID[] new_pointcloud_with_ids 14 | 15 | # Map IDs that the client side should remove 16 | string[] ids_to_remove 17 | -------------------------------------------------------------------------------- /autoware_v2x_msgs/msg/VirtualGateAreaStatus.msg: -------------------------------------------------------------------------------- 1 | # constants for status 2 | uint16 RESERVED = 1 3 | uint16 ACQUIRED = 2 4 | uint16 RELEASED = 3 5 | 6 | # variables for lock 7 | builtin_interfaces/Time stamp 8 | uint16 status 9 | uint16 sequence_id # Used to check correspondence with commands. 10 | string area_id # Target area ID. 11 | string[] gate_ids # Entry and exit gate ID. 12 | 13 | # variables for scheduling 14 | builtin_interfaces/Time[<=1] expected_time_arrival 15 | -------------------------------------------------------------------------------- /.markdownlint.yaml: -------------------------------------------------------------------------------- 1 | # This file is automatically synced from: 2 | # https://github.com/autowarefoundation/sync-file-templates 3 | # To make changes, update the source repository and follow the guidelines in its README. 4 | 5 | # See https://github.com/DavidAnson/markdownlint/blob/main/doc/Rules.md for all rules. 6 | default: true 7 | MD013: false 8 | MD024: 9 | siblings_only: true 10 | MD029: 11 | style: ordered 12 | MD033: false 13 | MD041: false 14 | MD045: false 15 | MD046: false 16 | MD049: false 17 | -------------------------------------------------------------------------------- /autoware_planning_msgs/srv/SetPreferredPrimitive.srv: -------------------------------------------------------------------------------- 1 | # Holds the list of preferred_primitives to be modified to in the current-route 2 | autoware_planning_msgs/LaneletPrimitive[] preferred_primitives 3 | # reset flag for preferred primitives in route 4 | # If set to true, this signals to mission_planner that the preferred-primitives have been reverted to those of the original path 5 | bool reset 6 | # ID of the route that will be modified. 7 | unique_identifier_msgs/UUID uuid 8 | --- 9 | autoware_common_msgs/ResponseStatus status 10 | -------------------------------------------------------------------------------- /.github/workflows/semantic-pull-request.yaml: -------------------------------------------------------------------------------- 1 | # This file is automatically synced from: 2 | # https://github.com/autowarefoundation/sync-file-templates 3 | # To make changes, update the source repository and follow the guidelines in its README. 4 | 5 | name: semantic-pull-request 6 | 7 | on: 8 | pull_request_target: 9 | types: 10 | - opened 11 | - edited 12 | - synchronize 13 | 14 | jobs: 15 | semantic-pull-request: 16 | uses: autowarefoundation/autoware-github-actions/.github/workflows/semantic-pull-request.yaml@v1 17 | -------------------------------------------------------------------------------- /autoware_sensing_msgs/msg/GnssInsOrientation.msg: -------------------------------------------------------------------------------- 1 | # GNSS(Global Navigation Satellite System) INS(Inertial Navigation System) orientation message 2 | # 3 | # Represents a 3D orientation in a global coordinate system. 4 | # 5 | # ROS uses ENU axes convention (East, North, Up) corresponds to (x, y, z). 6 | 7 | # Quaternion representation of the orientation. 8 | geometry_msgs/Quaternion orientation 9 | 10 | # Root mean square error of the rotation [rad] 11 | # (x, y, z) axes corresponding to (roll, pitch, yaw) 12 | float32 rmse_rotation_x 13 | float32 rmse_rotation_y 14 | float32 rmse_rotation_z 15 | -------------------------------------------------------------------------------- /autoware_perception_msgs/README.md: -------------------------------------------------------------------------------- 1 | # autoware_perception_msgs 2 | 3 | ## TrafficSignalElement.msg 4 | 5 | This is the element of traffic signals such as red, amber, green, and turn arrow. 6 | The elements are based on Vienna Convention on Road Signs and Signals. 7 | 8 | ## TrafficSignal.msg 9 | 10 | For each direction of an intersection, there is one state of traffic signal regardless of the number of equipment. 11 | This message represents the traffic signal as a concept and is used by components such as planning. 12 | 13 | ## TrafficSignalArray.msg 14 | 15 | This is a plural type of TrafficSignal.msg. 16 | -------------------------------------------------------------------------------- /.github/dependabot.yaml: -------------------------------------------------------------------------------- 1 | # This file is automatically synced from: 2 | # https://github.com/autowarefoundation/sync-file-templates 3 | # To make changes, update the source repository and follow the guidelines in its README. 4 | 5 | version: 2 6 | updates: 7 | - package-ecosystem: github-actions 8 | directory: / 9 | # https://docs.github.com/en/code-security/dependabot/dependabot-version-updates/configuration-options-for-the-dependabot.yml-file#scheduleinterval 10 | schedule: 11 | interval: monthly 12 | open-pull-requests-limit: 1 13 | labels: 14 | - tag:bot 15 | - type:github-actions 16 | -------------------------------------------------------------------------------- /autoware_v2x_msgs/CMakeLists.txt: -------------------------------------------------------------------------------- 1 | cmake_minimum_required(VERSION 3.14) 2 | project(autoware_v2x_msgs) 3 | 4 | find_package(ament_cmake_auto REQUIRED) 5 | ament_auto_find_build_dependencies() 6 | 7 | rosidl_generate_interfaces(${PROJECT_NAME} 8 | "msg/VirtualGateAreaCommand.msg" 9 | "msg/VirtualGateAreaStatus.msg" 10 | "msg/VirtualGateCommand.msg" 11 | "msg/VirtualGateStatus.msg" 12 | DEPENDENCIES 13 | builtin_interfaces 14 | geometry_msgs 15 | ) 16 | 17 | if(BUILD_TESTING) 18 | find_package(ament_lint_auto REQUIRED) 19 | ament_lint_auto_find_test_dependencies() 20 | endif() 21 | 22 | ament_auto_package() 23 | -------------------------------------------------------------------------------- /autoware_sensing_msgs/msg/RadarClassification.msg: -------------------------------------------------------------------------------- 1 | # Common autoware classes 2 | uint8 UNKNOWN = 0 3 | uint8 CAR = 1 4 | uint8 TRUCK = 2 5 | uint8 BUS = 3 6 | uint8 TRAILER = 4 7 | uint8 MOTORCYCLE = 5 8 | uint8 BICYCLE = 6 9 | uint8 PEDESTRIAN = 7 10 | uint8 ANIMAL = 8 11 | 12 | # Radar specific classes 13 | uint8 HAZARD = 9 # Defined as an object that can cause danger to autonomous driving 14 | uint8 OVER_DRIVABLE = 10 # Defined as an object that can be safely driven over (e.g., leaf) 15 | uint8 UNDER_DRIVABLE = 11 # Defined as an object that can be safely driven under (e.g., overpass) 16 | 17 | uint8 label 18 | float32 probability 19 | -------------------------------------------------------------------------------- /.github/stale.yml: -------------------------------------------------------------------------------- 1 | # This file is automatically synced from: 2 | # https://github.com/autowarefoundation/sync-file-templates 3 | # To make changes, update the source repository and follow the guidelines in its README. 4 | 5 | # Modified from https://github.com/probot/stale#usage 6 | 7 | # Number of days of inactivity before an Issue or Pull Request with the stale label is closed 8 | daysUntilClose: false 9 | 10 | # Label to use when marking as stale 11 | staleLabel: status:stale 12 | 13 | # Comment to post when marking as stale 14 | markComment: > 15 | This pull request has been automatically marked as stale because it has not had 16 | recent activity. 17 | -------------------------------------------------------------------------------- /autoware_vehicle_msgs/msg/GearReport.msg: -------------------------------------------------------------------------------- 1 | uint8 NONE = 0 2 | uint8 NEUTRAL = 1 3 | uint8 DRIVE = 2 4 | uint8 DRIVE_2 = 3 5 | uint8 DRIVE_3 = 4 6 | uint8 DRIVE_4 = 5 7 | uint8 DRIVE_5 = 6 8 | uint8 DRIVE_6 = 7 9 | uint8 DRIVE_7 = 8 10 | uint8 DRIVE_8 = 9 11 | uint8 DRIVE_9 = 10 12 | uint8 DRIVE_10 = 11 13 | uint8 DRIVE_11 = 12 14 | uint8 DRIVE_12 = 13 15 | uint8 DRIVE_13 = 14 16 | uint8 DRIVE_14 = 15 17 | uint8 DRIVE_15 = 16 18 | uint8 DRIVE_16 = 17 19 | uint8 DRIVE_17 = 18 20 | uint8 DRIVE_18 = 19 21 | uint8 REVERSE = 20 22 | uint8 REVERSE_2 = 21 23 | uint8 PARK = 22 24 | uint8 LOW = 23 25 | uint8 LOW_2 = 24 26 | 27 | builtin_interfaces/Time stamp 28 | uint8 report 29 | -------------------------------------------------------------------------------- /autoware_vehicle_msgs/msg/GearCommand.msg: -------------------------------------------------------------------------------- 1 | uint8 NONE = 0 2 | uint8 NEUTRAL = 1 3 | uint8 DRIVE = 2 4 | uint8 DRIVE_2 = 3 5 | uint8 DRIVE_3 = 4 6 | uint8 DRIVE_4 = 5 7 | uint8 DRIVE_5 = 6 8 | uint8 DRIVE_6 = 7 9 | uint8 DRIVE_7 = 8 10 | uint8 DRIVE_8 = 9 11 | uint8 DRIVE_9 = 10 12 | uint8 DRIVE_10 = 11 13 | uint8 DRIVE_11 = 12 14 | uint8 DRIVE_12 = 13 15 | uint8 DRIVE_13 = 14 16 | uint8 DRIVE_14 = 15 17 | uint8 DRIVE_15 = 16 18 | uint8 DRIVE_16 = 17 19 | uint8 DRIVE_17 = 18 20 | uint8 DRIVE_18 = 19 21 | uint8 REVERSE = 20 22 | uint8 REVERSE_2 = 21 23 | uint8 PARK = 22 24 | uint8 LOW = 23 25 | uint8 LOW_2 = 24 26 | 27 | builtin_interfaces/Time stamp 28 | uint8 command 29 | -------------------------------------------------------------------------------- /autoware_perception_msgs/msg/ObjectClassification.msg: -------------------------------------------------------------------------------- 1 | uint8 UNKNOWN = 0 2 | uint8 CAR = 1 3 | uint8 TRUCK = 2 4 | uint8 BUS = 3 5 | uint8 TRAILER = 4 6 | uint8 MOTORCYCLE = 5 7 | uint8 BICYCLE = 6 8 | uint8 PEDESTRIAN = 7 9 | uint8 ANIMAL = 8 10 | uint8 HAZARD = 9 # Defined as an object that can cause danger to autonomous driving 11 | uint8 OVER_DRIVABLE = 10 # Defined as an object that can be safely driven over (e.g., leaf) 12 | uint8 UNDER_DRIVABLE = 11 # Defined as an object that can be safely driven under (e.g., overpass) 13 | 14 | # Object classification label (use constants above) 15 | uint8 label 16 | # Classification probability. Range: 0.0 to 1.0 17 | float32 probability 18 | -------------------------------------------------------------------------------- /autoware_control_msgs/CMakeLists.txt: -------------------------------------------------------------------------------- 1 | cmake_minimum_required(VERSION 3.5) 2 | project(autoware_control_msgs) 3 | 4 | find_package(ament_cmake_auto REQUIRED) 5 | ament_auto_find_build_dependencies() 6 | 7 | set(msg_files 8 | "msg/Control.msg" 9 | "msg/ControlHorizon.msg" 10 | "msg/Lateral.msg" 11 | "msg/Longitudinal.msg") 12 | 13 | set(msg_dependencies 14 | builtin_interfaces) 15 | 16 | rosidl_generate_interfaces(${PROJECT_NAME} 17 | ${msg_files} 18 | DEPENDENCIES ${msg_dependencies} 19 | ADD_LINTER_TESTS) 20 | 21 | if(BUILD_TESTING) 22 | find_package(ament_lint_auto REQUIRED) 23 | ament_lint_auto_find_test_dependencies() 24 | endif() 25 | 26 | ament_auto_package() 27 | -------------------------------------------------------------------------------- /autoware_map_msgs/msg/LaneletMapBin.msg: -------------------------------------------------------------------------------- 1 | # Lanelet map message 2 | # This message contains the binary data of a Lanelet map. 3 | # Also contains the map name, version and format. 4 | 5 | # Header with timestamp when the message is published 6 | # And frame of the Lanelet Map origin (probably just "map") 7 | std_msgs/Header header 8 | 9 | # Version of the map format (optional) 10 | # Example: "1.1.1" 11 | string version_map_format 12 | 13 | # Version of the map (encouraged, optional) 14 | # Example: "1.0.0" 15 | string version_map 16 | 17 | # Name of the map (encouraged, optional) 18 | # Example: "florence-prato-city-center" 19 | string name_map 20 | 21 | # Binary map data 22 | uint8[] data 23 | -------------------------------------------------------------------------------- /autoware_localization_msgs/CMakeLists.txt: -------------------------------------------------------------------------------- 1 | cmake_minimum_required(VERSION 3.5) 2 | project(autoware_localization_msgs) 3 | 4 | find_package(ament_cmake_auto REQUIRED) 5 | ament_auto_find_build_dependencies() 6 | 7 | set(msg_files 8 | "msg/KinematicState.msg" 9 | "srv/InitializeLocalization.srv") 10 | 11 | set(msg_dependencies 12 | autoware_common_msgs 13 | std_msgs 14 | geometry_msgs) 15 | 16 | rosidl_generate_interfaces(${PROJECT_NAME} 17 | ${msg_files} 18 | DEPENDENCIES ${msg_dependencies} 19 | ADD_LINTER_TESTS) 20 | 21 | if(BUILD_TESTING) 22 | find_package(ament_lint_auto REQUIRED) 23 | ament_lint_auto_find_test_dependencies() 24 | endif() 25 | 26 | ament_auto_package() 27 | -------------------------------------------------------------------------------- /.prettierrc.yaml: -------------------------------------------------------------------------------- 1 | # This file is automatically synced from: 2 | # https://github.com/autowarefoundation/sync-file-templates 3 | # To make changes, update the source repository and follow the guidelines in its README. 4 | 5 | printWidth: 100 6 | tabWidth: 2 7 | overrides: 8 | - files: package.xml 9 | options: 10 | printWidth: 1000 11 | xmlSelfClosingSpace: false 12 | xmlWhitespaceSensitivity: ignore 13 | 14 | - files: "*.launch.xml" 15 | options: 16 | printWidth: 200 17 | xmlSelfClosingSpace: false 18 | xmlWhitespaceSensitivity: ignore 19 | 20 | - files: "*.xacro" 21 | options: 22 | printWidth: 200 23 | xmlSelfClosingSpace: false 24 | xmlWhitespaceSensitivity: ignore 25 | -------------------------------------------------------------------------------- /autoware_control_msgs/msg/ControlHorizon.msg: -------------------------------------------------------------------------------- 1 | # Control messages calculated for a future horizon 2 | # 3 | # Control messages are ordered from near to far future [0 to N) with time_step_ms increments. 4 | # 5 | # First element of the array contains the control signals at the control_time of this message. 6 | # 7 | # The control_time field in each element of the controls array can be ignored. 8 | 9 | # Time this message was created 10 | builtin_interfaces/Time stamp 11 | 12 | # Time when controls[0] configuration state is expected to be achieved in 13 | builtin_interfaces/Time control_time 14 | 15 | # Time difference between consecutive elements of the controls array in milliseconds 16 | float32 time_step_ms 17 | 18 | Control[] controls 19 | -------------------------------------------------------------------------------- /.github/ISSUE_TEMPLATE/config.yml: -------------------------------------------------------------------------------- 1 | # This file is automatically synced from: 2 | # https://github.com/autowarefoundation/sync-file-templates 3 | # To make changes, update the source repository and follow the guidelines in its README. 4 | 5 | blank_issues_enabled: false 6 | contact_links: 7 | - name: Question 8 | url: https://github.com/autowarefoundation/autoware/discussions/new?category=q-a 9 | about: Ask a question 10 | 11 | - name: Feature request 12 | url: https://github.com/autowarefoundation/autoware/discussions/new?category=feature-requests 13 | about: Send a feature request 14 | 15 | - name: Idea 16 | url: https://github.com/autowarefoundation/autoware/discussions/new?category=ideas 17 | about: Post an idea 18 | -------------------------------------------------------------------------------- /.pre-commit-config-optional.yaml: -------------------------------------------------------------------------------- 1 | # This file is automatically synced from: 2 | # https://github.com/autowarefoundation/sync-file-templates 3 | # To make changes, update the source repository and follow the guidelines in its README. 4 | 5 | # https://pre-commit.ci/#configuration 6 | ci: 7 | autofix_commit_msg: "style(pre-commit-optional): autofix" 8 | # we already have our own daily update mechanism, we set this to quarterly 9 | autoupdate_schedule: quarterly 10 | autoupdate_commit_msg: "ci(pre-commit-optional): quarterly autoupdate" 11 | 12 | repos: 13 | - repo: https://github.com/tcort/markdown-link-check 14 | rev: v3.12.2 15 | hooks: 16 | - id: markdown-link-check 17 | args: [--quiet, --config=.markdown-link-check.json] 18 | -------------------------------------------------------------------------------- /autoware_perception_msgs/msg/TrafficSignalElement.msg: -------------------------------------------------------------------------------- 1 | # TODO(youtalk): Remove this after migration to TrafficLight 2 | # constants for common use 3 | uint8 UNKNOWN = 0 4 | 5 | # constants for color 6 | uint8 RED = 1 7 | uint8 AMBER = 2 8 | uint8 GREEN = 3 9 | uint8 WHITE = 4 10 | 11 | # constants for shape 12 | uint8 CIRCLE = 1 13 | uint8 LEFT_ARROW = 2 14 | uint8 RIGHT_ARROW = 3 15 | uint8 UP_ARROW = 4 16 | uint8 UP_LEFT_ARROW=5 17 | uint8 UP_RIGHT_ARROW=6 18 | uint8 DOWN_ARROW = 7 19 | uint8 DOWN_LEFT_ARROW = 8 20 | uint8 DOWN_RIGHT_ARROW = 9 21 | uint8 CROSS = 10 22 | 23 | # constants for status 24 | uint8 SOLID_OFF = 1 25 | uint8 SOLID_ON = 2 26 | uint8 FLASHING = 3 27 | 28 | # variables 29 | uint8 color 30 | uint8 shape 31 | uint8 status 32 | float32 confidence 33 | -------------------------------------------------------------------------------- /.github/workflows/pre-commit-optional.yaml: -------------------------------------------------------------------------------- 1 | # This file is automatically synced from: 2 | # https://github.com/autowarefoundation/sync-file-templates 3 | # To make changes, update the source repository and follow the guidelines in its README. 4 | 5 | name: pre-commit-optional 6 | 7 | on: 8 | pull_request: 9 | 10 | jobs: 11 | pre-commit-optional: 12 | runs-on: ubuntu-22.04 13 | steps: 14 | - name: Check out repository 15 | uses: actions/checkout@v4 16 | with: 17 | fetch-depth: 0 18 | 19 | - name: Run pre-commit 20 | uses: autowarefoundation/autoware-github-actions/pre-commit@v1 21 | with: 22 | pre-commit-config: .pre-commit-config-optional.yaml 23 | base-branch: origin/${{ github.base_ref }} 24 | -------------------------------------------------------------------------------- /autoware_system_msgs/CMakeLists.txt: -------------------------------------------------------------------------------- 1 | cmake_minimum_required(VERSION 3.5) 2 | project(autoware_system_msgs) 3 | 4 | find_package(ament_cmake_auto REQUIRED) 5 | ament_auto_find_build_dependencies() 6 | 7 | rosidl_generate_interfaces(${PROJECT_NAME} 8 | "msg/AutowareState.msg" 9 | "msg/HazardStatus.msg" 10 | "msg/HazardStatusStamped.msg" 11 | "srv/ChangeOperationMode.srv" 12 | "srv/ChangeAutowareControl.srv" 13 | DEPENDENCIES 14 | autoware_common_msgs 15 | geometry_msgs 16 | std_msgs 17 | unique_identifier_msgs 18 | nav_msgs 19 | builtin_interfaces 20 | diagnostic_msgs 21 | ADD_LINTER_TESTS 22 | ) 23 | 24 | if(BUILD_TESTING) 25 | find_package(ament_lint_auto REQUIRED) 26 | ament_lint_auto_find_test_dependencies() 27 | endif() 28 | 29 | ament_auto_package() 30 | -------------------------------------------------------------------------------- /autoware_control_msgs/msg/Longitudinal.msg: -------------------------------------------------------------------------------- 1 | # Longitudinal control message 2 | # 3 | # Values are in the base_link frame in X axis 4 | # 5 | # Positive values represent forward motion (+X) 6 | # Negative values represent backward motion (-X) 7 | 8 | # Time this message was created 9 | builtin_interfaces/Time stamp 10 | 11 | # Time this configuration state is expected to be achieved in (optional) 12 | builtin_interfaces/Time control_time 13 | 14 | # Desired vehicle velocity in in m/s 15 | float32 velocity 16 | 17 | # Desired vehicle acceleration in m/s² 18 | float32 acceleration 19 | 20 | # Desired vehicle jerk in m/s³ 21 | float32 jerk 22 | 23 | # Controller has filled in the acceleration value 24 | bool is_defined_acceleration 25 | 26 | # Controller has filled in the jerk value 27 | bool is_defined_jerk 28 | -------------------------------------------------------------------------------- /autoware_localization_msgs/srv/InitializeLocalization.srv: -------------------------------------------------------------------------------- 1 | # constants for specifying initialization method 2 | uint8 AUTO = 0 3 | uint8 DIRECT = 1 4 | 5 | # input pose for initialization 6 | geometry_msgs/PoseWithCovarianceStamped[<=1] pose_with_covariance 7 | 8 | # Variable to set initialization method 9 | # AUTO: The initial position is automatically estimated with localization algorithm. 10 | # The input pose will be used as an initial guess if provided. 11 | # DIRECT: The initial position is set directly by the input pose without going through localization algorithm. 12 | uint8 method 13 | --- 14 | # ERROR CODES used in response status in case of failure 15 | uint16 ERROR_UNSAFE = 1 16 | uint16 ERROR_GNSS_SUPPORT = 2 17 | uint16 ERROR_GNSS = 3 18 | uint16 ERROR_ESTIMATION = 4 19 | 20 | autoware_common_msgs/ResponseStatus status 21 | -------------------------------------------------------------------------------- /.yamllint.yaml: -------------------------------------------------------------------------------- 1 | # This file is automatically synced from: 2 | # https://github.com/autowarefoundation/sync-file-templates 3 | # To make changes, update the source repository and follow the guidelines in its README. 4 | 5 | extends: default 6 | 7 | ignore: | 8 | *.param.yaml 9 | 10 | rules: 11 | braces: 12 | level: error 13 | max-spaces-inside: 1 # To format with Prettier 14 | comments: 15 | level: error 16 | min-spaces-from-content: 1 # To be compatible with C++ and Python 17 | document-start: 18 | level: error 19 | present: false # Don't need document start markers 20 | line-length: disable # Delegate to Prettier 21 | truthy: 22 | level: error 23 | check-keys: false # To allow 'on' of GitHub Actions 24 | quoted-strings: 25 | level: error 26 | required: only-when-needed # To keep consistent style 27 | -------------------------------------------------------------------------------- /autoware_localization_msgs/msg/KinematicState.msg: -------------------------------------------------------------------------------- 1 | # KinematicState represents an estimate of a position, velocity and acceleration in free space. 2 | # The pose_with_covariance is in the coordinate frame given by header.frame_id 3 | # The twist_with_covariance and accel_with_covariance are in the coordinate frame given by the child_frame_id 4 | 5 | # Includes the frame id of the pose parent. 6 | std_msgs/Header header 7 | 8 | # Frame id the pose points to. 9 | string child_frame_id 10 | 11 | # Estimated pose that is relative to the header.frame_id. 12 | geometry_msgs/PoseWithCovariance pose_with_covariance 13 | 14 | # Estimated linear and angular velocity relative to child_frame_id. 15 | geometry_msgs/TwistWithCovariance twist_with_covariance 16 | 17 | # Estimated linear and angular acceleration relative to child_frame_id. 18 | geometry_msgs/AccelWithCovariance accel_with_covariance 19 | -------------------------------------------------------------------------------- /.github/workflows/spell-check-differential.yaml: -------------------------------------------------------------------------------- 1 | # This file is automatically synced from: 2 | # https://github.com/autowarefoundation/sync-file-templates 3 | # To make changes, update the source repository and follow the guidelines in its README. 4 | 5 | name: spell-check-differential 6 | 7 | on: 8 | pull_request: 9 | 10 | jobs: 11 | spell-check-differential: 12 | runs-on: ubuntu-22.04 13 | steps: 14 | - name: Check out repository 15 | uses: actions/checkout@v4 16 | 17 | - name: Run spell-check 18 | uses: autowarefoundation/autoware-github-actions/spell-check@v1 19 | with: 20 | cspell-json-url: https://raw.githubusercontent.com/autowarefoundation/autoware-spell-check-dict/main/.cspell.json 21 | dict-packages: | 22 | https://github.com/autowarefoundation/autoware-spell-check-dict 23 | https://github.com/tier4/cspell-dicts 24 | -------------------------------------------------------------------------------- /autoware_sensing_msgs/CMakeLists.txt: -------------------------------------------------------------------------------- 1 | cmake_minimum_required(VERSION 3.5) 2 | project(autoware_sensing_msgs) 3 | 4 | find_package(ament_cmake_auto REQUIRED) 5 | ament_auto_find_build_dependencies() 6 | 7 | set(msg_files 8 | "msg/ConcatenatedPointCloudInfo.msg" 9 | "msg/GnssInsOrientation.msg" 10 | "msg/GnssInsOrientationStamped.msg" 11 | "msg/RadarClassification.msg" 12 | "msg/RadarFieldInfo.msg" 13 | "msg/RadarInfo.msg" 14 | "msg/RadarObject.msg" 15 | "msg/RadarObjects.msg" 16 | "msg/SourcePointCloudInfo.msg") 17 | 18 | set(msg_dependencies 19 | geometry_msgs 20 | sensor_msgs 21 | std_msgs) 22 | 23 | rosidl_generate_interfaces(${PROJECT_NAME} 24 | ${msg_files} 25 | DEPENDENCIES ${msg_dependencies} 26 | ADD_LINTER_TESTS) 27 | 28 | if(BUILD_TESTING) 29 | find_package(ament_lint_auto REQUIRED) 30 | ament_lint_auto_find_test_dependencies() 31 | endif() 32 | 33 | ament_auto_package() 34 | -------------------------------------------------------------------------------- /.github/workflows/release-new-version-when-merged.yaml: -------------------------------------------------------------------------------- 1 | name: tag release after PR merge 2 | 3 | on: 4 | pull_request: 5 | types: [closed] 6 | 7 | jobs: 8 | tag-on-merge: 9 | if: | 10 | github.event.pull_request.merged == true && 11 | contains( 12 | join(github.event.pull_request.labels.*.name, ','), 13 | 'release:bump-version' 14 | ) 15 | runs-on: ubuntu-22.04 16 | steps: 17 | - name: Generate token 18 | id: generate-token 19 | uses: actions/create-github-app-token@v1 20 | with: 21 | app-id: ${{ secrets.APP_ID }} 22 | private-key: ${{ secrets.PRIVATE_KEY }} 23 | 24 | - name: Run 25 | uses: autowarefoundation/autoware-github-actions/release-new-tag-when-merged@v1 26 | with: 27 | github_token: ${{ steps.generate-token.outputs.token }} 28 | commit_sha: ${{ github.event.pull_request.merge_commit_sha }} 29 | -------------------------------------------------------------------------------- /autoware_perception_msgs/msg/TrafficLightElement.msg: -------------------------------------------------------------------------------- 1 | # constants for common use 2 | uint8 UNKNOWN = 0 3 | 4 | # constants for color 5 | uint8 RED = 1 6 | uint8 AMBER = 2 7 | uint8 GREEN = 3 8 | uint8 WHITE = 4 9 | 10 | # constants for shape 11 | uint8 CIRCLE = 1 12 | uint8 LEFT_ARROW = 2 13 | uint8 RIGHT_ARROW = 3 14 | uint8 UP_ARROW = 4 15 | uint8 UP_LEFT_ARROW=5 16 | uint8 UP_RIGHT_ARROW=6 17 | uint8 DOWN_ARROW = 7 18 | uint8 DOWN_LEFT_ARROW = 8 19 | uint8 DOWN_RIGHT_ARROW = 9 20 | uint8 CROSS = 10 21 | 22 | # constants for status 23 | uint8 SOLID_OFF = 1 24 | uint8 SOLID_ON = 2 25 | uint8 FLASHING = 3 26 | 27 | # fields 28 | # Traffic light color (use color constants above, or UNKNOWN) 29 | uint8 color 30 | # Traffic light shape (use shape constants above, or UNKNOWN) 31 | uint8 shape 32 | # Traffic light status (use status constants above, or UNKNOWN) 33 | uint8 status 34 | # Detection confidence. Range: 0.0 to 1.0 35 | float32 confidence 36 | -------------------------------------------------------------------------------- /autoware_sensing_msgs/msg/SourcePointCloudInfo.msg: -------------------------------------------------------------------------------- 1 | # This message holds metadata information about a source point cloud segment 2 | # within a concatenated point cloud, including its spatial boundaries and structural properties. 3 | 4 | # Available status codes for source point cloud 5 | uint8 STATUS_OK = 0 # Cloud received (may have 0 or more points) 6 | uint8 STATUS_TIMEOUT = 1 # Cloud not received due to timeout 7 | uint8 STATUS_INVALID = 2 # Cloud arrived but was malformed/corrupt 8 | 9 | # Time of sensor data acquisition, and the coordinate frame ID (for 3d points). 10 | std_msgs/Header header 11 | 12 | string topic # Source topic 13 | uint8 status # Status of the source point cloud 14 | 15 | # The starting index (inclusive) of the point cloud segment within the concatenated point cloud 16 | uint32 idx_begin 17 | 18 | # The length of the point cloud segment in the concatenated point cloud 19 | uint32 length 20 | -------------------------------------------------------------------------------- /autoware_map_msgs/msg/MapProjectorInfo.msg: -------------------------------------------------------------------------------- 1 | # Projector type 2 | string LOCAL = "Local" 3 | string LOCAL_CARTESIAN_UTM = "LocalCartesianUTM" 4 | string LOCAL_CARTESIAN = "LocalCartesian" 5 | string MGRS = "MGRS" 6 | string TRANSVERSE_MERCATOR = "TransverseMercator" 7 | string projector_type 8 | 9 | # Vertical datum 10 | string WGS84 = "WGS84" 11 | string EGM2008 = "EGM2008" 12 | string vertical_datum 13 | 14 | # Used for MGRS map 15 | string mgrs_grid 16 | 17 | # Used for some map projection types 18 | # Altitude is not used, so there is no need to specify it. 19 | # Even if altitude is specified, it will be overwritten with 0.0. 20 | geographic_msgs/GeoPoint map_origin 21 | 22 | # Scale factor of the map 23 | # Used for TransverseMercator map (default: 0.9996) 24 | # In the case of LocalCartesianUTM and MGRS, it will be overwritten with 0.9996. 25 | # In the case of Local and LocalCartesian, it will be overwritten with 1.0. 26 | float32 scale_factor 27 | -------------------------------------------------------------------------------- /.github/workflows/spell-check-daily.yaml: -------------------------------------------------------------------------------- 1 | # This file is automatically synced from: 2 | # https://github.com/autowarefoundation/sync-file-templates 3 | # To make changes, update the source repository and follow the guidelines in its README. 4 | 5 | name: spell-check-daily 6 | 7 | on: 8 | schedule: 9 | - cron: 0 0 * * * 10 | workflow_dispatch: 11 | 12 | jobs: 13 | spell-check-daily: 14 | runs-on: ubuntu-22.04 15 | steps: 16 | - name: Check out repository 17 | uses: actions/checkout@v4 18 | 19 | - name: Run spell-check 20 | uses: autowarefoundation/autoware-github-actions/spell-check@v1 21 | with: 22 | incremental-files-only: false 23 | cspell-json-url: https://raw.githubusercontent.com/tier4/autoware-spell-check-dict/main/.cspell.json 24 | dict-packages: | 25 | https://github.com/autowarefoundation/autoware-spell-check-dict 26 | https://github.com/tier4/cspell-dicts 27 | -------------------------------------------------------------------------------- /autoware_control_msgs/msg/Lateral.msg: -------------------------------------------------------------------------------- 1 | # Lateral control message for Ackermann-style platforms 2 | # 3 | # Note regarding tires: If the platform has multiple steering tires, the commands 4 | # given here are for a virtual tire at the average lateral position of the steering tires. 5 | # 6 | # Look up Ackermann Bicycle Model for more details 7 | # 8 | # Positive values represents left inclination (if forward) 9 | # Negative values represents right inclination (if forward) 10 | 11 | # Time this message was created 12 | builtin_interfaces/Time stamp 13 | 14 | # Time this configuration state is expected to be achieved in (optional) 15 | builtin_interfaces/Time control_time 16 | 17 | # Desired angle of the steering tire in rad (radians) 18 | float32 steering_tire_angle 19 | 20 | # Desired rate of change of the steering tire angle in rad/s 21 | float32 steering_tire_rotation_rate 22 | 23 | # Controller has filled in the steering_tire_rotation_rate value 24 | bool is_defined_steering_tire_rotation_rate 25 | -------------------------------------------------------------------------------- /autoware_planning_msgs/CMakeLists.txt: -------------------------------------------------------------------------------- 1 | cmake_minimum_required(VERSION 3.5) 2 | project(autoware_planning_msgs) 3 | 4 | find_package(ament_cmake_auto REQUIRED) 5 | ament_auto_find_build_dependencies() 6 | 7 | rosidl_generate_interfaces(${PROJECT_NAME} 8 | "msg/LaneletPrimitive.msg" 9 | "msg/LaneletRoute.msg" 10 | "msg/LaneletSegment.msg" 11 | "msg/PoseWithUuidStamped.msg" 12 | "msg/Trajectory.msg" 13 | "msg/TrajectoryPoint.msg" 14 | "msg/Path.msg" 15 | "msg/PathPoint.msg" 16 | "msg/RouteState.msg" 17 | "srv/ClearRoute.srv" 18 | "srv/SetLaneletRoute.srv" 19 | "srv/SetPreferredPrimitive.srv" 20 | "srv/SetWaypointRoute.srv" 21 | DEPENDENCIES 22 | autoware_common_msgs 23 | geometry_msgs 24 | std_msgs 25 | unique_identifier_msgs 26 | nav_msgs 27 | builtin_interfaces 28 | ADD_LINTER_TESTS 29 | ) 30 | 31 | if(BUILD_TESTING) 32 | find_package(ament_lint_auto REQUIRED) 33 | ament_lint_auto_find_test_dependencies() 34 | endif() 35 | 36 | ament_auto_package() 37 | -------------------------------------------------------------------------------- /autoware_vehicle_msgs/CMakeLists.txt: -------------------------------------------------------------------------------- 1 | # All rights reserved. 2 | cmake_minimum_required(VERSION 3.5) 3 | 4 | ### Export headers 5 | project(autoware_vehicle_msgs) 6 | 7 | # Generate messages 8 | find_package(ament_cmake_auto REQUIRED) 9 | ament_auto_find_build_dependencies() 10 | 11 | rosidl_generate_interfaces(${PROJECT_NAME} 12 | "msg/ControlModeReport.msg" 13 | "msg/Engage.msg" 14 | "msg/GearCommand.msg" 15 | "msg/GearReport.msg" 16 | "msg/HazardLightsCommand.msg" 17 | "msg/HazardLightsReport.msg" 18 | "msg/SteeringReport.msg" 19 | "msg/TurnIndicatorsCommand.msg" 20 | "msg/TurnIndicatorsReport.msg" 21 | "msg/VelocityReport.msg" 22 | "srv/ControlModeCommand.srv" 23 | DEPENDENCIES 24 | "autoware_planning_msgs" 25 | "builtin_interfaces" 26 | "std_msgs" 27 | ADD_LINTER_TESTS 28 | ) 29 | 30 | if(BUILD_TESTING) 31 | find_package(ament_lint_auto REQUIRED) 32 | ament_lint_auto_find_test_dependencies() 33 | endif() 34 | 35 | ament_auto_package() 36 | -------------------------------------------------------------------------------- /autoware_sensing_msgs/msg/RadarObject.msg: -------------------------------------------------------------------------------- 1 | float32 INVALID_COV_VALUE = -1.0 2 | 3 | uint8 MEASUREMENT_STATUS_INVALID = 0 4 | uint8 MEASUREMENT_STATUS_MEASURED = 1 5 | uint8 MEASUREMENT_STATUS_PREDICTED = 2 6 | uint8 MEASUREMENT_STATUS_NEW = 3 7 | uint8 MEASUREMENT_STATUS_UNKNOWN = 4 8 | 9 | uint8 MOVEMENT_STATUS_INVALID = 0 10 | uint8 MOVEMENT_STATUS_DYNAMIC = 1 11 | uint8 MOVEMENT_STATUS_STATIC = 2 12 | uint8 MOVEMENT_STATUS_UNKNOWN = 3 13 | 14 | uint32 object_id 15 | uint16 age 16 | uint8 measurement_status 17 | uint8 movement_status 18 | 19 | geometry_msgs/Point position 20 | geometry_msgs/Vector3 velocity 21 | geometry_msgs/Vector3 acceleration 22 | geometry_msgs/Vector3 size 23 | 24 | float32[6] position_covariance 25 | float32[6] velocity_covariance 26 | float32[6] acceleration_covariance 27 | float32[6] size_covariance 28 | 29 | float32 orientation 30 | float32 orientation_std 31 | float32 orientation_rate 32 | float32 orientation_rate_std 33 | 34 | float32 existence_probability 35 | RadarClassification[] classifications 36 | -------------------------------------------------------------------------------- /autoware_sensing_msgs/msg/ConcatenatedPointCloudInfo.msg: -------------------------------------------------------------------------------- 1 | # This message holds information about a concatenated point cloud that combines multiple source 2 | # point clouds, including the overall point cloud structure and metadata for each source segment. 3 | 4 | # Available matching strategies for source point clouds concatenation 5 | uint8 STRATEGY_NAIVE = 0 # Assigns the oldest stamp of the sensor that was concatenated 6 | uint8 STRATEGY_ADVANCED = 1 # Assigns the oldest stamp of the sensor that was concatenated 7 | 8 | # The concatenated point cloud header, where timestamp assignment depends on matching strategy 9 | std_msgs/Header header 10 | 11 | bool concatenation_success # Whether concatenation was successful 12 | uint8 matching_strategy # Strategy used for concatenation 13 | 14 | # Raw data of concatenation config, relevant to matching_strategy field. 15 | uint8[] matching_strategy_config 16 | 17 | SourcePointCloudInfo[] source_info # Meta information of input point clouds 18 | -------------------------------------------------------------------------------- /autoware_msgs/CHANGELOG.rst: -------------------------------------------------------------------------------- 1 | ^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^ 2 | Changelog for package autoware_msgs 3 | ^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^ 4 | 5 | 1.11.0 (2025-10-23) 6 | ------------------- 7 | 8 | 1.10.0 (2025-07-18) 9 | ------------------- 10 | 11 | 1.9.0 (2025-06-18) 12 | ------------------ 13 | 14 | 1.8.0 (2025-05-21) 15 | ------------------ 16 | * chore: fix email domain (`#133 `_) 17 | * chore: update maintainers (`#132 `_) 18 | * Contributors: Mete Fatih Cırıt 19 | 20 | 1.7.0 (2025-04-21) 21 | ------------------ 22 | 23 | 1.6.0 (2025-04-07) 24 | ------------------ 25 | * feat(autoware msgs): create metapackage (`#123 `_) 26 | * create autoware_msgs 27 | * add maintainer 28 | * style(pre-commit): autofix 29 | * Update autoware_msgs/package.xml 30 | --------- 31 | Co-authored-by: pre-commit-ci[bot] <66853113+pre-commit-ci[bot]@users.noreply.github.com> 32 | * Contributors: Yutaka Kondo 33 | -------------------------------------------------------------------------------- /.github/workflows/pre-commit.yaml: -------------------------------------------------------------------------------- 1 | # This file is automatically synced from: 2 | # https://github.com/autowarefoundation/sync-file-templates 3 | # To make changes, update the source repository and follow the guidelines in its README. 4 | 5 | name: pre-commit 6 | 7 | on: 8 | pull_request: 9 | 10 | jobs: 11 | pre-commit: 12 | if: ${{ github.event.repository.private }} # Use pre-commit.ci for public repositories 13 | runs-on: ubuntu-22.04 14 | steps: 15 | - name: Generate token 16 | id: generate-token 17 | uses: tibdex/github-app-token@v2 18 | with: 19 | app_id: ${{ secrets.APP_ID }} 20 | private_key: ${{ secrets.PRIVATE_KEY }} 21 | 22 | - name: Check out repository 23 | uses: actions/checkout@v4 24 | with: 25 | ref: ${{ github.event.pull_request.head.ref }} 26 | 27 | - name: Run pre-commit 28 | uses: autowarefoundation/autoware-github-actions/pre-commit@v1 29 | with: 30 | pre-commit-config: .pre-commit-config.yaml 31 | token: ${{ steps.generate-token.outputs.token }} 32 | -------------------------------------------------------------------------------- /autoware_map_msgs/CMakeLists.txt: -------------------------------------------------------------------------------- 1 | cmake_minimum_required(VERSION 3.5) 2 | project(autoware_map_msgs) 3 | 4 | find_package(ament_cmake_auto REQUIRED) 5 | ament_auto_find_build_dependencies() 6 | 7 | set(msg_files 8 | "msg/AreaInfo.msg" 9 | "msg/LaneletMapBin.msg" 10 | "msg/LaneletMapMetaData.msg" 11 | "msg/LaneletMapCellMetaData.msg" 12 | "msg/MapProjectorInfo.msg" 13 | "msg/PointCloudMapCellWithID.msg" 14 | "msg/PointCloudMapCellMetaData.msg" 15 | "msg/PointCloudMapCellMetaDataWithID.msg" 16 | "msg/PointCloudMapMetaData.msg" 17 | "srv/GetPartialPointCloudMap.srv" 18 | "srv/GetDifferentialPointCloudMap.srv" 19 | "srv/GetSelectedPointCloudMap.srv" 20 | "srv/GetSelectedLanelet2Map.srv") 21 | 22 | set(msg_dependencies 23 | std_msgs 24 | geometry_msgs 25 | geographic_msgs 26 | sensor_msgs) 27 | 28 | rosidl_generate_interfaces(${PROJECT_NAME} 29 | ${msg_files} 30 | DEPENDENCIES ${msg_dependencies} 31 | ADD_LINTER_TESTS) 32 | 33 | if(BUILD_TESTING) 34 | find_package(ament_lint_auto REQUIRED) 35 | ament_lint_auto_find_test_dependencies() 36 | endif() 37 | 38 | ament_auto_package() 39 | -------------------------------------------------------------------------------- /autoware_control_msgs/package.xml: -------------------------------------------------------------------------------- 1 | 2 | 3 | 4 | autoware_control_msgs 5 | 1.11.0 6 | Autoware control messages package. 7 | 8 | Mete Fatih Cırıt 9 | Ryohsuke Mitsudome 10 | Yutaka Kondo 11 | 12 | Apache License 2.0 13 | 14 | ament_cmake_auto 15 | rosidl_default_generators 16 | 17 | builtin_interfaces 18 | 19 | rosidl_default_runtime 20 | 21 | ament_lint_auto 22 | ament_lint_common 23 | 24 | rosidl_interface_packages 25 | 26 | 27 | ament_cmake 28 | 29 | 30 | -------------------------------------------------------------------------------- /autoware_perception_msgs/msg/TrackedObjectKinematics.msg: -------------------------------------------------------------------------------- 1 | # Only position is available, orientation is empty. Note that the shape can be an oriented 2 | # bounding box but the direction the object is facing is unknown, in which case 3 | # orientation should be empty. 4 | uint8 UNAVAILABLE=0 5 | 6 | # The orientation is determined only up to a sign flip. For instance, assume that cars are 7 | # longer than they are wide, and the perception pipeline can accurately estimate the 8 | # dimensions of a car. It should set the orientation to coincide with the major axis, with 9 | # the sign chosen arbitrarily, and use this tag to signify that the orientation could 10 | # point to the front or the back. 11 | uint8 SIGN_UNKNOWN=1 12 | 13 | # The full orientation is available. Use e.g. for machine-learning models that can 14 | # differentiate between the front and back of a vehicle. 15 | uint8 AVAILABLE=2 16 | 17 | geometry_msgs/PoseWithCovariance pose_with_covariance 18 | geometry_msgs/TwistWithCovariance twist_with_covariance 19 | geometry_msgs/AccelWithCovariance acceleration_with_covariance 20 | 21 | uint8 orientation_availability 22 | bool is_stationary 23 | -------------------------------------------------------------------------------- /autoware_perception_msgs/msg/DetectedObjectKinematics.msg: -------------------------------------------------------------------------------- 1 | # Only position is available, orientation is empty. Note that the shape can be an oriented 2 | # bounding box but the direction the object is facing is unknown, in which case 3 | # orientation should be empty. 4 | uint8 UNAVAILABLE=0 5 | 6 | # The orientation is determined only up to a sign flip. For instance, assume that cars are 7 | # longer than they are wide, and the perception pipeline can accurately estimate the 8 | # dimensions of a car. It should set the orientation to coincide with the major axis, with 9 | # the sign chosen arbitrarily, and use this tag to signify that the orientation could 10 | # point to the front or the back. 11 | uint8 SIGN_UNKNOWN=1 12 | 13 | # The full orientation is available. Use e.g. for machine-learning models that can 14 | # differentiate between the front and back of a vehicle. 15 | uint8 AVAILABLE=2 16 | 17 | geometry_msgs/PoseWithCovariance pose_with_covariance 18 | 19 | bool has_position_covariance 20 | uint8 orientation_availability 21 | 22 | geometry_msgs/TwistWithCovariance twist_with_covariance 23 | 24 | bool has_twist 25 | bool has_twist_covariance 26 | -------------------------------------------------------------------------------- /autoware_v2x_msgs/package.xml: -------------------------------------------------------------------------------- 1 | 2 | 3 | 4 | autoware_v2x_msgs 5 | 1.11.0 6 | Autoware v2x messages package. 7 | Takagi, Isamu 8 | Ryohsuke Mitsudome 9 | Yukihiro Saito 10 | Apache License 2.0 11 | 12 | ament_cmake_auto 13 | 14 | rosidl_default_generators 15 | 16 | builtin_interfaces 17 | geometry_msgs 18 | 19 | rosidl_default_runtime 20 | 21 | ament_lint_auto 22 | ament_lint_common 23 | 24 | rosidl_interface_packages 25 | 26 | 27 | ament_cmake 28 | 29 | 30 | -------------------------------------------------------------------------------- /autoware_perception_msgs/CMakeLists.txt: -------------------------------------------------------------------------------- 1 | cmake_minimum_required(VERSION 3.14) 2 | project(autoware_perception_msgs) 3 | 4 | find_package(ament_cmake_auto REQUIRED) 5 | ament_auto_find_build_dependencies() 6 | 7 | rosidl_generate_interfaces(${PROJECT_NAME} 8 | "msg/DetectedObject.msg" 9 | "msg/DetectedObjectKinematics.msg" 10 | "msg/DetectedObjects.msg" 11 | "msg/ObjectClassification.msg" 12 | "msg/PredictedObject.msg" 13 | "msg/PredictedObjectKinematics.msg" 14 | "msg/PredictedObjects.msg" 15 | "msg/PredictedPath.msg" 16 | "msg/PredictedTrafficLightState.msg" 17 | "msg/Shape.msg" 18 | "msg/TrackedObject.msg" 19 | "msg/TrackedObjectKinematics.msg" 20 | "msg/TrackedObjects.msg" 21 | "msg/TrafficLightElement.msg" 22 | "msg/TrafficLightGroup.msg" 23 | "msg/TrafficLightGroupArray.msg" 24 | # TODO(youtalk): Remove below after migration to TrafficLight 25 | "msg/TrafficSignalElement.msg" 26 | "msg/TrafficSignal.msg" 27 | "msg/TrafficSignalArray.msg" 28 | 29 | DEPENDENCIES 30 | std_msgs 31 | geometry_msgs 32 | builtin_interfaces 33 | unique_identifier_msgs 34 | 35 | ADD_LINTER_TESTS 36 | ) 37 | 38 | ament_auto_package() 39 | -------------------------------------------------------------------------------- /.github/workflows/sync-files.yaml: -------------------------------------------------------------------------------- 1 | # This file is automatically synced from: 2 | # https://github.com/autowarefoundation/sync-file-templates 3 | # To make changes, update the source repository and follow the guidelines in its README. 4 | 5 | name: sync-files 6 | 7 | on: 8 | schedule: 9 | - cron: 0 0 * * * 10 | workflow_dispatch: 11 | 12 | jobs: 13 | check-secret: 14 | uses: autowarefoundation/autoware-github-actions/.github/workflows/check-secret.yaml@v1 15 | secrets: 16 | secret: ${{ secrets.APP_ID }} 17 | 18 | sync-files: 19 | needs: check-secret 20 | if: ${{ needs.check-secret.outputs.set == 'true' }} 21 | runs-on: ubuntu-22.04 22 | steps: 23 | - name: Generate token 24 | id: generate-token 25 | uses: tibdex/github-app-token@v2 26 | with: 27 | app_id: ${{ secrets.APP_ID }} 28 | private_key: ${{ secrets.PRIVATE_KEY }} 29 | 30 | - name: Run sync-files 31 | uses: autowarefoundation/autoware-github-actions/sync-files@v1 32 | with: 33 | token: ${{ steps.generate-token.outputs.token }} 34 | pr-labels: | 35 | tag:bot 36 | tag:sync-files 37 | auto-merge-method: squash 38 | -------------------------------------------------------------------------------- /autoware_common_msgs/package.xml: -------------------------------------------------------------------------------- 1 | 2 | 3 | 4 | autoware_common_msgs 5 | 1.11.0 6 | Autoware common messages package. 7 | Takagi, Isamu 8 | Mete Fatih Cırıt 9 | Ryohsuke Mitsudome 10 | Yukihiro Saito 11 | Yutaka Kondo 12 | Apache License 2.0 13 | 14 | ament_cmake_auto 15 | rosidl_default_generators 16 | 17 | rosidl_default_runtime 18 | 19 | ament_lint_auto 20 | ament_lint_common 21 | 22 | rosidl_interface_packages 23 | 24 | 25 | ament_cmake 26 | 27 | 28 | -------------------------------------------------------------------------------- /autoware_perception_msgs/msg/PredictedTrafficLightState.msg: -------------------------------------------------------------------------------- 1 | # Information source values (string constants): 2 | # - V2N: Signal data sent from a server (Internet) 3 | # - V2I: Direct from RSU (Roadside Unit) 4 | # - V2V: Signal data from another vehicle 5 | # - LOCAL_PERCEPTION: Information detected by onboard sensors 6 | # - MANUAL_OVERRIDE: Manually set signal data (for testing/debugging) 7 | # - SIMULATION: Signal data from a simulated environment 8 | # - INTERNAL_ESTIMATION: Information that was predicted by an onboard model 9 | 10 | string INFORMATION_SOURCE_V2N="V2N" 11 | string INFORMATION_SOURCE_V2I="V2I" 12 | string INFORMATION_SOURCE_V2V="V2V" 13 | string INFORMATION_SOURCE_LOCAL_PERCEPTION="LOCAL_PERCEPTION" 14 | string INFORMATION_SOURCE_MANUAL_OVERRIDE="MANUAL_OVERRIDE" 15 | string INFORMATION_SOURCE_SIMULATION="SIMULATION" 16 | string INFORMATION_SOURCE_INTERNAL_ESTIMATION="INTERNAL_ESTIMATION" 17 | 18 | # Absolute time this state is expected 19 | builtin_interfaces/Time predicted_stamp 20 | 21 | # Valid signals at this time 22 | autoware_perception_msgs/TrafficLightElement[] simultaneous_elements 23 | 24 | # Confidence level [0.0–1.0] 25 | float32 reliability 26 | 27 | # Source of information, using predefined string constants 28 | string information_source 29 | -------------------------------------------------------------------------------- /autoware_v2x_msgs/CHANGELOG.rst: -------------------------------------------------------------------------------- 1 | ^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^ 2 | Changelog for package autoware_v2x_msgs 3 | ^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^ 4 | 5 | 1.11.0 (2025-10-23) 6 | ------------------- 7 | 8 | 1.10.0 (2025-07-18) 9 | ------------------- 10 | 11 | 1.9.0 (2025-06-18) 12 | ------------------ 13 | 14 | 1.8.0 (2025-05-21) 15 | ------------------ 16 | 17 | 1.7.0 (2025-04-21) 18 | ------------------ 19 | 20 | 1.6.0 (2025-04-07) 21 | ------------------ 22 | 23 | 1.5.0 (2025-04-02) 24 | ------------------ 25 | 26 | 1.4.0 (2025-02-25) 27 | ------------------ 28 | * chore: sync files (`#107 `_) 29 | * chore: sync files 30 | * style(pre-commit): autofix 31 | --------- 32 | Co-authored-by: github-actions 33 | Co-authored-by: pre-commit-ci[bot] <66853113+pre-commit-ci[bot]@users.noreply.github.com> 34 | * Contributors: awf-autoware-bot[bot] 35 | 36 | 1.3.0 (2024-11-25) 37 | ------------------ 38 | 39 | 1.2.0 (2024-10-01) 40 | ------------------ 41 | * feat(autoware_v2x_msgs): add virtual gate messages (`#77 `_) 42 | * Contributors: Takagi, Isamu 43 | 44 | 1.1.0 (2024-05-10) 45 | ------------------ 46 | -------------------------------------------------------------------------------- /autoware_sensing_msgs/package.xml: -------------------------------------------------------------------------------- 1 | 2 | 3 | 4 | autoware_sensing_msgs 5 | 1.11.0 6 | Autoware sensing messages package. 7 | 8 | Mete Fatih Cırıt 9 | Ryohsuke Mitsudome 10 | Yukihiro Saito 11 | Yutaka Kondo 12 | 13 | Apache License 2.0 14 | 15 | ament_cmake_auto 16 | rosidl_default_generators 17 | 18 | geometry_msgs 19 | sensor_msgs 20 | std_msgs 21 | 22 | rosidl_default_runtime 23 | 24 | ament_lint_auto 25 | ament_lint_common 26 | 27 | rosidl_interface_packages 28 | 29 | 30 | ament_cmake 31 | 32 | 33 | -------------------------------------------------------------------------------- /autoware_localization_msgs/package.xml: -------------------------------------------------------------------------------- 1 | 2 | 3 | 4 | autoware_localization_msgs 5 | 1.11.0 6 | Autoware localization messages package. 7 | 8 | Mete Fatih Cırıt 9 | Ryohsuke Mitsudome 10 | Yukihiro Saito 11 | Yutaka Kondo 12 | 13 | Apache License 2.0 14 | 15 | ament_cmake_auto 16 | rosidl_default_generators 17 | 18 | autoware_common_msgs 19 | geometry_msgs 20 | std_msgs 21 | 22 | rosidl_default_runtime 23 | 24 | ament_lint_auto 25 | ament_lint_common 26 | 27 | rosidl_interface_packages 28 | 29 | 30 | ament_cmake 31 | 32 | 33 | -------------------------------------------------------------------------------- /autoware_msgs/package.xml: -------------------------------------------------------------------------------- 1 | 2 | 3 | 4 | autoware_msgs 5 | 1.11.0 6 | Meta package for the autoware_msgs packages 7 | 8 | Mete Fatih Cırıt 9 | Ryohsuke Mitsudome 10 | Yutaka Kondo 11 | Apache License 2.0 12 | 13 | ament_cmake 14 | 15 | autoware_common_msgs 16 | autoware_control_msgs 17 | autoware_localization_msgs 18 | autoware_map_msgs 19 | autoware_perception_msgs 20 | autoware_planning_msgs 21 | autoware_sensing_msgs 22 | autoware_system_msgs 23 | autoware_v2x_msgs 24 | autoware_vehicle_msgs 25 | 26 | 27 | ament_cmake 28 | 29 | 30 | -------------------------------------------------------------------------------- /.github/workflows/update-codeowners-from-packages.yaml: -------------------------------------------------------------------------------- 1 | # This file is automatically synced from: 2 | # https://github.com/autowarefoundation/sync-file-templates 3 | # To make changes, update the source repository and follow the guidelines in its README. 4 | 5 | name: update-codeowners-from-packages 6 | 7 | on: 8 | schedule: 9 | - cron: 0 0 * * * 10 | workflow_dispatch: 11 | 12 | jobs: 13 | check-secret: 14 | uses: autowarefoundation/autoware-github-actions/.github/workflows/check-secret.yaml@v1 15 | secrets: 16 | secret: ${{ secrets.APP_ID }} 17 | 18 | update-codeowners-from-packages: 19 | needs: check-secret 20 | if: ${{ needs.check-secret.outputs.set == 'true' }} 21 | runs-on: ubuntu-22.04 22 | steps: 23 | - name: Generate token 24 | id: generate-token 25 | uses: tibdex/github-app-token@v2 26 | with: 27 | app_id: ${{ secrets.APP_ID }} 28 | private_key: ${{ secrets.PRIVATE_KEY }} 29 | 30 | - name: Run update-codeowners-from-packages 31 | uses: autowarefoundation/autoware-github-actions/update-codeowners-from-packages@v1 32 | with: 33 | token: ${{ steps.generate-token.outputs.token }} 34 | pr-labels: | 35 | tag:bot 36 | tag:update-codeowners-from-packages 37 | auto-merge-method: squash 38 | -------------------------------------------------------------------------------- /autoware_map_msgs/package.xml: -------------------------------------------------------------------------------- 1 | 2 | 3 | 4 | autoware_map_msgs 5 | 1.11.0 6 | Autoware map messages package. 7 | 8 | Mete Fatih Cırıt 9 | Yutaka Kondo 10 | Yukihiro Saito 11 | Ryohsuke Mitsudome 12 | 13 | Apache License 2.0 14 | 15 | Koji Minoda 16 | 17 | ament_cmake_auto 18 | rosidl_default_generators 19 | 20 | geographic_msgs 21 | geometry_msgs 22 | sensor_msgs 23 | std_msgs 24 | 25 | rosidl_default_runtime 26 | 27 | ament_lint_auto 28 | ament_lint_common 29 | 30 | rosidl_interface_packages 31 | 32 | 33 | ament_cmake 34 | 35 | 36 | -------------------------------------------------------------------------------- /autoware_v2x_msgs/README.md: -------------------------------------------------------------------------------- 1 | # autoware_v2x_msgs 2 | 3 | ## Virtual gate messages 4 | 5 | ### Overview 6 | 7 | This message represents the status of the virtual gate for passing through the area managed by the facility. 8 | The virtual gate treats area entry permission as a shared resource and controls vehicles by acquiring and releasing locks. 9 | Each facility may support different protocols, but Autoware V2X component converts each protocol and this message. 10 | This allows Autoware to handle facilities with different protocols with a unified message. 11 | 12 | ![virtual-gate-nodes](./doc/virtual-gate-nodes.drawio.svg) 13 | 14 | ### Sequence 15 | 16 | Because there is a time lag before commands are reflected, the vehicle must wait until it receives the status of the same sequence as the command it sent. 17 | Until the vehicle receives the status, treat it as if it were unlocked. 18 | 19 | ### Gates 20 | 21 | Specify the entrance and exit gate IDs. This is used to check if vehicles can pass simultaneously when multiple routes are possible within an area. 22 | If omitted, it is treated as a lock for the entire area. 23 | 24 | ### Vehicle ID 25 | 26 | This message does not include the vehicle ID, so add it in the V2X component if required by the communication protocol. 27 | And if facilities publish multiple vehicle statuses, filter to only status for own vehicle. 28 | -------------------------------------------------------------------------------- /autoware_vehicle_msgs/package.xml: -------------------------------------------------------------------------------- 1 | 2 | 3 | 4 | autoware_vehicle_msgs 5 | 1.11.0 6 | Interfaces between core Autoware vehicle components 7 | 8 | Mete Fatih Cırıt 9 | Ryohsuke Mitsudome 10 | Yukihiro Saito 11 | Yutaka Kondo 12 | 13 | Apache License 2.0 14 | 15 | beginning.fan 16 | 17 | ament_cmake_auto 18 | rosidl_default_generators 19 | 20 | autoware_planning_msgs 21 | builtin_interfaces 22 | std_msgs 23 | 24 | rosidl_default_runtime 25 | 26 | ament_lint_auto 27 | ament_lint_common 28 | 29 | rosidl_interface_packages 30 | 31 | 32 | ament_cmake 33 | 34 | 35 | -------------------------------------------------------------------------------- /autoware_perception_msgs/package.xml: -------------------------------------------------------------------------------- 1 | 2 | 3 | 4 | autoware_perception_msgs 5 | 1.11.0 6 | Autoware perception messages package. 7 | Takagi, Isamu 8 | Mete Fatih Cırıt 9 | Ryohsuke Mitsudome 10 | Yukihiro Saito 11 | Yutaka Kondo 12 | Apache License 2.0 13 | 14 | ament_cmake_auto 15 | rosidl_default_generators 16 | 17 | builtin_interfaces 18 | geometry_msgs 19 | std_msgs 20 | unique_identifier_msgs 21 | 22 | rosidl_default_runtime 23 | 24 | ament_lint_auto 25 | ament_lint_common 26 | 27 | rosidl_interface_packages 28 | 29 | 30 | ament_cmake 31 | 32 | 33 | -------------------------------------------------------------------------------- /.github/CODEOWNERS: -------------------------------------------------------------------------------- 1 | ### Automatically generated from package.xml ### 2 | autoware_common_msgs/** isamu.takagi@tier4.jp mfc@autoware.org ryohsuke.mitsudome@tier4.jp yukihiro.saito@tier4.jp yutaka.kondo@tier4.jp 3 | autoware_control_msgs/** mfc@autoware.org ryohsuke.mitsudome@tier4.jp yutaka.kondo@tier4.jp 4 | autoware_localization_msgs/** mfc@autoware.org ryohsuke.mitsudome@tier4.jp yukihiro.saito@tier4.jp yutaka.kondo@tier4.jp 5 | autoware_map_msgs/** mfc@autoware.org ryohsuke.mitsudome@tier4.jp yukihiro.saito@tier4.jp yutaka.kondo@tier4.jp 6 | autoware_msgs/** mfc@autoware.org ryohsuke.mitsudome@tier4.jp yutaka.kondo@tier4.jp 7 | autoware_perception_msgs/** isamu.takagi@tier4.jp mfc@autoware.org ryohsuke.mitsudome@tier4.jp yukihiro.saito@tier4.jp yutaka.kondo@tier4.jp 8 | autoware_planning_msgs/** isamu.takagi@tier4.jp mfc@autoware.org ryohsuke.mitsudome@tier4.jp yukihiro.saito@tier4.jp yutaka.kondo@tier4.jp 9 | autoware_sensing_msgs/** mfc@autoware.org ryohsuke.mitsudome@tier4.jp yukihiro.saito@tier4.jp yutaka.kondo@tier4.jp 10 | autoware_system_msgs/** isamu.takagi@tier4.jp mfc@autoware.org ryohsuke.mitsudome@tier4.jp yukihiro.saito@tier4.jp yutaka.kondo@tier4.jp 11 | autoware_v2x_msgs/** isamu.takagi@tier4.jp ryohsuke.mitsudome@tier4.jp yukihiro.saito@tier4.jp 12 | autoware_vehicle_msgs/** mfc@autoware.org ryohsuke.mitsudome@tier4.jp yukihiro.saito@tier4.jp yutaka.kondo@tier4.jp 13 | 14 | ### Copied from .github/CODEOWNERS-manual ### 15 | -------------------------------------------------------------------------------- /autoware_planning_msgs/package.xml: -------------------------------------------------------------------------------- 1 | 2 | 3 | 4 | autoware_planning_msgs 5 | 1.11.0 6 | Autoware planning messages package. 7 | Takagi, Isamu 8 | Mete Fatih Cırıt 9 | Ryohsuke Mitsudome 10 | Yukihiro Saito 11 | Yutaka Kondo 12 | Apache License 2.0 13 | 14 | ament_cmake_auto 15 | 16 | rosidl_default_generators 17 | 18 | autoware_common_msgs 19 | builtin_interfaces 20 | geometry_msgs 21 | nav_msgs 22 | std_msgs 23 | unique_identifier_msgs 24 | 25 | rosidl_default_runtime 26 | 27 | ament_lint_auto 28 | ament_lint_common 29 | 30 | rosidl_interface_packages 31 | 32 | 33 | ament_cmake 34 | 35 | 36 | -------------------------------------------------------------------------------- /autoware_system_msgs/package.xml: -------------------------------------------------------------------------------- 1 | 2 | 3 | 4 | autoware_system_msgs 5 | 1.11.0 6 | Autoware system messages package. 7 | Takagi, Isamu 8 | Mete Fatih Cırıt 9 | Ryohsuke Mitsudome 10 | Yukihiro Saito 11 | Yutaka Kondo 12 | Apache License 2.0 13 | 14 | ament_cmake_auto 15 | 16 | rosidl_default_generators 17 | 18 | autoware_common_msgs 19 | builtin_interfaces 20 | diagnostic_msgs 21 | geometry_msgs 22 | nav_msgs 23 | std_msgs 24 | unique_identifier_msgs 25 | 26 | rosidl_default_runtime 27 | 28 | ament_lint_auto 29 | ament_lint_common 30 | 31 | rosidl_interface_packages 32 | 33 | 34 | ament_cmake 35 | 36 | 37 | -------------------------------------------------------------------------------- /autoware_control_msgs/CHANGELOG.rst: -------------------------------------------------------------------------------- 1 | ^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^ 2 | Changelog for package autoware_control_msgs 3 | ^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^ 4 | 5 | 1.11.0 (2025-10-23) 6 | ------------------- 7 | 8 | 1.10.0 (2025-07-18) 9 | ------------------- 10 | 11 | 1.9.0 (2025-06-18) 12 | ------------------ 13 | 14 | 1.8.0 (2025-05-21) 15 | ------------------ 16 | * chore: fix email domain (`#133 `_) 17 | * chore: update maintainers (`#132 `_) 18 | * Contributors: Mete Fatih Cırıt 19 | 20 | 1.7.0 (2025-04-21) 21 | ------------------ 22 | 23 | 1.6.0 (2025-04-07) 24 | ------------------ 25 | 26 | 1.5.0 (2025-04-02) 27 | ------------------ 28 | 29 | 1.4.0 (2025-02-25) 30 | ------------------ 31 | * fix(autoware_msgs): fix links to issues in CHANGELOG.rst files (`#108 `_) 32 | * Contributors: Esteve Fernandez 33 | 34 | 1.3.0 (2024-11-25) 35 | ------------------ 36 | 37 | 1.2.0 (2024-10-01) 38 | ------------------ 39 | 40 | 1.1.0 (2024-05-10) 41 | ------------------ 42 | * chore: update `package.xml` and fix `CMakeLists.txt` (`#91 `_) 43 | update package.xml and fix cmakefiles 44 | * feat(control-messages): add control messages (`#11 `_) 45 | * Contributors: M. Fatih Cırıt, Yutaka Kondo 46 | -------------------------------------------------------------------------------- /.github/workflows/comment-on-pr.yaml: -------------------------------------------------------------------------------- 1 | # This file is automatically synced from: 2 | # https://github.com/autowarefoundation/sync-file-templates 3 | # To make changes, update the source repository and follow the guidelines in its README. 4 | 5 | name: comment-on-pr 6 | on: 7 | pull_request_target: 8 | 9 | jobs: 10 | comment-on-pr: 11 | runs-on: ubuntu-22.04 12 | permissions: 13 | pull-requests: write 14 | steps: 15 | - name: Check out repository 16 | uses: actions/checkout@v4 17 | 18 | - name: Initial PR comment 19 | uses: marocchino/sticky-pull-request-comment@v2 20 | with: 21 | message: | 22 | Thank you for contributing to the Autoware project! 23 | 24 | 🚧 If your pull request is in progress, [switch it to draft mode](https://docs.github.com/en/pull-requests/collaborating-with-pull-requests/proposing-changes-to-your-work-with-pull-requests/changing-the-stage-of-a-pull-request#converting-a-pull-request-to-a-draft). 25 | 26 | Please ensure: 27 | - You've checked our [contribution guidelines](https://autowarefoundation.github.io/autoware-documentation/main/contributing/). 28 | - Your PR follows our [pull request guidelines](https://autowarefoundation.github.io/autoware-documentation/main/contributing/pull-request-guidelines/). 29 | - All required CI checks pass before [marking the PR ready for review](https://docs.github.com/en/pull-requests/collaborating-with-pull-requests/proposing-changes-to-your-work-with-pull-requests/changing-the-stage-of-a-pull-request#marking-a-pull-request-as-ready-for-review). 30 | -------------------------------------------------------------------------------- /.github/ISSUE_TEMPLATE/task.yaml: -------------------------------------------------------------------------------- 1 | # This file is automatically synced from: 2 | # https://github.com/autowarefoundation/sync-file-templates 3 | # To make changes, update the source repository and follow the guidelines in its README. 4 | 5 | name: Task 6 | description: Plan a task 7 | body: 8 | - type: checkboxes 9 | attributes: 10 | label: Checklist 11 | description: Confirm the following items before proceeding. If one cannot be satisfied, create a discussion thread instead. 12 | options: 13 | - label: I've read the [contribution guidelines](https://github.com/autowarefoundation/autoware/blob/main/CONTRIBUTING.md). 14 | required: true 15 | - label: I've searched other issues and no duplicate issues were found. 16 | required: true 17 | - label: I've agreed with the maintainers that I can plan this task. 18 | required: true 19 | 20 | - type: textarea 21 | attributes: 22 | label: Description 23 | description: Write a brief description of the task. 24 | validations: 25 | required: true 26 | 27 | - type: textarea 28 | attributes: 29 | label: Purpose 30 | description: Describe the purpose of the task. 31 | validations: 32 | required: true 33 | 34 | - type: textarea 35 | attributes: 36 | label: Possible approaches 37 | description: Describe possible approaches for the task. 38 | validations: 39 | required: true 40 | 41 | - type: textarea 42 | attributes: 43 | label: Definition of done 44 | description: Write the definition of done for the task. 45 | validations: 46 | required: true 47 | -------------------------------------------------------------------------------- /.github/workflows/bump-new-version.yaml: -------------------------------------------------------------------------------- 1 | name: bump-new-version 2 | 3 | on: 4 | workflow_dispatch: 5 | inputs: 6 | source_branch: 7 | description: The branch to merge from, which can be from the original or a forked repository. 8 | required: true 9 | default: main 10 | target_branch: 11 | description: The branch to merge into, owned by the original repository owner. 12 | required: true 13 | default: main 14 | bump_version: 15 | description: The type of version bump to apply. 16 | required: true 17 | default: patch 18 | type: choice 19 | options: 20 | - patch 21 | - minor 22 | - major 23 | source_repository_owner: 24 | description: The owner of the source repository (organization or user). 25 | required: false 26 | default: autowarefoundation 27 | 28 | jobs: 29 | update-versions: 30 | runs-on: ubuntu-22.04 31 | steps: 32 | - name: Generate token 33 | id: generate-token 34 | uses: actions/create-github-app-token@v1 35 | with: 36 | app-id: ${{ secrets.APP_ID }} 37 | private-key: ${{ secrets.PRIVATE_KEY }} 38 | 39 | - name: Run 40 | uses: autowarefoundation/autoware-github-actions/bump-new-version@v1 41 | with: 42 | github_token: ${{ steps.generate-token.outputs.token }} 43 | source_branch: ${{ github.event.inputs.source_branch }} 44 | target_branch: ${{ github.event.inputs.target_branch }} 45 | bump_version: ${{ github.event.inputs.bump_version }} 46 | source_repository_owner: ${{ github.event.inputs.source_repository_owner }} 47 | -------------------------------------------------------------------------------- /.github/sync-files.yaml: -------------------------------------------------------------------------------- 1 | - repository: autowarefoundation/sync-file-templates 2 | source-dir: sources 3 | files: 4 | - source: CODE_OF_CONDUCT.md 5 | - source: CONTRIBUTING.md 6 | - source: DISCLAIMER.md 7 | - source: LICENSE 8 | - source: .github/ISSUE_TEMPLATE/bug.yaml 9 | - source: .github/ISSUE_TEMPLATE/config.yml 10 | - source: .github/ISSUE_TEMPLATE/task.yaml 11 | - source: .github/pull_request_template.md 12 | - source: .github/dependabot.yaml 13 | - source: .github/stale.yml 14 | - source: .github/workflows/comment-on-pr.yaml 15 | - source: .github/workflows/github-release.yaml 16 | - source: .github/workflows/pre-commit.yaml 17 | - source: .github/workflows/pre-commit-optional.yaml 18 | - source: .github/workflows/semantic-pull-request.yaml 19 | - source: .github/workflows/spell-check-daily.yaml 20 | - source: .github/workflows/spell-check-differential.yaml 21 | - source: .github/workflows/sync-files.yaml 22 | - source: .github/workflows/update-codeowners-from-packages.yaml 23 | - source: .markdown-link-check.json 24 | - source: .markdownlint.yaml 25 | - source: .pre-commit-config.yaml 26 | - source: .pre-commit-config-optional.yaml 27 | - source: .prettierignore 28 | - source: .prettierrc.yaml 29 | - source: .yamllint.yaml 30 | - source: .github/workflows/build-and-test.yaml 31 | pre-commands: | 32 | sed -i '/build-depends-repos/d' {source} 33 | - source: .github/workflows/build-and-test-differential.yaml 34 | pre-commands: | 35 | sed -i '/build-depends-repos/d' {source} 36 | 37 | # sed: The stream editor command, used for parsing and transforming text. 38 | # -i: Edit files in place. 39 | # '/build-depends-repos/d': Delete the line containing 'build-depends-repos'. 40 | -------------------------------------------------------------------------------- /autoware_localization_msgs/CHANGELOG.rst: -------------------------------------------------------------------------------- 1 | ^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^ 2 | Changelog for package autoware_localization_msgs 3 | ^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^ 4 | 5 | 1.11.0 (2025-10-23) 6 | ------------------- 7 | 8 | 1.10.0 (2025-07-18) 9 | ------------------- 10 | * chore: update maintainer for autoware_msgs packages (`#143 `_) 11 | * Contributors: Ryohsuke Mitsudome 12 | 13 | 1.9.0 (2025-06-18) 14 | ------------------ 15 | * feat(autoware_localization_msgs): add InitializeLocalization service (`#139 `_) 16 | * feat: add InitializeLocalization service 17 | * fix: add service file in CMakeLists.txt 18 | --------- 19 | * Contributors: Ryohsuke Mitsudome 20 | 21 | 1.8.0 (2025-05-21) 22 | ------------------ 23 | * chore: fix email domain (`#133 `_) 24 | * chore: update maintainers (`#132 `_) 25 | * Contributors: Mete Fatih Cırıt 26 | 27 | 1.7.0 (2025-04-21) 28 | ------------------ 29 | 30 | 1.6.0 (2025-04-07) 31 | ------------------ 32 | 33 | 1.5.0 (2025-04-02) 34 | ------------------ 35 | 36 | 1.4.0 (2025-02-25) 37 | ------------------ 38 | * fix(autoware_msgs): fix links to issues in CHANGELOG.rst files (`#108 `_) 39 | * Contributors: Esteve Fernandez 40 | 41 | 1.3.0 (2024-11-25) 42 | ------------------ 43 | 44 | 1.2.0 (2024-10-01) 45 | ------------------ 46 | 47 | 1.1.0 (2024-05-10) 48 | ------------------ 49 | * chore: update `package.xml` and fix `CMakeLists.txt` (`#91 `_) 50 | update package.xml and fix cmakefiles 51 | * feat(localization-messages): add autoware_localization_msgs (`#16 `_) 52 | * Contributors: M. Fatih Cırıt, Yutaka Kondo 53 | -------------------------------------------------------------------------------- /autoware_common_msgs/CHANGELOG.rst: -------------------------------------------------------------------------------- 1 | ^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^ 2 | Changelog for package autoware_common_msgs 3 | ^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^ 4 | 5 | 1.11.0 (2025-10-23) 6 | ------------------- 7 | 8 | 1.10.0 (2025-07-18) 9 | ------------------- 10 | * chore: update maintainer for autoware_msgs packages (`#143 `_) 11 | * Contributors: Ryohsuke Mitsudome 12 | 13 | 1.9.0 (2025-06-18) 14 | ------------------ 15 | 16 | 1.8.0 (2025-05-21) 17 | ------------------ 18 | * chore: fix email domain (`#133 `_) 19 | * chore: update maintainers (`#132 `_) 20 | * Contributors: Mete Fatih Cırıt 21 | 22 | 1.7.0 (2025-04-21) 23 | ------------------ 24 | 25 | 1.6.0 (2025-04-07) 26 | ------------------ 27 | 28 | 1.5.0 (2025-04-02) 29 | ------------------ 30 | 31 | 1.4.0 (2025-02-25) 32 | ------------------ 33 | * fix(autoware_msgs): fix links to issues in CHANGELOG.rst files (`#108 `_) 34 | * Contributors: Esteve Fernandez 35 | 36 | 1.3.0 (2024-11-25) 37 | ------------------ 38 | 39 | 1.2.0 (2024-10-01) 40 | ------------------ 41 | 42 | 1.1.0 (2024-05-10) 43 | ------------------ 44 | * chore: update `package.xml` and fix `CMakeLists.txt` (`#91 `_) 45 | update package.xml and fix cmakefiles 46 | * build: package.xml dependencies (`#60 `_) 47 | * mark rosidl_default_generators as 48 | * add missing rosidl_default_runtime 49 | --------- 50 | * feat(autoware_common_msgs): add autoware common messages (`#37 `_) 51 | * feat(autoware_common_msgs): add autoware common messages 52 | * fix: fix dependency 53 | * Contributors: Takagi, Isamu, Vincent Richard, Yutaka Kondo 54 | -------------------------------------------------------------------------------- /autoware_control_msgs/README.md: -------------------------------------------------------------------------------- 1 | # autoware_control_msgs 2 | 3 | ## Design 4 | 5 | Vehicle dimensions and axes: 6 | 7 | ### Lateral.msg 8 | 9 | Defines a lateral control command message with a timestamp. 10 | 11 | The message conveys the expectation for vehicle's lateral state to be in the given configuration in the time point: `control_time`. 12 | 13 | - The field `steering_tire_angle` is required. 14 | - The field `steering_tire_rotation_rate` is optional but may be required by some nodes. 15 | - If this field is used, `is_defined_steering_tire_rotation_rate` must be set `true`. 16 | 17 | ### Longitudinal.msg 18 | 19 | Defines a longitudinal control command message with a timestamp. 20 | 21 | The message conveys the expectation for vehicle's longitudinal state to be in the given configuration in the time point: `control_time`. 22 | 23 | - The field `velocity` is required. 24 | - The field `acceleration` is optional but may be required by some nodes. 25 | - If this field is used, `is_defined_acceleration` must be set `true`. 26 | - The field `jerk` is optional but may be required by some nodes. 27 | - If this field is used, `is_defined_jerk` must be set `true`. 28 | 29 | ### Control.msg 30 | 31 | Defines a control command message, combining `Lateral.msg` and `Longitudinal.msg`. 32 | 33 | The message conveys the expectation for vehicle's combined control state to be in the given configuration in the time point: `control_time`. 34 | 35 | If the `control_time` is defined, the `control_time` field in the `lateral` and `longitudinal` fields are ignored. 36 | 37 | ### ControlHorizon.msg 38 | 39 | Defines a control commands array calculated for a future horizon. 40 | 41 | - Control messages are ordered from near to far future `[0 to N)` with `time_step_ms` increments. 42 | - First element of the array contains the control signals at the `control_time` of this message. 43 | - The `control_time` field in each element of the controls array can be ignored. 44 | -------------------------------------------------------------------------------- /autoware_system_msgs/CHANGELOG.rst: -------------------------------------------------------------------------------- 1 | ^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^ 2 | Changelog for package autoware_system_msgs 3 | ^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^ 4 | 5 | 1.11.0 (2025-10-23) 6 | ------------------- 7 | 8 | 1.10.0 (2025-07-18) 9 | ------------------- 10 | * chore: update maintainer for autoware_msgs packages (`#143 `_) 11 | * Contributors: Ryohsuke Mitsudome 12 | 13 | 1.9.0 (2025-06-18) 14 | ------------------ 15 | * feat(autoware_system_msgs): move services from tier4_system_msgs (`#140 `_) 16 | * Contributors: Ryohsuke Mitsudome 17 | 18 | 1.8.0 (2025-05-21) 19 | ------------------ 20 | * chore: fix email domain (`#133 `_) 21 | * chore: update maintainers (`#132 `_) 22 | * Contributors: Mete Fatih Cırıt 23 | 24 | 1.7.0 (2025-04-21) 25 | ------------------ 26 | 27 | 1.6.0 (2025-04-07) 28 | ------------------ 29 | 30 | 1.5.0 (2025-04-02) 31 | ------------------ 32 | 33 | 1.4.0 (2025-02-25) 34 | ------------------ 35 | * fix(autoware_msgs): fix links to issues in CHANGELOG.rst files (`#108 `_) 36 | * Contributors: Esteve Fernandez 37 | 38 | 1.3.0 (2024-11-25) 39 | ------------------ 40 | 41 | 1.2.0 (2024-10-01) 42 | ------------------ 43 | 44 | 1.1.0 (2024-05-10) 45 | ------------------ 46 | * chore: update `package.xml` and fix `CMakeLists.txt` (`#91 `_) 47 | update package.xml and fix cmakefiles 48 | * fix: add system msg (`#79 `_) 49 | * fix:add system msg 50 | * fix:add system msgs 51 | * fix:add system msgs 52 | * fix:add system msgs 53 | * style(pre-commit): autofix 54 | --------- 55 | Co-authored-by: pre-commit-ci[bot] <66853113+pre-commit-ci[bot]@users.noreply.github.com> 56 | * Contributors: Yutaka Kondo, shulanbushangshu 57 | -------------------------------------------------------------------------------- /autoware_sensing_msgs/CHANGELOG.rst: -------------------------------------------------------------------------------- 1 | ^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^ 2 | Changelog for package autoware_sensing_msgs 3 | ^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^ 4 | 5 | 1.11.0 (2025-10-23) 6 | ------------------- 7 | 8 | 1.10.0 (2025-07-18) 9 | ------------------- 10 | * feat(autoware_sensing_msgs): add PointCloud meta info msgs (`#142 `_) 11 | Co-authored-by: Mete Fatih Cırıt 12 | * chore: update maintainer for autoware_msgs packages (`#143 `_) 13 | * Contributors: Amadeusz Szymko, Ryohsuke Mitsudome 14 | 15 | 1.9.0 (2025-06-18) 16 | ------------------ 17 | 18 | 1.8.0 (2025-05-21) 19 | ------------------ 20 | * chore: fix email domain (`#133 `_) 21 | * chore: update maintainers (`#132 `_) 22 | * Contributors: Mete Fatih Cırıt 23 | 24 | 1.7.0 (2025-04-21) 25 | ------------------ 26 | * feat(autoware_sensing_msgs): implement the proposed universal radar messages (`#120 `_) 27 | Co-authored-by: Taekjin LEE 28 | Co-authored-by: Mete Fatih Cırıt 29 | * Contributors: Kenzo Lobos Tsunekawa 30 | 31 | 1.6.0 (2025-04-07) 32 | ------------------ 33 | 34 | 1.5.0 (2025-04-02) 35 | ------------------ 36 | 37 | 1.4.0 (2025-02-25) 38 | ------------------ 39 | * fix(autoware_msgs): fix links to issues in CHANGELOG.rst files (`#108 `_) 40 | * Contributors: Esteve Fernandez 41 | 42 | 1.3.0 (2024-11-25) 43 | ------------------ 44 | 45 | 1.2.0 (2024-10-01) 46 | ------------------ 47 | 48 | 1.1.0 (2024-05-10) 49 | ------------------ 50 | * chore: update `package.xml` and fix `CMakeLists.txt` (`#91 `_) 51 | update package.xml and fix cmakefiles 52 | * feat(sensing-messages): add sensing messages (`#24 `_) 53 | * feat(sensing-messages): add sensing messages 54 | * Contributors: M. Fatih Cırıt, Yutaka Kondo 55 | -------------------------------------------------------------------------------- /.github/workflows/github-release.yaml: -------------------------------------------------------------------------------- 1 | # This file is automatically synced from: 2 | # https://github.com/autowarefoundation/sync-file-templates 3 | # To make changes, update the source repository and follow the guidelines in its README. 4 | 5 | name: github-release 6 | 7 | on: 8 | push: 9 | tags: 10 | - "[0-9]+.[0-9]+.[0-9]+" 11 | workflow_dispatch: 12 | inputs: 13 | tag-name: 14 | description: The name of the tag to release 15 | type: string 16 | required: true 17 | 18 | jobs: 19 | github-release: 20 | runs-on: ubuntu-22.04 21 | steps: 22 | - name: Set tag name 23 | id: set-tag-name 24 | run: | 25 | if [ "${{ github.event_name }}" = "workflow_dispatch" ]; then 26 | REF_NAME="${{ github.event.inputs.tag-name }}" 27 | else 28 | REF_NAME="${{ github.ref_name }}" 29 | fi 30 | 31 | echo "tag-name=$REF_NAME" >> $GITHUB_OUTPUT 32 | 33 | - name: Check out repository 34 | uses: actions/checkout@v4 35 | with: 36 | fetch-depth: 0 37 | ref: ${{ steps.set-tag-name.outputs.tag-name }} 38 | 39 | - name: Run generate-changelog 40 | id: generate-changelog 41 | uses: autowarefoundation/autoware-github-actions/generate-changelog@v1 42 | with: 43 | git-cliff-args: --tag-pattern "^(\d+)\.(\d+)\.(\d+)$" --latest 44 | 45 | - name: Select verb 46 | id: select-verb 47 | run: | 48 | has_previous_draft=$(gh release view --json isDraft -q ".isDraft" "${{ steps.set-tag-name.outputs.tag-name }}") || true 49 | 50 | verb=create 51 | if [ "$has_previous_draft" = "true" ]; then 52 | verb=edit 53 | fi 54 | 55 | echo "verb=$verb" >> $GITHUB_OUTPUT 56 | env: 57 | GITHUB_TOKEN: ${{ secrets.GITHUB_TOKEN }} 58 | 59 | - name: Release to GitHub 60 | run: | 61 | gh release ${{ steps.select-verb.outputs.verb }} "${{ steps.set-tag-name.outputs.tag-name }}" \ 62 | --draft \ 63 | --title "Release ${{ steps.set-tag-name.outputs.tag-name }}" \ 64 | --notes "$NOTES" 65 | env: 66 | GITHUB_TOKEN: ${{ secrets.GITHUB_TOKEN }} 67 | NOTES: ${{ steps.generate-changelog.outputs.changelog }} 68 | -------------------------------------------------------------------------------- /.github/ISSUE_TEMPLATE/bug.yaml: -------------------------------------------------------------------------------- 1 | # This file is automatically synced from: 2 | # https://github.com/autowarefoundation/sync-file-templates 3 | # To make changes, update the source repository and follow the guidelines in its README. 4 | 5 | name: Bug 6 | description: Report a bug 7 | body: 8 | - type: checkboxes 9 | attributes: 10 | label: Checklist 11 | description: Confirm the following items before proceeding. If one cannot be satisfied, create a discussion thread instead. 12 | options: 13 | - label: I've read the [contribution guidelines](https://github.com/autowarefoundation/autoware/blob/main/CONTRIBUTING.md). 14 | required: true 15 | - label: I've searched other issues and no duplicate issues were found. 16 | required: true 17 | - label: I'm convinced that this is not my fault but a bug. 18 | required: true 19 | 20 | - type: textarea 21 | attributes: 22 | label: Description 23 | description: Write a brief description of the bug. 24 | validations: 25 | required: true 26 | 27 | - type: textarea 28 | attributes: 29 | label: Expected behavior 30 | description: Describe the expected behavior. 31 | validations: 32 | required: true 33 | 34 | - type: textarea 35 | attributes: 36 | label: Actual behavior 37 | description: Describe the actual behavior. 38 | validations: 39 | required: true 40 | 41 | - type: textarea 42 | attributes: 43 | label: Steps to reproduce 44 | description: Write the steps to reproduce the bug. 45 | placeholder: |- 46 | 1. 47 | 2. 48 | 3. 49 | validations: 50 | required: true 51 | 52 | - type: textarea 53 | attributes: 54 | label: Versions 55 | description: Provide the version information. You can omit this if you believe it's irrelevant. 56 | placeholder: |- 57 | - OS: 58 | - ROS 2: 59 | - Autoware: 60 | validations: 61 | required: false 62 | 63 | - type: textarea 64 | attributes: 65 | label: Possible causes 66 | description: Write the possible causes if you have any ideas. 67 | validations: 68 | required: false 69 | 70 | - type: textarea 71 | attributes: 72 | label: Additional context 73 | description: Add any other additional context if it exists. 74 | validations: 75 | required: false 76 | -------------------------------------------------------------------------------- /.github/workflows/build-and-test.yaml: -------------------------------------------------------------------------------- 1 | # This file is automatically synced from: 2 | # https://github.com/autowarefoundation/sync-file-templates 3 | # To make changes, update the source repository and follow the guidelines in its README. 4 | 5 | name: build-and-test 6 | 7 | on: 8 | push: 9 | schedule: 10 | - cron: 0 0 * * * 11 | workflow_dispatch: 12 | 13 | jobs: 14 | build-and-test: 15 | if: ${{ github.event_name != 'push' || github.ref_name == github.event.repository.default_branch }} 16 | runs-on: ubuntu-22.04 17 | container: ${{ matrix.container }} 18 | strategy: 19 | fail-fast: false 20 | matrix: 21 | rosdistro: 22 | - humble 23 | - jazzy 24 | include: 25 | - rosdistro: humble 26 | container: ros:humble 27 | - rosdistro: jazzy 28 | container: ros:jazzy 29 | steps: 30 | - name: Check out repository 31 | uses: actions/checkout@v4 32 | with: 33 | fetch-depth: 1 34 | 35 | - name: Show disk space before the tasks 36 | run: df -h 37 | 38 | - name: Remove exec_depend 39 | uses: autowarefoundation/autoware-github-actions/remove-exec-depend@v1 40 | 41 | - name: Get self packages 42 | id: get-self-packages 43 | uses: autowarefoundation/autoware-github-actions/get-self-packages@v1 44 | 45 | - name: Build 46 | if: ${{ steps.get-self-packages.outputs.self-packages != '' }} 47 | uses: autowarefoundation/autoware-github-actions/colcon-build@v1 48 | with: 49 | rosdistro: ${{ matrix.rosdistro }} 50 | target-packages: ${{ steps.get-self-packages.outputs.self-packages }} 51 | 52 | - name: Test 53 | if: ${{ steps.get-self-packages.outputs.self-packages != '' }} 54 | id: test 55 | uses: autowarefoundation/autoware-github-actions/colcon-test@v1 56 | with: 57 | rosdistro: ${{ matrix.rosdistro }} 58 | target-packages: ${{ steps.get-self-packages.outputs.self-packages }} 59 | 60 | - name: Upload coverage to CodeCov 61 | if: ${{ steps.test.outputs.coverage-report-files != '' }} 62 | uses: codecov/codecov-action@v5 63 | with: 64 | files: ${{ steps.test.outputs.coverage-report-files }} 65 | fail_ci_if_error: false 66 | verbose: true 67 | flags: total 68 | 69 | - name: Show disk space after the tasks 70 | run: df -h 71 | -------------------------------------------------------------------------------- /autoware_map_msgs/README.md: -------------------------------------------------------------------------------- 1 | # autoware_map_msgs 2 | 3 | ## AreaInfo.msg 4 | 5 | The message represents an area information. This is intended to be used as a query for partial / differential map loading (see `GetPartialPointCloudMap.srv` and `GetDifferentialPointCloudMap.srv` section). 6 | 7 | ## PointCloudMapCellWithID.msg 8 | 9 | The message contains a pointcloud data attached with an ID. 10 | 11 | ## PointCloudMapCellMetaDataWithID.msg 12 | 13 | The message contains a pointcloud meta data attached with an ID. These IDs are intended to be used as a query for selected PCD map loading (see `GetSelectedPointCloudMap.srv` section). 14 | 15 | ## MapProjectorInfo.msg 16 | 17 | The message contains the information required to project global coordinates to local coordinates used by Autoware, which includes the name of the projection method and the parameters for the projection. 18 | For further information, please refer to the readme of [map_projection_loader](https://github.com/autowarefoundation/autoware.universe/blob/main/map/autoware_map_projection_loader/README.md) in Autoware Universe. 19 | 20 | ## GetPartialPointCloudMap.srv 21 | 22 | Given an area query (`AreaInfo`), the response is expected to contain the PCD maps (each of which attached with unique ID) whose area overlaps with the query. 23 | 24 | drawing 25 | 26 | ## GetDifferentialPointCloudMap.srv 27 | 28 | Given an area query and the IDs that the client node already has, the response is expected to contain the PCD maps (each of which attached with unique ID) that... 29 | 30 | - overlaps with the area query 31 | - is not possessed by the client node 32 | 33 | Let $X_0$ be a set of PCD map ID that the client node has, $X_1$ be a set of PCD map ID that overlaps with the area query, ${\rm pcd}(id)$ be a function that returns PCD data that corresponds to ID $id$. In this case, the response would be 34 | 35 | - `loaded_pcds`: $\lbrace [id,{\rm pcd}(id)]~|~id \in X_1 \backslash X_0 \rbrace$ 36 | - `ids_to_remove`: $\lbrace id~|~id \in X_0 \backslash X_1 \rbrace$ 37 | 38 | ( $x \in A\backslash B \iff x \in A \wedge x \notin B$ ) 39 | 40 | drawing 41 | 42 | ## GetSelectedPointCloudMap.srv 43 | 44 | Given IDs query, the response is expected to contain the PCD maps (each of which attached with unique ID) specified by query. Before using this interface, the client is expected to receive the `PointCloudMapCellMetaDataWithID.msg` metadata to retrieve information about IDs. 45 | -------------------------------------------------------------------------------- /DISCLAIMER.md: -------------------------------------------------------------------------------- 1 | DISCLAIMER 2 | 3 | “Autoware” will be provided by The Autoware Foundation under the Apache License 2.0. 4 | This “DISCLAIMER” will be applied to all users of Autoware (a “User” or “Users”) with 5 | the Apache License 2.0 and Users shall hereby approve and acknowledge all the contents 6 | specified in this disclaimer below and will be deemed to consent to this 7 | disclaimer without any objection upon utilizing or downloading Autoware. 8 | 9 | Disclaimer and Waiver of Warranties 10 | 11 | 1. AUTOWARE FOUNDATION MAKES NO REPRESENTATION OR WARRANTY OF ANY KIND, 12 | EXPRESS OR IMPLIED, WITH RESPECT TO PROVIDING AUTOWARE (the “Service”) 13 | including but not limited to any representation or warranty (i) of fitness or 14 | suitability for a particular purpose contemplated by the Users, (ii) of the 15 | expected functions, commercial value, accuracy, or usefulness of the Service, 16 | (iii) that the use by the Users of the Service complies with the laws and 17 | regulations applicable to the Users or any internal rules established by 18 | industrial organizations, (iv) that the Service will be free of interruption or 19 | defects, (v) of the non-infringement of any third party's right and (vi) the 20 | accuracy of the content of the Services and the software itself. 21 | 22 | 2. The Autoware Foundation shall not be liable for any damage incurred by the 23 | User that are attributable to the Autoware Foundation for any reasons 24 | whatsoever. UNDER NO CIRCUMSTANCES SHALL THE AUTOWARE FOUNDATION BE LIABLE FOR 25 | INCIDENTAL, INDIRECT, SPECIAL OR FUTURE DAMAGES OR LOSS OF PROFITS. 26 | 27 | 3. A User shall be entirely responsible for the content posted by the User and 28 | its use of any content of the Service or the Website. If the User is held 29 | responsible in a civil action such as a claim for damages or even in a criminal 30 | case, the Autoware Foundation and member companies, governments and academic & 31 | non-profit organizations and their directors, officers, employees and agents 32 | (collectively, the “Indemnified Parties”) shall be completely discharged from 33 | any rights or assertions the User may have against the Indemnified Parties, or 34 | from any legal action, litigation or similar procedures. 35 | 36 | Indemnity 37 | 38 | A User shall indemnify and hold the Indemnified Parties harmless from any of 39 | their damages, losses, liabilities, costs or expenses (including attorneys' 40 | fees or criminal compensation), or any claims or demands made against the 41 | Indemnified Parties by any third party, due to or arising out of, or in 42 | connection with utilizing Autoware (including the representations and 43 | warranties), the violation of applicable Product Liability Law of each country 44 | (including criminal case) or violation of any applicable laws by the Users, or 45 | the content posted by the User or its use of any content of the Service or the 46 | Website. 47 | -------------------------------------------------------------------------------- /.github/workflows/build-and-test-differential.yaml: -------------------------------------------------------------------------------- 1 | # This file is automatically synced from: 2 | # https://github.com/autowarefoundation/sync-file-templates 3 | # To make changes, update the source repository and follow the guidelines in its README. 4 | 5 | name: build-and-test-differential 6 | 7 | on: 8 | pull_request: 9 | types: 10 | - opened 11 | - synchronize 12 | - reopened 13 | - labeled 14 | 15 | jobs: 16 | make-sure-label-is-present: 17 | uses: autowarefoundation/autoware-github-actions/.github/workflows/make-sure-label-is-present.yaml@v1 18 | with: 19 | label: run:build-and-test-differential 20 | 21 | build-and-test-differential: 22 | needs: make-sure-label-is-present 23 | if: ${{ needs.make-sure-label-is-present.outputs.result == 'true' }} 24 | runs-on: ubuntu-22.04 25 | container: ${{ matrix.container }} 26 | strategy: 27 | fail-fast: false 28 | matrix: 29 | rosdistro: 30 | - humble 31 | - jazzy 32 | include: 33 | - rosdistro: humble 34 | container: ros:humble 35 | - rosdistro: jazzy 36 | container: ros:jazzy 37 | steps: 38 | - name: Set PR fetch depth 39 | run: echo "PR_FETCH_DEPTH=$(( ${{ github.event.pull_request.commits }} + 1 ))" >> "${GITHUB_ENV}" 40 | 41 | - name: Checkout PR branch and all PR commits 42 | uses: actions/checkout@v4 43 | with: 44 | ref: ${{ github.event.pull_request.head.sha }} 45 | fetch-depth: ${{ env.PR_FETCH_DEPTH }} 46 | 47 | - name: Show disk space before the tasks 48 | run: df -h 49 | 50 | - name: Remove exec_depend 51 | uses: autowarefoundation/autoware-github-actions/remove-exec-depend@v1 52 | 53 | - name: Get modified packages 54 | id: get-modified-packages 55 | uses: autowarefoundation/autoware-github-actions/get-modified-packages@v1 56 | 57 | - name: Build 58 | if: ${{ steps.get-modified-packages.outputs.modified-packages != '' }} 59 | uses: autowarefoundation/autoware-github-actions/colcon-build@v1 60 | with: 61 | rosdistro: ${{ matrix.rosdistro }} 62 | target-packages: ${{ steps.get-modified-packages.outputs.modified-packages }} 63 | 64 | - name: Test 65 | id: test 66 | if: ${{ steps.get-modified-packages.outputs.modified-packages != '' }} 67 | uses: autowarefoundation/autoware-github-actions/colcon-test@v1 68 | with: 69 | rosdistro: ${{ matrix.rosdistro }} 70 | target-packages: ${{ steps.get-modified-packages.outputs.modified-packages }} 71 | 72 | - name: Upload coverage to CodeCov 73 | if: ${{ steps.test.outputs.coverage-report-files != '' }} 74 | uses: codecov/codecov-action@v5 75 | with: 76 | files: ${{ steps.test.outputs.coverage-report-files }} 77 | fail_ci_if_error: false 78 | verbose: true 79 | flags: differential 80 | 81 | - name: Show disk space after the tasks 82 | run: df -h 83 | -------------------------------------------------------------------------------- /.pre-commit-config.yaml: -------------------------------------------------------------------------------- 1 | # This file is automatically synced from: 2 | # https://github.com/autowarefoundation/sync-file-templates 3 | # To make changes, update the source repository and follow the guidelines in its README. 4 | 5 | # https://pre-commit.ci/#configuration 6 | ci: 7 | autofix_commit_msg: "style(pre-commit): autofix" 8 | # we already have our own daily update mechanism, we set this to quarterly 9 | autoupdate_schedule: quarterly 10 | autoupdate_commit_msg: "ci(pre-commit): quarterly autoupdate" 11 | 12 | repos: 13 | - repo: https://github.com/pre-commit/pre-commit-hooks 14 | rev: v5.0.0 15 | hooks: 16 | - id: check-json 17 | - id: check-merge-conflict 18 | - id: check-toml 19 | - id: check-xml 20 | - id: check-yaml 21 | args: [--unsafe] 22 | - id: detect-private-key 23 | - id: end-of-file-fixer 24 | - id: mixed-line-ending 25 | - id: trailing-whitespace 26 | args: [--markdown-linebreak-ext=md] 27 | 28 | - repo: https://github.com/igorshubovych/markdownlint-cli 29 | rev: v0.43.0 30 | hooks: 31 | - id: markdownlint 32 | args: [-c, .markdownlint.yaml, --fix] 33 | 34 | - repo: https://github.com/pre-commit/mirrors-prettier 35 | rev: v4.0.0-alpha.8 36 | hooks: 37 | - id: prettier 38 | 39 | - repo: https://github.com/adrienverge/yamllint 40 | rev: v1.35.1 41 | hooks: 42 | - id: yamllint 43 | 44 | - repo: https://github.com/autowarefoundation/autoware-guideline-check 45 | rev: 0.1.0 46 | hooks: 47 | - id: check-package-depends 48 | 49 | - repo: https://github.com/tier4/pre-commit-hooks-ros 50 | rev: v0.10.0 51 | hooks: 52 | - id: flake8-ros 53 | - id: prettier-xacro 54 | - id: prettier-launch-xml 55 | - id: prettier-package-xml 56 | - id: ros-include-guard 57 | - id: sort-package-xml 58 | 59 | - repo: https://github.com/shellcheck-py/shellcheck-py 60 | rev: v0.10.0.1 61 | hooks: 62 | - id: shellcheck 63 | 64 | - repo: https://github.com/scop/pre-commit-shfmt 65 | rev: v3.10.0-2 66 | hooks: 67 | - id: shfmt 68 | args: [-w, -s, -i=4] 69 | 70 | - repo: https://github.com/pycqa/isort 71 | rev: 5.13.2 72 | hooks: 73 | - id: isort 74 | 75 | - repo: https://github.com/psf/black 76 | rev: 24.10.0 77 | hooks: 78 | - id: black 79 | args: [--line-length=100] 80 | 81 | - repo: https://github.com/pre-commit/mirrors-clang-format 82 | rev: v19.1.6 83 | hooks: 84 | - id: clang-format 85 | types_or: [c++, c, cuda] 86 | 87 | - repo: https://github.com/cpplint/cpplint 88 | rev: 2.0.0 89 | hooks: 90 | - id: cpplint 91 | args: [--quiet] 92 | exclude: .cu 93 | 94 | - repo: https://github.com/python-jsonschema/check-jsonschema 95 | rev: 0.30.0 96 | hooks: 97 | - id: check-metaschema 98 | files: ^.+/schema/.*schema\.json$ 99 | 100 | - repo: local 101 | hooks: 102 | - id: prettier-svg 103 | name: prettier svg 104 | description: Apply Prettier with plugin-xml to svg. 105 | entry: prettier --write --list-different --ignore-unknown --print-width 200 --xml-self-closing-space false --xml-whitespace-sensitivity ignore 106 | language: node 107 | files: .svg$ 108 | additional_dependencies: [prettier@2.7.1, "@prettier/plugin-xml@2.2.0"] 109 | 110 | - repo: https://github.com/AleksaC/hadolint-py 111 | rev: v2.12.1b3 112 | hooks: 113 | - id: hadolint 114 | exclude: .svg$ 115 | -------------------------------------------------------------------------------- /autoware_vehicle_msgs/CHANGELOG.rst: -------------------------------------------------------------------------------- 1 | ^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^ 2 | Changelog for package autoware_vehicle_msgs 3 | ^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^ 4 | 5 | 1.11.0 (2025-10-23) 6 | ------------------- 7 | 8 | 1.10.0 (2025-07-18) 9 | ------------------- 10 | * chore: update maintainer for autoware_msgs packages (`#143 `_) 11 | * Contributors: Ryohsuke Mitsudome 12 | 13 | 1.9.0 (2025-06-18) 14 | ------------------ 15 | 16 | 1.8.0 (2025-05-21) 17 | ------------------ 18 | * chore: fix email domain (`#133 `_) 19 | * chore: update maintainers (`#132 `_) 20 | * Contributors: Mete Fatih Cırıt 21 | 22 | 1.7.0 (2025-04-21) 23 | ------------------ 24 | 25 | 1.6.0 (2025-04-07) 26 | ------------------ 27 | 28 | 1.5.0 (2025-04-02) 29 | ------------------ 30 | 31 | 1.4.0 (2025-02-25) 32 | ------------------ 33 | * fix(autoware_msgs): fix links to issues in CHANGELOG.rst files (`#108 `_) 34 | * Contributors: Esteve Fernandez 35 | 36 | 1.3.0 (2024-11-25) 37 | ------------------ 38 | 39 | 1.2.0 (2024-10-01) 40 | ------------------ 41 | 42 | 1.1.0 (2024-05-10) 43 | ------------------ 44 | * chore: update `package.xml` and fix `CMakeLists.txt` (`#91 `_) 45 | update package.xml and fix cmakefiles 46 | * feat: update msg definitions (`#87 `_) 47 | * feat(autoware_perception_msgs): Add DetectedObjects messages and TrackedObjects messages 48 | * feat!(autoware_planning_msgs): remove PathWithLaneId msgs 49 | * feat!(autoware_perception_msgs): rename traffic signals to traffic lights 50 | * remove control mode command msg 51 | * fix(autoware_vehicle_msgs): remove ControlModeCommands.msg in CMakeLists.txt (`#90 `_) 52 | * feat(autoware_vehicle_msgs)!: remove VehicleControlCommand, VehicleKinematicState, and VehicleOdometry messages (`#88 `_) 53 | feat!(autoware_vehicle_msgs): remove VehicleControlCommand, VehicleKinematicState, and VehicleOdometry messages 54 | * Revert "feat!(autoware_perception_msgs): rename traffic signals to traffic lights" 55 | This reverts commit 768bb854036fc94db4364168e68d48b21401c17b. 56 | * add TrafficLight msgs 57 | * add todo 58 | --------- 59 | Co-authored-by: Ryohsuke Mitsudome 60 | Co-authored-by: Ryohsuke Mitsudome <43976834+mitsudome-r@users.noreply.github.com> 61 | Co-authored-by: Yutaka Kondo 62 | * fix(autoware_vehicle_msgs): add missed vehicle msgs (`#80 `_) 63 | * fix(autoware_vehicle_msgs): add missed vehicle msgs 64 | * style(pre-commit): autofix 65 | --------- 66 | Co-authored-by: pre-commit-ci[bot] <66853113+pre-commit-ci[bot]@users.noreply.github.com> 67 | * feat(autoware_vehicle_msgs): add autoware_vehicle_msgs (`#78 `_) 68 | * feat(autoware_vehicle_msgs): add autoware_vehicle_msgs 69 | * feat(autoware_vehicle_msgs): add ControlModeCommand.srv 70 | * style(pre-commit): autofix 71 | * fix(autoware_vehicle_msgs): remove msgs unused 72 | * style(pre-commit): autofix 73 | --------- 74 | Co-authored-by: pre-commit-ci[bot] <66853113+pre-commit-ci[bot]@users.noreply.github.com> 75 | * Contributors: Yukihiro Saito, Yutaka Kondo, beginningfan 76 | -------------------------------------------------------------------------------- /autoware_map_msgs/CHANGELOG.rst: -------------------------------------------------------------------------------- 1 | ^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^ 2 | Changelog for package autoware_map_msgs 3 | ^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^ 4 | 5 | 1.11.0 (2025-10-23) 6 | ------------------- 7 | 8 | 1.10.0 (2025-07-18) 9 | ------------------- 10 | * chore: update maintainer for autoware_msgs packages (`#143 `_) 11 | * Contributors: Ryohsuke Mitsudome 12 | 13 | 1.9.0 (2025-06-18) 14 | ------------------ 15 | 16 | 1.8.0 (2025-05-21) 17 | ------------------ 18 | * chore: fix email domain (`#133 `_) 19 | * chore: update maintainers (`#132 `_) 20 | * Contributors: Mete Fatih Cırıt 21 | 22 | 1.7.0 (2025-04-21) 23 | ------------------ 24 | 25 | 1.6.0 (2025-04-07) 26 | ------------------ 27 | 28 | 1.5.0 (2025-04-02) 29 | ------------------ 30 | * feat(autoware_msg_msgs): add scale factor remove altitude (`#121 `_) 31 | * add_scale_factor_remove_altitude 32 | * add newline 33 | --------- 34 | * Contributors: Yamato Ando 35 | 36 | 1.4.0 (2025-02-25) 37 | ------------------ 38 | * feat(MapProjectorInfo.msg): add LocalCartesian const (`#118 `_) 39 | * fix(autoware_msgs): fix links to issues in CHANGELOG.rst files (`#108 `_) 40 | * Contributors: Esteve Fernandez, Sebastian Zęderowski 41 | 42 | 1.3.0 (2024-11-25) 43 | ------------------ 44 | * feat(autoware_map_msgs): add MapProjectorInfo message (`#102 `_) 45 | * Contributors: Ryohsuke Mitsudome 46 | 47 | 1.2.0 (2024-10-01) 48 | ------------------ 49 | * feat(autoware_map_msgs): add msg and srv files releated with dynamic lanelet loading (`#81 `_) 50 | * Contributors: Barış Zeren, Ryohsuke Mitsudome, Yamato Ando 51 | 52 | 1.1.0 (2024-05-10) 53 | ------------------ 54 | * chore: update `package.xml` and fix `CMakeLists.txt` (`#91 `_) 55 | update package.xml and fix cmakefiles 56 | * feat(autoware_map_msgs): support cylindrical AreaInfo (`#64 `_) 57 | * feat(autoware_map_msgs): support cylindrical AreaInfo 58 | * update attribute 59 | --------- 60 | * feat(autoware_map_msgs): add selected map loading (`#57 `_) 61 | * feat(map_loader): add support for sequential_map_loading 62 | * feat(autoware_map_msgs): add PointCloudMetaData.msg 63 | * docs(autoware_map_msgs): add description of selected_map_loading 64 | * docs(autoware_map_msgs): remove gif for selected_map_loading 65 | * docs(autoware_map_msgs): fix typo 66 | * feat(autoware_map_msgs): make member of msg plural 67 | * docs(autoware_map_msgs): clarify the client needs to receive msg beforehand 68 | * docs(autoware_map_msgs): clarify IDs included in msgs are used as query for service 69 | --------- 70 | * feat(autoware_map_msgs): add grid coordinates in PointCloudMapCellWithID.msg (`#52 `_) 71 | * feat(autoware_map_msgs): add grid coordinates in PointCloudMapCellWithID.msg 72 | * style(pre-commit): autofix 73 | * debug 74 | --------- 75 | Co-authored-by: pre-commit-ci[bot] <66853113+pre-commit-ci[bot]@users.noreply.github.com> 76 | * feat(map-messages): add LaneletMapBin.msg (`#30 `_) 77 | * feat: add autoware_map_msgs for dynamic map loading (`#39 `_) 78 | Co-authored-by: M. Fatih Cırıt 79 | Co-authored-by: Kenji Miyake <31987104+kenji-miyake@users.noreply.github.com> 80 | Co-authored-by: Takagi, Isamu <43976882+isamu-takagi@users.noreply.github.com> 81 | * Contributors: M. Fatih Cırıt, Shintaro Tomie, Yutaka Kondo, kminoda 82 | -------------------------------------------------------------------------------- /CODE_OF_CONDUCT.md: -------------------------------------------------------------------------------- 1 | # Contributor Covenant Code of Conduct 2 | 3 | ## Our Pledge 4 | 5 | We as members, contributors, and leaders pledge to make participation in our 6 | community a harassment-free experience for everyone, regardless of age, body 7 | size, visible or invisible disability, ethnicity, sex characteristics, gender 8 | identity and expression, level of experience, education, socio-economic status, 9 | nationality, personal appearance, race, caste, color, religion, or sexual 10 | identity and orientation. 11 | 12 | We pledge to act and interact in ways that contribute to an open, welcoming, 13 | diverse, inclusive, and healthy community. 14 | 15 | ## Our Standards 16 | 17 | Examples of behavior that contributes to a positive environment for our 18 | community include: 19 | 20 | - Demonstrating empathy and kindness toward other people 21 | - Being respectful of differing opinions, viewpoints, and experiences 22 | - Giving and gracefully accepting constructive feedback 23 | - Accepting responsibility and apologizing to those affected by our mistakes, 24 | and learning from the experience 25 | - Focusing on what is best not just for us as individuals, but for the overall 26 | community 27 | 28 | Examples of unacceptable behavior include: 29 | 30 | - The use of sexualized language or imagery, and sexual attention or advances of 31 | any kind 32 | - Trolling, insulting or derogatory comments, and personal or political attacks 33 | - Public or private harassment 34 | - Publishing others' private information, such as a physical or email address, 35 | without their explicit permission 36 | - Other conduct which could reasonably be considered inappropriate in a 37 | professional setting 38 | 39 | ## Enforcement Responsibilities 40 | 41 | Community leaders are responsible for clarifying and enforcing our standards of 42 | acceptable behavior and will take appropriate and fair corrective action in 43 | response to any behavior that they deem inappropriate, threatening, offensive, 44 | or harmful. 45 | 46 | Community leaders have the right and responsibility to remove, edit, or reject 47 | comments, commits, code, wiki edits, issues, and other contributions that are 48 | not aligned to this Code of Conduct, and will communicate reasons for moderation 49 | decisions when appropriate. 50 | 51 | ## Scope 52 | 53 | This Code of Conduct applies within all community spaces, and also applies when 54 | an individual is officially representing the community in public spaces. 55 | Examples of representing our community include using an official e-mail address, 56 | posting via an official social media account, or acting as an appointed 57 | representative at an online or offline event. 58 | 59 | ## Enforcement 60 | 61 | Instances of abusive, harassing, or otherwise unacceptable behavior may be 62 | reported to the community leaders responsible for enforcement at 63 | . 64 | All complaints will be reviewed and investigated promptly and fairly. 65 | 66 | All community leaders are obligated to respect the privacy and security of the 67 | reporter of any incident. 68 | 69 | ## Enforcement Guidelines 70 | 71 | Community leaders will follow these Community Impact Guidelines in determining 72 | the consequences for any action they deem in violation of this Code of Conduct: 73 | 74 | ### 1. Correction 75 | 76 | **Community Impact**: Use of inappropriate language or other behavior deemed 77 | unprofessional or unwelcome in the community. 78 | 79 | **Consequence**: A private, written warning from community leaders, providing 80 | clarity around the nature of the violation and an explanation of why the 81 | behavior was inappropriate. A public apology may be requested. 82 | 83 | ### 2. Warning 84 | 85 | **Community Impact**: A violation through a single incident or series of 86 | actions. 87 | 88 | **Consequence**: A warning with consequences for continued behavior. No 89 | interaction with the people involved, including unsolicited interaction with 90 | those enforcing the Code of Conduct, for a specified period of time. This 91 | includes avoiding interactions in community spaces as well as external channels 92 | like social media. Violating these terms may lead to a temporary or permanent 93 | ban. 94 | 95 | ### 3. Temporary Ban 96 | 97 | **Community Impact**: A serious violation of community standards, including 98 | sustained inappropriate behavior. 99 | 100 | **Consequence**: A temporary ban from any sort of interaction or public 101 | communication with the community for a specified period of time. No public or 102 | private interaction with the people involved, including unsolicited interaction 103 | with those enforcing the Code of Conduct, is allowed during this period. 104 | Violating these terms may lead to a permanent ban. 105 | 106 | ### 4. Permanent Ban 107 | 108 | **Community Impact**: Demonstrating a pattern of violation of community 109 | standards, including sustained inappropriate behavior, harassment of an 110 | individual, or aggression toward or disparagement of classes of individuals. 111 | 112 | **Consequence**: A permanent ban from any sort of public interaction within the 113 | community. 114 | 115 | ## Attribution 116 | 117 | This Code of Conduct is adapted from the [Contributor Covenant][homepage], 118 | version 2.1, available at 119 | [https://www.contributor-covenant.org/version/2/1/code_of_conduct.html][v2.1]. 120 | 121 | Community Impact Guidelines were inspired by 122 | [Mozilla's code of conduct enforcement ladder][mozilla coc]. 123 | 124 | For answers to common questions about this code of conduct, see the FAQ at 125 | [https://www.contributor-covenant.org/faq][faq]. Translations are available at 126 | [https://www.contributor-covenant.org/translations][translations]. 127 | 128 | [homepage]: https://www.contributor-covenant.org 129 | [v2.1]: https://www.contributor-covenant.org/version/2/1/code_of_conduct.html 130 | [mozilla coc]: https://github.com/mozilla/diversity 131 | [faq]: https://www.contributor-covenant.org/faq 132 | [translations]: https://www.contributor-covenant.org/translations 133 | -------------------------------------------------------------------------------- /autoware_perception_msgs/CHANGELOG.rst: -------------------------------------------------------------------------------- 1 | ^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^ 2 | Changelog for package autoware_perception_msgs 3 | ^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^ 4 | 5 | 1.11.0 (2025-10-23) 6 | ------------------- 7 | 8 | 1.10.0 (2025-07-18) 9 | ------------------- 10 | * chore: update maintainer for autoware_msgs packages (`#143 `_) 11 | * Contributors: Ryohsuke Mitsudome 12 | 13 | 1.9.0 (2025-06-18) 14 | ------------------ 15 | 16 | 1.8.0 (2025-05-21) 17 | ------------------ 18 | * feat(autoware_perception_msgs): update traffic light messages to include future states (`#134 `_) 19 | * feat: add autoware_perception_msgs/FutureTrafficLightState message 20 | * feat: update autoware_perception_msgs/TrafficLightGroup to include predictions 21 | * fix: add inline comments to autoware_perception_msgs/FutureTrafficLightState message 22 | * fix: rename to PredictedTrafficLightState, update field names 23 | * fix: change CMakeLists.txt to alphabetical order 24 | * fix: add local_perception as predicted traffic light state information_source 25 | --------- 26 | * chore: fix email domain (`#133 `_) 27 | * chore: update maintainers (`#132 `_) 28 | * Contributors: Mete Fatih Cırıt, Yu Asabe 29 | 30 | 1.7.0 (2025-04-21) 31 | ------------------ 32 | * feat(autoware_sensing_msgs): implement the proposed universal radar messages (`#120 `_) 33 | Co-authored-by: Taekjin LEE 34 | Co-authored-by: Mete Fatih Cırıt 35 | * Contributors: Kenzo Lobos Tsunekawa 36 | 37 | 1.6.0 (2025-04-07) 38 | ------------------ 39 | 40 | 1.5.0 (2025-04-02) 41 | ------------------ 42 | 43 | 1.4.0 (2025-02-25) 44 | ------------------ 45 | * fix(autoware_msgs): fix links to issues in CHANGELOG.rst files (`#108 `_) 46 | * Contributors: Esteve Fernandez 47 | 48 | 1.3.0 (2024-11-25) 49 | ------------------ 50 | 51 | 1.2.0 (2024-10-01) 52 | ------------------ 53 | 54 | 1.1.0 (2024-05-10) 55 | ------------------ 56 | * chore: update `package.xml` and fix `CMakeLists.txt` (`#91 `_) 57 | update package.xml and fix cmakefiles 58 | * feat: update msg definitions (`#87 `_) 59 | * feat(autoware_perception_msgs): Add DetectedObjects messages and TrackedObjects messages 60 | * feat!(autoware_planning_msgs): remove PathWithLaneId msgs 61 | * feat!(autoware_perception_msgs): rename traffic signals to traffic lights 62 | * remove control mode command msg 63 | * fix(autoware_vehicle_msgs): remove ControlModeCommands.msg in CMakeLists.txt (`#90 `_) 64 | * feat(autoware_vehicle_msgs)!: remove VehicleControlCommand, VehicleKinematicState, and VehicleOdometry messages (`#88 `_) 65 | feat!(autoware_vehicle_msgs): remove VehicleControlCommand, VehicleKinematicState, and VehicleOdometry messages 66 | * Revert "feat!(autoware_perception_msgs): rename traffic signals to traffic lights" 67 | This reverts commit 768bb854036fc94db4364168e68d48b21401c17b. 68 | * add TrafficLight msgs 69 | * add todo 70 | --------- 71 | Co-authored-by: Ryohsuke Mitsudome 72 | Co-authored-by: Ryohsuke Mitsudome <43976834+mitsudome-r@users.noreply.github.com> 73 | Co-authored-by: Yutaka Kondo 74 | * fix(autoware_perception_msgs): fix sequence length to dynamic (`#74 `_) 75 | * fix(autoware_perception_msgs): fix error in PredictedObject.msg (`#72 `_) 76 | * feat(autoware_perception_msgs): add PredictedObjects msgs (`#63 `_) 77 | * feat(autoware_perception_msgs): add PredictedObjects msgs 78 | * style(pre-commit): autofix 79 | * feat(autoware_perception_msgs): fix conflicting msgs 80 | --------- 81 | Co-authored-by: pre-commit-ci[bot] <66853113+pre-commit-ci[bot]@users.noreply.github.com> 82 | Co-authored-by: Ryohsuke Mitsudome <43976834+mitsudome-r@users.noreply.github.com> 83 | * feat(autoware_perception_msgs): remove traffic light messages (`#70 `_) 84 | * revert: "fix(autoware_perception_msgs): add Header to tlr messages and change TrafficLightElement.msg status" (`#69 `_) 85 | Revert "fix(autoware_perception_msgs): add Header to tlr messages and change TrafficLightElement.msg status (`#68 `_)" 86 | This reverts commit 18588df6eb7e7f694bd725bebd44f569f616964f. 87 | * fix(autoware_perception_msgs): add Header to tlr messages and change TrafficLightElement.msg status (`#68 `_) 88 | * add UP_LEFT_ARROW and UP_RIGHT_ARROW to traffic_light_element 89 | * add header to tlr messages and change status values of TrafficLight.msg 90 | --------- 91 | * feat(autoware_perception_msgs): add UP_LEFT_ARROW and UP_RIGHT_ARROW to traffic_light_element (`#67 `_) 92 | add UP_LEFT_ARROW and UP_RIGHT_ARROW to traffic_light_element 93 | * build: package.xml dependencies (`#60 `_) 94 | * mark rosidl_default_generators as 95 | * add missing rosidl_default_runtime 96 | --------- 97 | * feat(autoware_perception_msgs): add traffic light messages (`#48 `_) 98 | * Contributors: Mingyu1991, Takagi, Isamu, Vincent Richard, Yukihiro Saito, Yutaka Kondo, beginningfan 99 | -------------------------------------------------------------------------------- /autoware_planning_msgs/CHANGELOG.rst: -------------------------------------------------------------------------------- 1 | ^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^ 2 | Changelog for package autoware_planning_msgs 3 | ^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^ 4 | 5 | 1.11.0 (2025-10-23) 6 | ------------------- 7 | * feat(autoware_planning_msgs): added srv to package (`#151 `_) 8 | * added srv to package 9 | * comments added 10 | * Apply suggestion from @mitsudome-r 11 | Co-authored-by: Ryohsuke Mitsudome <43976834+mitsudome-r@users.noreply.github.com> 12 | * fix 13 | * rename 14 | * style(pre-commit): autofix 15 | --------- 16 | Co-authored-by: Ryohsuke Mitsudome <43976834+mitsudome-r@users.noreply.github.com> 17 | Co-authored-by: pre-commit-ci[bot] <66853113+pre-commit-ci[bot]@users.noreply.github.com> 18 | * Contributors: Arjun Jagdish Ram 19 | 20 | 1.10.0 (2025-07-18) 21 | ------------------- 22 | * chore: update maintainer for autoware_msgs packages (`#143 `_) 23 | * Contributors: Ryohsuke Mitsudome 24 | 25 | 1.9.0 (2025-06-18) 26 | ------------------ 27 | * feat(autoware_planning_msgs): add route services (`#138 `_) 28 | * feat(autoware_planning_msgs): add route services 29 | * style(pre-commit): autofix 30 | --------- 31 | Co-authored-by: pre-commit-ci[bot] <66853113+pre-commit-ci[bot]@users.noreply.github.com> 32 | * Contributors: Ryohsuke Mitsudome 33 | 34 | 1.8.0 (2025-05-21) 35 | ------------------ 36 | * chore: fix email domain (`#133 `_) 37 | * chore: update maintainers (`#132 `_) 38 | * Contributors: Mete Fatih Cırıt 39 | 40 | 1.7.0 (2025-04-21) 41 | ------------------ 42 | 43 | 1.6.0 (2025-04-07) 44 | ------------------ 45 | 46 | 1.5.0 (2025-04-02) 47 | ------------------ 48 | 49 | 1.4.0 (2025-02-25) 50 | ------------------ 51 | * fix(autoware_msgs): fix links to issues in CHANGELOG.rst files (`#108 `_) 52 | * Contributors: Esteve Fernandez 53 | 54 | 1.3.0 (2024-11-25) 55 | ------------------ 56 | 57 | 1.2.0 (2024-10-01) 58 | ------------------ 59 | * docs(TrajectoryPoint): add comment for acceleration_mps2 to clarify its usage (`#92 `_) 60 | * Contributors: Ahmed Ebrahim 61 | 62 | 1.1.0 (2024-05-10) 63 | ------------------ 64 | * chore: update `package.xml` and fix `CMakeLists.txt` (`#91 `_) 65 | update package.xml and fix cmakefiles 66 | * feat: update msg definitions (`#87 `_) 67 | * feat(autoware_perception_msgs): Add DetectedObjects messages and TrackedObjects messages 68 | * feat!(autoware_planning_msgs): remove PathWithLaneId msgs 69 | * feat!(autoware_perception_msgs): rename traffic signals to traffic lights 70 | * remove control mode command msg 71 | * fix(autoware_vehicle_msgs): remove ControlModeCommands.msg in CMakeLists.txt (`#90 `_) 72 | * feat(autoware_vehicle_msgs)!: remove VehicleControlCommand, VehicleKinematicState, and VehicleOdometry messages (`#88 `_) 73 | feat!(autoware_vehicle_msgs): remove VehicleControlCommand, VehicleKinematicState, and VehicleOdometry messages 74 | * Revert "feat!(autoware_perception_msgs): rename traffic signals to traffic lights" 75 | This reverts commit 768bb854036fc94db4364168e68d48b21401c17b. 76 | * add TrafficLight msgs 77 | * add todo 78 | --------- 79 | Co-authored-by: Ryohsuke Mitsudome 80 | Co-authored-by: Ryohsuke Mitsudome <43976834+mitsudome-r@users.noreply.github.com> 81 | Co-authored-by: Yutaka Kondo 82 | * fix: planning_msg (`#76 `_) 83 | * fix:planning_msg 84 | * fix:planning_msg 85 | --------- 86 | * feat(autoware_planning_msgs): migrate autoware_auto_planning_msg to autoware_planning_msg (`#66 `_) 87 | * add-autoware-planning-msg 88 | * add-autoware-planning-msg 89 | * add-autoware-planning-msg 90 | * add-autoware-planning-msg 91 | * add-autoware-planning-msg 92 | * delete old port 93 | * delete old port 94 | * delete old port 95 | * delete old port 96 | * add-autoware-planning-msg 97 | * style(pre-commit): autofix 98 | --------- 99 | Co-authored-by: pre-commit-ci[bot] <66853113+pre-commit-ci[bot]@users.noreply.github.com> 100 | Co-authored-by: Ryohsuke Mitsudome <43976834+mitsudome-r@users.noreply.github.com> 101 | * feat(autoware_planning_msgs): remove SetPoseWithUuidStamped (`#59 `_) 102 | * feat: rename route with uuid 103 | * feat: remove route with uuid 104 | --------- 105 | * feat: remove set route service (`#58 `_) 106 | * feat(autoware_planning_msgs): add allow_modification option (`#55 `_) 107 | * feat(autoware_planning_msgs): add allow_modification option to PoseWithUuidStamped 108 | * move allow_modification 109 | --------- 110 | * feat(autoware_planning_msgs): add the service to set uuid pose (`#54 `_) 111 | * feat(autoware_planning_msgs): move header to the top in PoseWithUuidStamped (`#50 `_) 112 | * feat(autoware_planning_msgs): change PoseWithUuid to PoseStampedWithUuid (`#47 `_) 113 | * feat(autoware_planning_msgs): create PoseWithUuid and add uuid to VectorMapRoute (`#42 `_) 114 | feat(autoware_planning_msgs): add PoseWithUuid and add uuid to LaneletRoute 115 | * refactor(planning-messages)!: rename VectorMap to Lanelet (`#41 `_) 116 | * feat(autoware_planning_msgs): add autoware planning messages (`#33 `_) 117 | Co-authored-by: kenji-miyake 118 | * Contributors: Kosuke Takeuchi, M. Fatih Cırıt, Takagi, Isamu, Yukihiro Saito, Yutaka Kondo, shulanbushangshu 119 | -------------------------------------------------------------------------------- /autoware_sensing_msgs/README.md: -------------------------------------------------------------------------------- 1 | # autoware_sensing_msgs 2 | 3 | ## GNSS/INS sensor messages 4 | 5 | **Possible Data Types:** 6 | 7 | - Position 8 | - Orientation 9 | - Twist (Velocity) 10 | - linear 11 | - angular 12 | - Accel 13 | - linear 14 | - angular 15 | 16 | ### Position 17 | 18 | For this information, you can use the [NavSatFix](https://docs.ros.org/en/noetic/api/sensor_msgs/html/msg/NavSatFix.html) message. 19 | 20 | If the sensor provides MSL(Mean Sea Level) for altitude, you can use it for the altitude field. 21 | 22 | - `sensor_msgs/NavSatFix` following fields are used: 23 | - `std_msgs/Header` header 24 | - `float64` latitude 25 | - `float64` longitude 26 | - `float64` altitude 27 | - `float64[9]` position_covariance 28 | 29 | For detailed info about the east, north, up, see the [Coordinate Axes Conventions](#coordinate-axes-conventions). 30 | 31 | ### Orientation 32 | 33 | #### GnssInsOrientationStamped.msg 34 | 35 | This message contains the GNSS-INS orientation information. 36 | 37 | The orientation is represented by a quaternion. 38 | 39 | If the sensor provides roll, pitch, yaw; you should convert it to quaternion. 40 | 41 | - [Example with tf2](http://wiki.ros.org/tf2/Tutorials/Quaternions#CA-f7f08c472826d99550c915a0b177064bf5594654_1). 42 | 43 | For detailed info about the roll, pitch, yaw and rotation axes see the [Coordinate Axes Conventions](#coordinate-axes-conventions). 44 | 45 | ### Velocity 46 | 47 | For this information, you can use the [TwistWithCovarianceStamped](http://docs.ros.org/en/noetic/api/geometry_msgs/html/msg/TwistWithCovarianceStamped.html) message. 48 | 49 | Its structure is as follows: 50 | 51 | - `geometry_msgs/TwistWithCovarianceStamped` following fields are used: 52 | - `std_msgs/Header` header 53 | - `geometry_msgs/TwistWithCovariance` twist 54 | - `geometry_msgs/Twist` twist 55 | - `geometry_msgs/Vector3` linear 56 | - `geometry_msgs/Vector3` angular 57 | - `float64[36]` covariance 58 | 59 | - The linear field contains the linear velocities in the x, y, z axes. 60 | - The angular field contains the angular velocities in the x, y, z axes. 61 | - The covariance matrix parameters are linear and angular velocities in order. 62 | 63 | For detailed info about the covariance matrix [RMSE? Variances? Covariance Matrix?](#rmse-variances-covariance-matrix). 64 | 65 | ### Acceleration 66 | 67 | For this information, you can use the [AccelWithCovarianceStamped](https://docs.ros.org/en/api/geometry_msgs/html/msg/AccelWithCovarianceStamped.html) message. 68 | 69 | Its structure is as follows: 70 | 71 | - `geometry_msgs/AccelWithCovarianceStamped` following fields are used: 72 | - `std_msgs/Header` header 73 | - `geometry_msgs/AccelWithCovariance` accel 74 | - `geometry_msgs/Accel` accel 75 | - `geometry_msgs/Vector3` linear 76 | - `geometry_msgs/Vector3` angular 77 | - `float64[36]` covariance 78 | 79 | - The linear field contains the linear accelerations in the x, y, z axes. 80 | - The angular field contains the angular accelerations in the x, y, z axes. 81 | - The covariance matrix parameters are linear and angular accelerations in order. 82 | 83 | For detailed info about the covariance matrix [RMSE? Variances? Covariance Matrix?](#rmse-variances-covariance-matrix). 84 | 85 | ### Design 86 | 87 | #### Coordinate Frames 88 | 89 | Frames used in Autoware are defined as follows: 90 | 91 | ```mermaid 92 | flowchart LR 93 | earth --> Map[map] --> base_link 94 | base_link --> gnss_ins 95 | base_link --> sensor_a 96 | base_link --> sensor_b 97 | ``` 98 | 99 | In Autoware, the `earth` frame is mostly omitted, only used in the `GnssInsPositionStamped` message. 100 | 101 | The `map` frame is used as the stationary reference frame. 102 | 103 | The `map` frame's axes point to the East, North, Up directions as explained in [Coordinate Axes Conventions](#coordinate-axes-conventions). 104 | 105 | The `base_link` is the center of the rear axle of the vehicle. 106 | 107 | `Map[map] --> base_link` is the main transformation that is attempted to be estimated by various localization modules. This transformation is output by the EKF(Extended Kalman Filter) localization module. 108 | 109 | Other sensors' frames are defined with respect to the `base_link` frame in the vehicle. 110 | 111 | #### Estimating the `base_link` frame by using the other sensors 112 | 113 | Generally we don't have the localization sensors physically at the `base_link` frame. So various sensors localize with respect to their own frames, let's call it `sensor` frame. 114 | 115 | We introduce a new frame naming convention: `x_by_y`: 116 | 117 | ```yaml 118 | x: estimated frame name 119 | y: localization method/source 120 | ``` 121 | 122 | We cannot directly get the `sensor` frame. Because we would need the EKF module to estimate the `base_link` frame first. 123 | 124 | Without the EKF module the best we can do is to estimate `Map[map] --> sensor_by_sensor --> base_link_by_sensor` using this sensor. 125 | 126 | ##### Example by the GNSS/INS sensor 127 | 128 | For the integrated GNSS/INS we use the following frames: 129 | 130 | ```mermaid 131 | flowchart LR 132 | earth --> Map[map] --> gnss_ins_by_gnss_ins --> base_link_by_gnss_ins 133 | ``` 134 | 135 | The `gnss_ins_by_gnss_ins` frame is obtained by the coordinates from GNSS/INS sensor. The coordinates are converted to `map` frame using the `gnss_poser` node. 136 | 137 | Finally `gnss_ins_by_gnss_ins` frame represents the position of the `gnss_ins` estimated by the `gnss_ins` sensor in the `map`. 138 | 139 | Then by using the static transformation between `gnss_ins` and the `base_link` frame, we can obtain the `base_link_by_gnss_ins` frame. Which represents the `base_link` estimated by the `gnss_ins` sensor. 140 | 141 | References: 142 | 143 | - 144 | 145 | #### Coordinate Axes Conventions 146 | 147 | We are using East, North, Up (ENU) coordinate axes convention by default throughout the stack. 148 | 149 | ```yaml 150 | X+: East 151 | Y+: North 152 | Z+: Up 153 | ``` 154 | 155 | The position, orientation, velocity, acceleration are all defined in the same axis convention. 156 | 157 | Position by the GNSS/INS sensor is expected to be in `earth` frame. 158 | 159 | Orientation, velocity, acceleration by the GNSS/INS sensor are expected to be in the sensor frame. Axes parallel to the `map` frame. 160 | 161 | If roll, pitch, yaw is provided, they correspond to rotation around X, Y, Z axes respectively. 162 | 163 | ```yaml 164 | Rotation around: 165 | X+: roll 166 | Y+: pitch 167 | Z+: yaw 168 | ``` 169 | 170 | References: 171 | 172 | - 173 | 174 | #### RMSE? Variances? Covariance Matrix? 175 | 176 | ##### Definitions 177 | 178 | **RMSE:** Root Mean Square Error is a measure of the differences between values predicted by a model or an estimator and the values observed. 179 | 180 | **Variance:** Squared deviation of a random variable from its sample mean. 181 | 182 | **Covariance:** A measure of the joint variability of two random variables. 183 | 184 | **Covariance Matrix:** A square matrix giving the covariance between each pair of elements of a given random vector 185 | 186 | ##### Simplified usage in Autoware 187 | 188 | `RMSE² = Variance` 189 | 190 | A covariance matrix is of `n` random variables is an `n×n` matrix. 191 | 192 | Covariance with itself is the variance of the random variable. 193 | 194 | The diagonal elements of the covariance matrix are the variances of the random variables. 195 | 196 | In Autoware, only these variance values are used, mostly in the RMSE form. The rest of the covariance matrix is not used, can be left `0.0`. 197 | 198 | ##### Example for TwistWithCovariance 199 | 200 | [This message](https://docs.ros.org/en/api/geometry_msgs/html/msg/TwistWithCovariance.html) contains the linear and angular velocities and the covariance matrix. 201 | 202 | Let's call RMSE values for these calculations as `σ_x, σ_y, σ_z, σ_r, σ_p, σ_y`. 203 | 204 | The covariance matrix can be constructed as follows: 205 | 206 | | | | | | | | 207 | | ------ | ------ | ------ | ------ | ------ | ------ | 208 | | σ_x | 0 | 0 | 0 | 0 | 0 | 209 | | 0 | σ_y | 0 | 0 | 0 | 0 | 210 | | 0 | 0 | σ_z | 0 | 0 | 0 | 211 | | 0 | 0 | 0 | σ_r | 0 | 0 | 212 | | 0 | 0 | 0 | 0 | σ_p | 0 | 213 | | 0 | 0 | 0 | 0 | 0 | σ_y | 214 | 215 | In the message file, it is a `float64[36]` array. We fill the indices at `i*7, i:[0,6]`, making up `0,7,14,21,28,35`th indices of this array. 216 | 217 | **References:** 218 | 219 | - 220 | - 221 | - 222 | - 223 | 224 | #### Q/A 225 | 226 | - Why is position and orientation not combined as a PoseWithCovarianceStamped message? 227 | - Modern GNSS/INS sensors provide both of these together but more affordable gnss only sensors might provide only position information. 228 | - We separated them to allow if the INS sensor is separate, the orientation information can be extracted from there with aid of a magnetometer. 229 | 230 | ## Concatenated point cloud messages 231 | 232 | ### ConcatenatedPointCloudInfo.msg 233 | 234 | This message provides metadata about concatenated point clouds that combine multiple LiDAR sensor inputs. It includes information about the concatenation strategy used and detailed metadata for each source point cloud segment. 235 | 236 | **Fields:** 237 | 238 | - `header`: Standard ROS header with timestamp and frame information for the concatenated point cloud 239 | - `concatenation_success`: Boolean indicating whether the concatenation process completed successfully 240 | - `matching_strategy`: Strategy used for concatenation (see constants below) 241 | - `matching_strategy_config`: Raw encoded configuration data specific to the matching strategy (decoded by the node). See [concatenate_and_time_synchronize_node documentation](https://autowarefoundation.github.io/autoware_universe/main/sensing/autoware_pointcloud_preprocessor/docs/concatenate-data/#meta-information-topic). 242 | - `source_info`: Array of metadata for each input point cloud source 243 | 244 | **Available concatenation strategies:** 245 | 246 | - **Naive** (`STRATEGY_NAIVE`): Direct concatenation without complex timestamp matching, suitable for non-synchronized LiDAR sensors 247 | - **Advanced** (`STRATEGY_ADVANCED`): Precise timestamp alignment with offset compensation and noise handling, ideal for synchronized LiDAR sensors 248 | 249 | ### SourcePointCloudInfo.msg 250 | 251 | This message contains metadata for individual point cloud segments within a concatenated point cloud, including status information, spatial boundaries, and source topic details. 252 | 253 | **Fields:** 254 | 255 | - `header`: Original timestamp and frame ID from the source point cloud 256 | - `topic`: ROS topic name where the source point cloud was received 257 | - `status`: Processing status of the source point cloud (see constants below) 258 | - `idx_begin`: Starting index (inclusive) of this segment within the concatenated point cloud 259 | - `length`: Number of points from this source in the concatenated point cloud 260 | 261 | **Available status codes:** 262 | 263 | - `STATUS_OK`: Point cloud received successfully (may contain 0 or more points) 264 | - `STATUS_TIMEOUT`: Point cloud not received due to timeout 265 | - `STATUS_INVALID`: Point cloud was malformed or corrupt 266 | 267 | For detailed information about concatenation strategies and parameter configuration, see the [concatenate_and_time_synchronize_node documentation](https://autowarefoundation.github.io/autoware_universe/main/sensing/autoware_pointcloud_preprocessor/docs/concatenate-data/#concatenation-strategies). 268 | -------------------------------------------------------------------------------- /LICENSE: -------------------------------------------------------------------------------- 1 | Apache License 2 | Version 2.0, January 2004 3 | http://www.apache.org/licenses/ 4 | 5 | TERMS AND CONDITIONS FOR USE, REPRODUCTION, AND DISTRIBUTION 6 | 7 | 1. Definitions. 8 | 9 | "License" shall mean the terms and conditions for use, reproduction, 10 | and distribution as defined by Sections 1 through 9 of this document. 11 | 12 | "Licensor" shall mean the copyright owner or entity authorized by 13 | the copyright owner that is granting the License. 14 | 15 | "Legal Entity" shall mean the union of the acting entity and all 16 | other entities that control, are controlled by, or are under common 17 | control with that entity. For the purposes of this definition, 18 | "control" means (i) the power, direct or indirect, to cause the 19 | direction or management of such entity, whether by contract or 20 | otherwise, or (ii) ownership of fifty percent (50%) or more of the 21 | outstanding shares, or (iii) beneficial ownership of such entity. 22 | 23 | "You" (or "Your") shall mean an individual or Legal Entity 24 | exercising permissions granted by this License. 25 | 26 | "Source" form shall mean the preferred form for making modifications, 27 | including but not limited to software source code, documentation 28 | source, and configuration files. 29 | 30 | "Object" form shall mean any form resulting from mechanical 31 | transformation or translation of a Source form, including but 32 | not limited to compiled object code, generated documentation, 33 | and conversions to other media types. 34 | 35 | "Work" shall mean the work of authorship, whether in Source or 36 | Object form, made available under the License, as indicated by a 37 | copyright notice that is included in or attached to the work 38 | (an example is provided in the Appendix below). 39 | 40 | "Derivative Works" shall mean any work, whether in Source or Object 41 | form, that is based on (or derived from) the Work and for which the 42 | editorial revisions, annotations, elaborations, or other modifications 43 | represent, as a whole, an original work of authorship. For the purposes 44 | of this License, Derivative Works shall not include works that remain 45 | separable from, or merely link (or bind by name) to the interfaces of, 46 | the Work and Derivative Works thereof. 47 | 48 | "Contribution" shall mean any work of authorship, including 49 | the original version of the Work and any modifications or additions 50 | to that Work or Derivative Works thereof, that is intentionally 51 | submitted to Licensor for inclusion in the Work by the copyright owner 52 | or by an individual or Legal Entity authorized to submit on behalf of 53 | the copyright owner. For the purposes of this definition, "submitted" 54 | means any form of electronic, verbal, or written communication sent 55 | to the Licensor or its representatives, including but not limited to 56 | communication on electronic mailing lists, source code control systems, 57 | and issue tracking systems that are managed by, or on behalf of, the 58 | Licensor for the purpose of discussing and improving the Work, but 59 | excluding communication that is conspicuously marked or otherwise 60 | designated in writing by the copyright owner as "Not a Contribution." 61 | 62 | "Contributor" shall mean Licensor and any individual or Legal Entity 63 | on behalf of whom a Contribution has been received by Licensor and 64 | subsequently incorporated within the Work. 65 | 66 | 2. Grant of Copyright License. Subject to the terms and conditions of 67 | this License, each Contributor hereby grants to You a perpetual, 68 | worldwide, non-exclusive, no-charge, royalty-free, irrevocable 69 | copyright license to reproduce, prepare Derivative Works of, 70 | publicly display, publicly perform, sublicense, and distribute the 71 | Work and such Derivative Works in Source or Object form. 72 | 73 | 3. Grant of Patent License. Subject to the terms and conditions of 74 | this License, each Contributor hereby grants to You a perpetual, 75 | worldwide, non-exclusive, no-charge, royalty-free, irrevocable 76 | (except as stated in this section) patent license to make, have made, 77 | use, offer to sell, sell, import, and otherwise transfer the Work, 78 | where such license applies only to those patent claims licensable 79 | by such Contributor that are necessarily infringed by their 80 | Contribution(s) alone or by combination of their Contribution(s) 81 | with the Work to which such Contribution(s) was submitted. If You 82 | institute patent litigation against any entity (including a 83 | cross-claim or counterclaim in a lawsuit) alleging that the Work 84 | or a Contribution incorporated within the Work constitutes direct 85 | or contributory patent infringement, then any patent licenses 86 | granted to You under this License for that Work shall terminate 87 | as of the date such litigation is filed. 88 | 89 | 4. Redistribution. You may reproduce and distribute copies of the 90 | Work or Derivative Works thereof in any medium, with or without 91 | modifications, and in Source or Object form, provided that You 92 | meet the following conditions: 93 | 94 | (a) You must give any other recipients of the Work or 95 | Derivative Works a copy of this License; and 96 | 97 | (b) You must cause any modified files to carry prominent notices 98 | stating that You changed the files; and 99 | 100 | (c) You must retain, in the Source form of any Derivative Works 101 | that You distribute, all copyright, patent, trademark, and 102 | attribution notices from the Source form of the Work, 103 | excluding those notices that do not pertain to any part of 104 | the Derivative Works; and 105 | 106 | (d) If the Work includes a "NOTICE" text file as part of its 107 | distribution, then any Derivative Works that You distribute must 108 | include a readable copy of the attribution notices contained 109 | within such NOTICE file, excluding those notices that do not 110 | pertain to any part of the Derivative Works, in at least one 111 | of the following places: within a NOTICE text file distributed 112 | as part of the Derivative Works; within the Source form or 113 | documentation, if provided along with the Derivative Works; or, 114 | within a display generated by the Derivative Works, if and 115 | wherever such third-party notices normally appear. The contents 116 | of the NOTICE file are for informational purposes only and 117 | do not modify the License. You may add Your own attribution 118 | notices within Derivative Works that You distribute, alongside 119 | or as an addendum to the NOTICE text from the Work, provided 120 | that such additional attribution notices cannot be construed 121 | as modifying the License. 122 | 123 | You may add Your own copyright statement to Your modifications and 124 | may provide additional or different license terms and conditions 125 | for use, reproduction, or distribution of Your modifications, or 126 | for any such Derivative Works as a whole, provided Your use, 127 | reproduction, and distribution of the Work otherwise complies with 128 | the conditions stated in this License. 129 | 130 | 5. Submission of Contributions. Unless You explicitly state otherwise, 131 | any Contribution intentionally submitted for inclusion in the Work 132 | by You to the Licensor shall be under the terms and conditions of 133 | this License, without any additional terms or conditions. 134 | Notwithstanding the above, nothing herein shall supersede or modify 135 | the terms of any separate license agreement you may have executed 136 | with Licensor regarding such Contributions. 137 | 138 | 6. Trademarks. This License does not grant permission to use the trade 139 | names, trademarks, service marks, or product names of the Licensor, 140 | except as required for reasonable and customary use in describing the 141 | origin of the Work and reproducing the content of the NOTICE file. 142 | 143 | 7. Disclaimer of Warranty. Unless required by applicable law or 144 | agreed to in writing, Licensor provides the Work (and each 145 | Contributor provides its Contributions) on an "AS IS" BASIS, 146 | WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or 147 | implied, including, without limitation, any warranties or conditions 148 | of TITLE, NON-INFRINGEMENT, MERCHANTABILITY, or FITNESS FOR A 149 | PARTICULAR PURPOSE. You are solely responsible for determining the 150 | appropriateness of using or redistributing the Work and assume any 151 | risks associated with Your exercise of permissions under this License. 152 | 153 | 8. Limitation of Liability. In no event and under no legal theory, 154 | whether in tort (including negligence), contract, or otherwise, 155 | unless required by applicable law (such as deliberate and grossly 156 | negligent acts) or agreed to in writing, shall any Contributor be 157 | liable to You for damages, including any direct, indirect, special, 158 | incidental, or consequential damages of any character arising as a 159 | result of this License or out of the use or inability to use the 160 | Work (including but not limited to damages for loss of goodwill, 161 | work stoppage, computer failure or malfunction, or any and all 162 | other commercial damages or losses), even if such Contributor 163 | has been advised of the possibility of such damages. 164 | 165 | 9. Accepting Warranty or Additional Liability. While redistributing 166 | the Work or Derivative Works thereof, You may choose to offer, 167 | and charge a fee for, acceptance of support, warranty, indemnity, 168 | or other liability obligations and/or rights consistent with this 169 | License. However, in accepting such obligations, You may act only 170 | on Your own behalf and on Your sole responsibility, not on behalf 171 | of any other Contributor, and only if You agree to indemnify, 172 | defend, and hold each Contributor harmless for any liability 173 | incurred by, or claims asserted against, such Contributor by reason 174 | of your accepting any such warranty or additional liability. 175 | 176 | END OF TERMS AND CONDITIONS 177 | 178 | APPENDIX: How to apply the Apache License to your work. 179 | 180 | To apply the Apache License to your work, attach the following 181 | boilerplate notice, with the fields enclosed by brackets "[]" 182 | replaced with your own identifying information. (Don't include 183 | the brackets!) The text should be enclosed in the appropriate 184 | comment syntax for the file format. We also recommend that a 185 | file or class name and description of purpose be included on the 186 | same "printed page" as the copyright notice for easier 187 | identification within third-party archives. 188 | 189 | Copyright [yyyy] [name of copyright owner] 190 | 191 | Licensed under the Apache License, Version 2.0 (the "License"); 192 | you may not use this file except in compliance with the License. 193 | You may obtain a copy of the License at 194 | 195 | http://www.apache.org/licenses/LICENSE-2.0 196 | 197 | Unless required by applicable law or agreed to in writing, software 198 | distributed under the License is distributed on an "AS IS" BASIS, 199 | WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. 200 | See the License for the specific language governing permissions and 201 | limitations under the License. 202 | -------------------------------------------------------------------------------- /autoware_v2x_msgs/doc/virtual-gate-nodes.drawio.svg: -------------------------------------------------------------------------------- 1 | 11 | 12 | 13 | 14 | 15 | 16 | 17 | 18 | 19 |
20 |
21 |
22 | planning 23 |
24 | component 25 |
26 |
27 |
28 |
29 | planning... 30 |
31 |
32 | 33 | 34 | 35 | 36 |
40 |
41 |
42 | v2x component 43 |
44 |
45 |
46 |
47 | v2x component 48 |
49 |
50 | 51 | 52 | 53 | 54 | 55 | 56 | 57 | 58 |
62 |
63 |
64 | virtual gate command 65 |
66 |
67 |
68 |
69 | virtual gate command 70 |
71 |
72 | 73 | 74 | 75 | 76 | 77 | 78 |
82 |
83 |
84 | virtual gate status 85 |
86 |
87 |
88 |
89 | virtual gate status 90 |
91 |
92 | 93 | 94 | 95 | 96 | 97 | 98 | 99 | 100 | 101 | 102 |
106 |
107 |
108 | Area 1 109 |
110 | (supports protocol A) 111 |
112 |
113 |
114 |
115 | Area 1... 116 |
117 |
118 | 119 | 120 | 121 | 122 |
126 |
127 |
128 | Area 2 129 |
130 | (supports protocol A) 131 |
132 |
133 |
134 |
135 | Area 2... 136 |
137 |
138 | 139 | 140 | 141 | 142 |
146 |
147 |
148 | driver 149 |
150 | (for protocol A) 151 |
152 |
153 |
154 |
155 | driver... 156 |
157 |
158 | 159 | 160 | 161 | 162 |
166 |
167 |
168 | driver 169 |
170 | (for protocol B) 171 |
172 |
173 |
174 |
175 | driver... 176 |
177 |
178 | 179 | 180 | 181 | 182 |
186 |
187 |
188 | Area 3 189 |
190 | (supports protocol B) 191 |
192 |
193 |
194 |
195 | Area 3... 196 |
197 |
198 | 199 | 200 | 201 | 202 | 203 | 204 | 205 | 206 | 207 | 208 | 209 | 210 | 211 |
212 |
213 |
214 | router 215 |
216 |
217 |
218 |
219 | router 220 |
221 |
222 |
223 | 224 | 225 | 226 | Text is not SVG - cannot display 227 | 228 | 229 |
230 | --------------------------------------------------------------------------------