Skip to content

Protocol Documentation#

Table of Contents#

Top

autoware_auto_control_msgs.proto#

AckermannControlCommand#

Field Type Label Description
stamp builtin_interfaces.Time
lateral AckermannLateralCommand
longitudinal LongitudinalCommand

AckermannLateralCommand#

Field Type Label Description
stamp builtin_interfaces.Time
steering_tire_angle float
steering_tire_rotation_rate float

LongitudinalCommand#

Field Type Label Description
stamp builtin_interfaces.Time
speed float
acceleration float
jerk float

Top

autoware_auto_vehicle_msgs.proto#

GearCommand#

Field Type Label Description
stamp builtin_interfaces.Time
command GearCommand_Constants

GearCommand_Constants#

Name Number Description
NONE 0
NEUTRAL 1
DRIVE 2
DRIVE_2 3
DRIVE_3 4
DRIVE_4 5
DRIVE_5 6
DRIVE_6 7
DRIVE_7 8
DRIVE_8 9
DRIVE_9 10
DRIVE_10 11
DRIVE_11 12
DRIVE_12 13
DRIVE_13 14
DRIVE_14 15
DRIVE_15 16
DRIVE_16 17
DRIVE_17 18
DRIVE_18 19
REVERSE 20
REVERSE_2 21
PARK 22
LOW 23
LOW_2 24

Top

builtin_interfaces.proto#

Duration#

Protobuf definition of builtin_interface/msg/Duration type in ROS 2.

Field Type Label Description
sec int32 The seconds component, valid over all int32 values.
nanosec uint32 The nanoseconds component, valid in the range [0, 10e9).

Time#

Protobuf definition of builtin_interface/msg/Time type in ROS 2.

Field Type Label Description
sec int32 The seconds component, valid over all int32 values.
nanosec uint32 The nanoseconds component, valid in the range [0, 10e9).

Top

geometry_msgs.proto#

Accel#

Protobuf definition of geometry_msgs/msg/Accel type in ROS 2.

Field Type Label Description
linear Vector3 Linear acceleration
angular Vector3 Angular acceleration

Point#

Protobuf definition of geometry_msgs/msg/Point type in ROS 2.

Field Type Label Description
x double X value in a cartesian coordinate.
y double Y value in a cartesian coordinate.
z double Z value in a cartesian coordinate.

Pose#

Protobuf definition of geometry_msgs/msg/Pose type in ROS 2.

Field Type Label Description
position Point Position of the pose.
orientation Quaternion Orientation of the pose.

Quaternion#

Protobuf definition of geometry_msgs/msg/Quaternion type in ROS 2.

Field Type Label Description
x double X value in a quaternion. (0 <= x <= 1)
y double Y value in a quaternion. (0 <= y <= 1)
z double Z value in a quaternion. (0 <= z <= 1)
w double W value in a quaternion. (0 <= w <= 1)

Twist#

Protobuf definition of geometry_msgs/msg/Twist type in ROS 2.

Field Type Label Description
linear Vector3 Linear velocity
angular Vector3 Angular velocity

Vector3#

Protobuf definition of geometry_msgs/msg/Vector3 type in ROS 2.

Field Type Label Description
x double First variable in vector
y double Second variable in vector
z double Third variable in vector

Top

rosgraph_msgs.proto#

Clock#

Protobuf definition of the rosgraph_msgs/msg/Clock type in ROS 2.

Field Type Label Description
clock builtin_interfaces.Time Describe current ros time.

Top

simulation_api_schema.proto#

AttachDetectionSensorRequest#

Requests attaching detection sensor to the target entity.

Field Type Label Description
configuration DetectionSensorConfiguration Configuration of the detection sensor.

AttachDetectionSensorResponse#

Response of attaching detection sensor to the target entity.

Field Type Label Description
result Result Result of AttachDetectionSensorRequest

AttachImuSensorRequest#

Requests attaching a imu sensor to the target entity.

Field Type Label Description
configuration ImuSensorConfiguration Configuration of the imu sensor.

AttachImuSensorResponse#

Requests attaching a imu sensor to the target entity.

Field Type Label Description
result Result Result of AttachImuSensorRequest

AttachLidarSensorRequest#

Requests attaching a lidar sensor to the target entity.

Field Type Label Description
configuration LidarConfiguration Configuration of the lidar sensor.

AttachLidarSensorResponse#

Response of attaching a lidar sensor to the target entity.

Field Type Label Description
result Result Result of AttachLidarSensorRequest

AttachOccupancyGridSensorRequest#

Requests attaching detection sensor to the target entity.

Field Type Label Description
configuration OccupancyGridSensorConfiguration Configuration of the occupancy grid sensor.

AttachOccupancyGridSensorResponse#

Response of attaching occupancy grid sensor to the target entity.

Field Type Label Description
result Result Result of AttachOccupancyGridSensorRequest

AttachPseudoTrafficLightDetectorRequest#

Requests attaching a traffic light detector emulator.

Field Type Label Description
configuration PseudoTrafficLightDetectorConfiguration Configuration of the traffic light detector emulator.

AttachPseudoTrafficLightDetectorResponse#

Response of attaching a traffic light detector emulator.

Field Type Label Description
result Result Result of AttachPseudoTrafficLightDetectorRequest

DespawnEntityRequest#

Requests despawning entity.

Field Type Label Description
name string Name of the entity you want to despawn.

DespawnEntityResponse#

Response of despawning entity.

Field Type Label Description
result Result Result of DespawnEntityRequest

DetectionSensorConfiguration#

Parameter configuration of the detection sensor

Field Type Label Description
entity string Name of the entity which you want to attach detection sensor.
update_duration double Update duration of the detection sensor. (unit : second)
range double Sensor detection range. (unit : meter)
architecture_type string Autoware architecture type.
detect_all_objects_in_range bool If false, simulator publish detection result only lidar ray was hit. If true, simulator publish detection result of entities in range.
pos_noise_stddev double standard deviation of position noise.
random_seed int32 random_seed for noise generation.
probability_of_lost double probability of lost recognition. (0.0 ~ 1.0)
object_recognition_delay double object recognition delay. (unit : second) It delays only the position recognition.
object_recognition_ground_truth_delay double object recognition ground truth delay. (unit : second) It delays only the position recognition.

EntityStatus#

Entity status passed over the protobuf interface

Field Type Label Description
type traffic_simulator_msgs.EntityType Type of the entity.
subtype traffic_simulator_msgs.EntitySubtype subtype of the entity.
time double Current simulation time.
name string Name of the entity.
action_status traffic_simulator_msgs.ActionStatus Action status of the entity.
pose geometry_msgs.Pose Pose in map coordinate of the entity.

ImuSensorConfiguration#

Parameter configuration of the imu sensor

Field Type Label Description
entity string Name of the entity which you want to attach imu.
frame_id string Frame ID for the IMU sensor
add_gravity bool If true, gravity will be added to the acceleration vector
use_seed bool If true, as seed will be used the passed value, if not it will be random
seed int32 Seed for random number generator
noise_standard_deviation_orientation double The standard deviation for orientation noise (normal distribution, mean = 0.0)
noise_standard_deviation_twist double The standard deviation for angular velocity noise (normal distribution, mean = 0.0)
noise_standard_deviation_acceleration double The standard deviation for linear acceleration noise (normal distribution, mean = 0.0)

InitializeRequest#

Requests initializing simulation.

Field Type Label Description
realtime_factor double Realtime factor of the simulation.
step_time double Step time of the simulation.
initialize_time double Simulation time at initialization
initialize_ros_time builtin_interfaces.Time ROS time at initialization
lanelet2_map_path string Path to lanelet2 map file

InitializeResponse#

Result of initializing simulation.

Field Type Label Description
result Result Result of InitializeRequest

LidarConfiguration#

Parameter configuration of the lidar sensor

Field Type Label Description
entity string Name of the entity which you want to attach lidar.
horizontal_resolution double Horizontal resolutions of the lidar. (unit : radian)
vertical_angles double repeated Vertical resolutions of the lidar. (unit : radian)
scan_duration double Scan duration of the lidar. (unit: second)
architecture_type string Autoware architecture type.
lidar_sensor_delay double lidar sensor delay. (unit : second) It delays publishing timing.

OccupancyGridSensorConfiguration#

Parameter configuration of the occupancy grid sensor

Field Type Label Description
entity string Name of the entity which you want to attach detection sensor.
update_duration double Update duration of the detection sensor. (unit : second)
resolution double Resolution of the occupancy grid. (unit : meter)
width uint32 Width of the occupancy grid. (unit : pixel)
height uint32 Height of the occupancy grid. (unit : pixel)
architecture_type string Autoware architecture type.
range double Sensor detection range. (unit : meter)
filter_by_range bool If false, simulator publish detection result only lidar ray was hit. If true, simulator publish detection result of entities in range.

PseudoTrafficLightDetectorConfiguration#

Parameter configuration of the traffic light detector emulator

Field Type Label Description
architecture_type string Autoware architecture type.

Result#

Result of the request

Field Type Label Description
success bool If true, the request was succeeded
description string Description of why the request was failed.

SimulationRequest#

Universal message for Request

Field Type Label Description
initialize InitializeRequest
update_frame UpdateFrameRequest
spawn_vehicle_entity SpawnVehicleEntityRequest
spawn_pedestrian_entity SpawnPedestrianEntityRequest
spawn_misc_object_entity SpawnMiscObjectEntityRequest
despawn_entity DespawnEntityRequest
update_entity_status UpdateEntityStatusRequest
attach_lidar_sensor AttachLidarSensorRequest
attach_detection_sensor AttachDetectionSensorRequest
attach_occupancy_grid_sensor AttachOccupancyGridSensorRequest
update_traffic_lights UpdateTrafficLightsRequest
attach_pseudo_traffic_light_detector AttachPseudoTrafficLightDetectorRequest
update_step_time UpdateStepTimeRequest
attach_imu_sensor AttachImuSensorRequest

SimulationResponse#

Universal message for Response

Field Type Label Description
initialize InitializeResponse
update_frame UpdateFrameResponse
spawn_vehicle_entity SpawnVehicleEntityResponse
spawn_pedestrian_entity SpawnPedestrianEntityResponse
spawn_misc_object_entity SpawnMiscObjectEntityResponse
despawn_entity DespawnEntityResponse
update_entity_status UpdateEntityStatusResponse
attach_lidar_sensor AttachLidarSensorResponse
attach_detection_sensor AttachDetectionSensorResponse
attach_occupancy_grid_sensor AttachOccupancyGridSensorResponse
update_traffic_lights UpdateTrafficLightsResponse
attach_pseudo_traffic_light_detector AttachPseudoTrafficLightDetectorResponse
update_step_time UpdateStepTimeResponse
attach_imu_sensor AttachImuSensorResponse

SpawnMiscObjectEntityRequest#

Requests spawning misc object entity

Field Type Label Description
parameters traffic_simulator_msgs.MiscObjectParameters Parameters of misc object entity.
asset_key string Asset key of the entity simulator entity
pose geometry_msgs.Pose Entity initial pose

SpawnMiscObjectEntityResponse#

Response of spawning misc object entity

Field Type Label Description
result Result Result of SpawnPedestrianEntityResponse

SpawnPedestrianEntityRequest#

Requests spawning pedestrian entity.

Field Type Label Description
parameters traffic_simulator_msgs.PedestrianParameters Parameters of pedestrian entity.
asset_key string Asset key of the entity simulator entity
pose geometry_msgs.Pose Entity initial pose

SpawnPedestrianEntityResponse#

Response of spawning vehicle entity.

Field Type Label Description
result Result Result of SpawnPedestrianEntityResponse

SpawnVehicleEntityRequest#

Requests spawning vehicle entity.

Field Type Label Description
parameters traffic_simulator_msgs.VehicleParameters Parameters of vehicle entity.
is_ego bool If true, the entity is Ego vehicle. (Autoware vehicle.)
asset_key string Asset key of the entity simulator entity
pose geometry_msgs.Pose Entity initial pose
initial_speed double Entity initial speed

SpawnVehicleEntityResponse#

Response of spawning vehicle entity.

Field Type Label Description
result Result Result of SpawnVehicleEntityResponse

TrafficLight#

Field Type Label Description
color TrafficLight.Color
shape TrafficLight.Shape
status TrafficLight.Status
confidence float

TrafficSignal#

Field Type Label Description
id int32
traffic_light_status TrafficLight repeated

UpdateEntityStatusRequest#

Requests updating entity status.

Field Type Label Description
status EntityStatus repeated List of updated entity status in traffic simulator.
npc_logic_started bool Npc logic started flag
overwrite_ego_status bool

UpdateEntityStatusResponse#

Response of updating entity status.

Field Type Label Description
result Result Result of UpdateEntityStatusRequest
status UpdatedEntityStatus repeated List of updated entity status in sensor/dynamics simulator

UpdateFrameRequest#

Requests updating simulation frame.

Field Type Label Description
current_simulation_time double
current_scenario_time double
current_ros_time builtin_interfaces.Time

UpdateFrameResponse#

Response of updating simulation frame.

Field Type Label Description
result Result Result of UpdateFrameRequest

UpdateStepTimeRequest#

Requests updating simulation step time.

Field Type Label Description
simulation_step_time double

UpdateStepTimeResponse#

Response of updating simulation step time.

Field Type Label Description
result Result Result of UpdateStepTimeRequest

UpdateTrafficLightsRequest#

Requests updating traffic lights in simulation.

Field Type Label Description
states TrafficSignal repeated

UpdateTrafficLightsResponse#

Response of updating traffic lights in simulation.

Field Type Label Description
result Result Result of DespawnEntityRequest

UpdatedEntityStatus#

Updated entity status by the simulator.

Field Type Label Description
name string Name of the entity.
action_status traffic_simulator_msgs.ActionStatus Action status of the entity.
pose geometry_msgs.Pose Pose of the entity in the map coordinate.

TrafficLight.Color#

Name Number Description
RED 0
AMBER 1
GREEN 2
WHITE 3
UNKNOWN_COLOR 4

TrafficLight.Shape#

Name Number Description
CIRCLE 0
LEFT_ARROW 1
RIGHT_ARROW 2
UP_ARROW 3
UP_LEFT_ARROW 4
UP_RIGHT_ARROW 5
DOWN_ARROW 6
DOWN_LEFT_ARROW 7
DOWN_RIGHT_ARROW 8
CROSS 9
UNKNOWN_SHAPE 10

TrafficLight.Status#

Name Number Description
SOLID_OFF 0
SOLID_ON 1
FLASHING 2
UNKNOWN_STATUS 3

Top

std_msgs.proto#

Protobuf definition of std_msgs::msgs::Header type in ROS 2.

Field Type Label Description
stamp builtin_interfaces.Time Two-integer timestamp that is expressed as seconds and nanoseconds.
frame_id string Transform frame with which this data is associated.

Top

traffic_simulator_msgs.proto#

ActionStatus#

Protobuf definition of traffic_simulator_msgs/msg/ActionStatus type in ROS 2.

Field Type Label Description
current_action string Current action of the entity.
twist geometry_msgs.Twist Velocity of the entity.
accel geometry_msgs.Accel Acceleration of the entity.
linear_jerk double Linear jerk of the entity.

Axle#

Protobuf definition of traffic_simulator_msgs/msg/Axle type in ROS 2.

Field Type Label Description
max_steering double Max steering of the entity axle.
wheel_diameter double Wheel diameter of the entity axle.
track_width double Track width of the entity axle.
position_x double Position x of the entity axle.(longitudinal)
position_z double Position z of the entity axle.(lateral)

Axles#

Protobuf definition of traffic_simulator_msgs/msg/Axles type in ROS 2.

Field Type Label Description
front_axle Axle Parameters of the front axle of the entity.
rear_axle Axle Parameters of rear axle of the entity.

BoundingBox#

Protobuf definition of traffic_simulator_msgs/msg/BoundingBox type in ROS 2.

Field Type Label Description
center geometry_msgs.Point Center point of the bounding box.
dimensions geometry_msgs.Vector3 Size of the bounding box.

EntityStatus#

Protobuf definition of traffic_simulator_msgs/msg/EntityStatus type in ROS 2.

Field Type Label Description
type EntityType Type of the entity.
subtype EntitySubtype subtype of the entity.
time double Current simulation time.
name string Name of the entity.
bounding_box BoundingBox Bounding box of the entity.
action_status ActionStatus Action status of the entity.
pose geometry_msgs.Pose Pose in map coordinate of the entity.
lanelet_pose LaneletPose Pose in lane coordinate of the entity.
lanelet_pose_valid bool If true, the lane matching of the entity is succeeded.

EntitySubtype#

Protobuf definition of traffic_simulator_msgs/msg/EntitySubtype type in ROS 2.

Field Type Label Description
value EntitySubtype.Enum

EntityType#

Field Type Label Description
type EntityType.Enum

LaneletPose#

Protobuf definition of traffic_simulator_msgs/msg/LaneletPose type in ROS 2.

Field Type Label Description
lanelet_id int64 Lanelet id of the entity exists.
s double S value in the lane coordinate.
offset double Offset value in the lane coordinate.
rpy geometry_msgs.Vector3 RPY(roll/pitch/yaw) value in the lane coordinate.

MiscObjectParameters#

Field Type Label Description
name string Name of the pedestrian entity.
bounding_box BoundingBox Bounding box of the pedestrian entity.

PedestrianParameters#

Protobuf definition of traffic_simulator_msgs/msg/PedestrianParameters type in ROS 2.

Field Type Label Description
name string Name of the pedestrian entity.
bounding_box BoundingBox Bounding box of the pedestrian entity.

Performance#

Protobuf definition of traffic_simulator_msgs/msg/Performance type in ROS 2.

Field Type Label Description
max_speed double Max speed of the entity.
max_acceleration double Max acceleration of the entity.
max_acceleration_rate double Max acceleration rate of the entity.
max_deceleration double Max deceleration of the entity.
max_deceleration_rate double Max deceleration rate of the entity.

Polyline#

Protobuf definition of traffic_simulator_msgs/msg/Polyline type in ROS 2.

Field Type Label Description
vertices Vertex repeated

PolylineTrajectory#

Protobuf definition of traffic_simulator_msgs/msg/PolylineTrajectory type in ROS 2.

Field Type Label Description
initial_distance_offset double
dynamic_constraints_ignorable bool
base_time double
closed bool
shape Polyline

Property#

Protobuf definition of traffic_simulator_msgs/msg/Property type in ROS 2.

VehicleCommand#

Field Type Label Description
ackermann_control_command autoware_auto_control_msgs.AckermannControlCommand
gear_command autoware_auto_vehicle_msgs.GearCommand

VehicleParameters#

Protobuf definition of traffic_simulator_msgs/msg/VehicleParameters type in ROS 2.

Field Type Label Description
name string Name of the vehicle entity
performance Performance Performance parameter of vehicle entity.
bounding_box BoundingBox Bounding box of the vehicle entity.
axles Axles Axles of the vehicle entity.
property Property Other parameters of the vehicle entity.

Vertex#

Protobuf definition of traffic_simulator_msgs/msg/Vertex type in ROS 2.

Field Type Label Description
time double
position geometry_msgs.Pose

Waypoints#

Protobuf definition of traffic_simulator_msgs/msg/Waypoints type in ROS 2.

Field Type Label Description
waypoints geometry_msgs.Point repeated Waypoints of the entity.

EntitySubtype.Enum#

Name Number Description
UNKNOWN 0 The entity is unknown object
CAR 1 The entity is car like a passenger vehicle
TRUCK 2 The entity is truck
BUS 3 The entity is bus
TRAILER 4 The entity is trailer
MOTORCYCLE 5 The entity is motorcycle
BICYCLE 6 THe entity is bicycle
PEDESTRIAN 7 The entity is pedestrian

EntityType.Enum#

Name Number Description
EGO 0 Ego Vehicle (Autoware Vehicle)
VEHICLE 1 Vehicle Entity (NPC Vehicle)
PEDESTRIAN 2 Pedestrian Entity (NPC Pedestrian)
MISC_OBJECT 3 Misc Object Entity (Static Objects in environment like cones)

Scalar Value Types#

.proto Type Notes C++ Java Python Go C# PHP Ruby
double double double float float64 double float Float
float float float float float32 float float Float
int32 Uses variable-length encoding. Inefficient for encoding negative numbers – if your field is likely to have negative values, use sint32 instead. int32 int int int32 int integer Bignum or Fixnum (as required)
int64 Uses variable-length encoding. Inefficient for encoding negative numbers – if your field is likely to have negative values, use sint64 instead. int64 long int/long int64 long integer/string Bignum
uint32 Uses variable-length encoding. uint32 int int/long uint32 uint integer Bignum or Fixnum (as required)
uint64 Uses variable-length encoding. uint64 long int/long uint64 ulong integer/string Bignum or Fixnum (as required)
sint32 Uses variable-length encoding. Signed int value. These more efficiently encode negative numbers than regular int32s. int32 int int int32 int integer Bignum or Fixnum (as required)
sint64 Uses variable-length encoding. Signed int value. These more efficiently encode negative numbers than regular int64s. int64 long int/long int64 long integer/string Bignum
fixed32 Always four bytes. More efficient than uint32 if values are often greater than 2^28. uint32 int int uint32 uint integer Bignum or Fixnum (as required)
fixed64 Always eight bytes. More efficient than uint64 if values are often greater than 2^56. uint64 long int/long uint64 ulong integer/string Bignum
sfixed32 Always four bytes. int32 int int int32 int integer Bignum or Fixnum (as required)
sfixed64 Always eight bytes. int64 long int/long int64 long integer/string Bignum
bool bool boolean boolean bool bool boolean TrueClass/FalseClass
string A string must always contain UTF-8 encoded or 7-bit ASCII text. string String str/unicode string string string String (UTF-8)
bytes May contain any arbitrary sequence of bytes. string ByteString str []byte ByteString string String (ASCII-8BIT)