Skip to main content
Skip table of contents

gRPC Messages


Message Definition

Ego

EgoState

No

Name

Type

Unit

Remarks

1

unique_id

string

-

object’s unique id value

2

acceleration

Vector3

m/s2

ego vehicle’s current acceleration vector value

3

position

Vector3

m

ego vehicle’s current position

4

velocity

Vector3

km/h

ego vehicle’s current speed vector value

5

rotation

Vector3

deg

refers to the vehicle’s heading(deg)

6

accel

float32

-

It has a state value of 0 to 1 of the acceleration pedal of the vehicle.

7

brake

float32

-

It has a state value of 0 to 1 of the brake pedal of the vehicle.

8

front_wheel_angle

float32

rad

Vehicle's current front wheel angle value

9

link_id

MGeoInfo

 

link information of current driving

10

is_pass_dest_pos

bool

 

whether it arrives its destination or not

11

remaining_distance

float

m

remaining distance to its destination

12

tl_id

string

 

Traffic light id adjacent to vehicle driving direction

13

tl_color

TrafficLight.LightColor

 

The color of the traffic light adjacent to the traveling direction of the vehicle.

SetEgoParam

No

Name

Type

Unit

Remarks

1

position

vector3

 

 

2

rotation

Vector3

deg

 

3

velocity

float

 

 

4

cruise_settings

EgoCruiseCtrl

 

cruise mode setting

5

pause

bool

 

whether the vehicle pauses or not

EgoCtrlCmd

No

Name

Type

Unit

Remarks

1

longCmdType

int32

 

index that determines how to control


1: Throttle control, 2: Velocity control, 3: Acceleration control

2

accel

float64

-

It means the acceleration pedal value of the vehicle and has a range of 0 to 1.

3

brake

float64

-

It means the brake pedal value of the vehicle and has a range of 0 to 1.

4

steering

float64

rad

It means a front wheel angle of the vehicle and is in Rad units.

5

velocity

float64

km/h

(Only active if CmdType == 2)

6

acceleration

float64

m/s2

(Only active if CmdType == 3)

EgoCruiseCtrl

No

Name

Type

Unit

Remarks

1

cruise_on

bool

 

whether to use cruise control mode

2

cruise_type

enum Velocity

 

ex)
EgoCruiseCtrl.LINK

EgoCruiseCtrl.CONSTANT

3

link_speed_ratio

int32

 

ratio of the current Link speed limit

4

constant_velocity

float

km/h

target driving speed


MultiEgo

MultiEgoStateList

list of MultiEgoState

No

Name

Type

Unit

Remarks

1

service_name

string

-

Object’s unique id value

2

multi_ego_state_list

List<MultiEgoState>

 

 

MultiEgoState

No

Name

Type

Unit

Remarks

1

unique_id

string

 

Object’s unique id value

2

acceleration

Vector3

m/s2

current acceleration vector value of ego vehicle

3

position

Vector3

m

ego vehicle’s current position

4

velocity

Vector3

km/h

ego vehicle’s current velocity vector value

5

rotation

Vector3

deg

indicates vehicle heading(deg)

6

accel

float32

-

It has a state value of 0 to 1 of the acceleration pedal of the vehicle.

7

brake

float32

-

It has a state value of 0 to 1 of the brake pedal of the vehicle.

8

front_wheel_angle

float32

rad

Vehicle's current front wheel angle value

9

link_id

MGeoInfo

 

link information in driving

10

is_pass_dest_pos

bool

 

whether to arrive at the destination

11

remaining_distance

float

m

remaining distance to destination

12

tl_id

string

 

traffic lights adjacent to the vehicle's direction of travel(traffic light) id

13

tl_color

TrafficLight.LightColor

 

The color of the traffic light adjacent to the traveling direction of the vehicle.

MultiEgoCtrlCmdList

list of MultiEgoCtrlCmd

No

Name

Type

Unit

Remarks

1

service_name

string

2

multi_ego_ctrl_cmd

List<MultiEgoCtrlCmd>

MultiEgoCtrlCmd

No

Name

Type

Unit

Remarks

1

unique_id

string

 

Object’s unique id value

2

longCmdType

int32

 

index that determines how to control
1: Throttle control, 2: Velocity control, 3: Acceleration control

3

accel

float64

-

It means the acceleration pedal value of the vehicle and has a range of 0 to 1.

4

brake

float64

-

It means the brake pedal value of the vehicle and has a range of 0 to 1.

5

steering

float64

rad

It means a wheel angle in front of the vehicle and is in Rad units.

6

velocity

float64

km/h

(Only active if CmdType == 2)

7

acceleration

float64

m/s2

(Only active if CmdType == 3)

MultiEgoEventCmdRequestList

list of MultiEgoEventCmdRequest

No

Name

Type

Unit

Remarks

1

service_name

string

2

cmd_list

List<MultiEgoEventCmdRequest>

MultiEgoEventCmdRequest

No

Name

Type

Unit

Remarks

1

unique_id

string

 

unique id of vehicle to be controlled

2

option

int8

 

Field Options Requesting Event Control

(Bit-wise operation)

(1: ctrl_mode, 2:gear, 4:lamps (fields 4 and 5), 8:set_pause)

3

ctrl_mode

int32

 

Vehicle’s control mode control (1: Keyboard 2: Game Wheel, 3: Automode, 4: cruise mode)

4

gear

int32

 

Vehicle gear change (-1: Maintain previous state,

1: P, 2: R, 3: N, 4: D)

5

turn_signal

int8

 

Turn signal control (0:No signal, 1:Left, 2:Right, 3:Leave)

6

emergency_signal

int8

 

Turn signal control (0: No signal, 1: Emergency signal)

7

set_pause

bool

 

True: remain in Pause state

False: Switch to play state

MultiEgoEventCmdResponseList

list of MultiEgoEventCmdResponse

No

Name

Type

Unit

Remarks

1

service_name

string

2

res_list

List<MultiEgoEventCmdResponse>

MultiEgoEventCmdResponse

No

Name

Type

Unit

Remarks

1

unique_id

string

 

vehicle’s unique id

2

ctrl_mode

int32

 

The present state of vehicle’s control mode

3

gear

int32

 

current gear condition of vehicle
(1: Keyboard 2: GameWheel, 3: automode, 4: cruisemode)

4

turn_signal

int8

 

turn signal current state
(0: No signal, 1: Left, 2: Right, 3: maintenance of previous status)

5

emergency_signal

int8

 

turn signal current state
(0: No signal, 1: Emergency signal)

6

set_pause

bool

 

whether to pause or not

CreateMultiEgoVehicleRequestList

list of CreateMultiEgoVehicleRequest

No

Name

Type

Unit

Remarks

1

service_name

string

2

req_list

List<CreateMultiEgoVehicleRequest>

CreateMultiEgoVehicleRequest

No

Name

Type

Unit

Remarks

1

unique_id

string

 

Specify the unique id of the Multi-Ego Vehicle to be generated

2

position

Vector3

m

Initial position

3

rotation

Vector3

deg

Initial direction (heading)

4

velocity

float64

km/h

Initial speed

5

vehicleName

string

 

The name of the vehicle to be created (ex: 2016_Hyundai_Ioniq)

6

pause

bool

 

True: Keep the pause state of Simulator

False: Switch to play state of Simulator

DeleteMultiEgoVehicleRequest

No

Name

Type

Unit

Remarks

1

req_delete

bool

ServiceRequest

No

Name

Type

Unit

Remarks

1

service_name

string

2

msg

string

ServiceResponse

No

Name

Type

Unit

Remarks

1

service_name

string

Ego vehicle : “/morai_msgs/EgoState“
Multi-Ego vehicle : “/morai_msgs/MultiEgoState“

2

msg

string

Ego Vehicle : EgoState
Multi-Ego Vehicle : list of MultiEgoState


Map

No

Name

Type

Unit

Remarks

1

map_name

string

 

In the case of the map name NOTE Asset Bundle Map to be executed, it is called as follows.
”V_Extra_Scene,asset_bundle_map_name

2

ego_name

string

 

Ego vehicle’s model name

Result

No

Name

Type

Unit

Remarks

1

success

bool

 

procedure execution result

2

description

string

 

procedure execution result information

Scenario

No

Name

Type

Unit

Remarks

1

scenario_filename

string

 

MORAI SIM’s scenario file name

Empty

Empty message ( ≈ null message)

Vector3

No

Name

Type

Unit

Remarks

1

x

double

2

y

double

3

z

double

ActorResponseList

list of ActorResponse

No

Name

Type

Unit

Remarks

2

res_list

List<ActorResponse>

ActorResponse

No

Name

Type

Unit

Remarks

1

result

bool

 

request success or fail

2

actor_name

string

 

unique id requested from client

3

display_name

string

 

unique id displayed in Simulator


Open Scenario

StartRequest

No

Name

Type

Unit

Remarks

1

service_name

string

 

“/morai_msgs/StartCmd“

2

cmd_start

bool

 

whether to start or not

StopRequest

No

Name

Type

Unit

Remarks

1

service_name

string

 

“/morai_msgs/StopCmd“

2

cmd_start

bool

 

whether to stop or not


MGeoInfo

No

Name

Type

Unit

Remarks

1

result

bool

 

get link information success or fail

2

link_id

string

 

link id

3

waypoint

int64

 

way point index inside link

LinkInfo

No

Name

Type

Unit

Remarks

1

unique_id

string

Link ID

2

index

int

wayPoint index

GetLinkResponseList

list of GetLinkResponse

No

Name

Type

Unit

Remarks

1

result

bool

2

res_list

List<LinkInfo>

GetLinkResponse

No

Name

Type

Unit

Remarks

1

result

bool

 

True: the link exists
False: no such link

2

unique_id

string

 

link id

GetVehiclesOnLinkResponseList

No

Name

Type

Unit

Remarks

1

result

bool

 

True: the link exists
False: no such link

2

res_list

List<VehicleInfo>

 

list of vehicle unique id


Pedestrian

PedestrianSpawnList

list of PedestrianSpawn

No

Name

Type

Unit

Remarks

1

req_list

List<PedestrianSpawn>

PedestrianSpawn

No

Name

Type

Unit

Remarks

1

unique_id

string

 

pedestrian’s unique id

2

position

Vector3

 

position to spawn

3

rotation

Vector3

 

direction to spawn

4

velocity

float

km/h

pedestrian moving speed

5

active_dist

float

m

detection range

6

move_dist

float

m

moving distance

7

pedestrian_name

string

 

pedestrian model name

8

start_action

bool

 

Whether or not pedestrian walking starts after spawn.

PedestrianActionList

list of PedestrianAction

No

Name

Type

Unit

Remarks

1

req_list

List<PedestrianAction>

PedestrianAction

No

Name

Type

Unit

Remarks

1

unique_id

string

 

pedestrian unique id


Driving Path

VehicleInfo

No

Name

Type

Unit

Remarks

1

unique_id

string

 

vehicle unique id

RouteList

list of VehicleRoute

No

Name

Type

Unit

Remarks

1

req_list

List<VehicleRoute>

VehicleRoute

No

Name

Type

Unit

Remarks

1

unique_id

string

 

vehicle unique id

2

obj_type

enum Type

 

ex)
VehicleRoute.EGO

3

link_list

List<LinkInfo>

 

vehicle path information

DestinationList

list of VehicleDestination

No

Name

Type

Unit

Remarks

1

req_list

List<VehicleDestination>

VehicleDestination

No

Name

Type

Unit

Remarks

1

unique_id

string

 

vehicle unique id

2

obj_type

enum Type

 

ex)
VehicleDestination.EGO

3

decision_range

float

m

Destination proximity detection range

4

position

vector3

 

Destination coordinates

VehicleRouteResultList

list of VehicleRouteResult

No

Name

Type

Unit

Remarks

1

res_list

List<VehicleRouteResult>

VehicleRouteResult

No

Name

Type

Unit

Remarks

1

success

bool

2

unique_id

string

3

error_code

enum ERROR_CODE

4

description

string

5

waypoints

LinkInfo

PathOffsetList

list of PathOffset

No

Name

Type

Unit

Remarks

1

req_list

List<PathOffset>

PathOffset

No

Name

Type

Unit

Remarks

1

unique_id

string

 

vehicle unique id

2

obj_type

enum VehicleType

 

ex)
VehicleType.EGO

3

value

float

%

bias

4

lat_bias_mode

enum OffsetType

 

ex)
PathOffset.FIX

VehicleAuxStateInfoList

list of VehicleAuxStateInfo

No

Name

Type

Unit

Remarks

1

res_list

List<VehicleAuxStateInfo>

VehicleAuxStateInfo

No

Name

Type

Unit

Remarks

1

unique_id

string

 

Object’s unique id value

2

isPassDestPos

bool

 

Whether to arrive at the destination

3

destPos

Vector3

 

Destination coordinates

4

remaining_distance

float

m

Remaining distance to the destination

5

global_path

LinkInfo

 

Driving path of MGeo link path information

6

local_path

LinkInfo

 

Current MGeo link information for vehicles

7

range

float

m

decision range (decision boundary) for determining whether to arrive at the destination


Sensor

SensorSettingList

list of SensorSetting

No

Name

Type

Unit

Remarks

1

req_list

List<SensorSetting>

SensorSetting

No

Name

Type

Unit

Remarks

1

unique_id

string

 

vehicle’s unique id

2

sensor_type

enum SensorType

 

ex)
SensorType.GPS

3

position

vector3

 

Sensor attachment position

4

rotation

vector3

 

Sensor attachment direction

SensorResponseList

list of SensorResponse

No

Name

Type

Unit

Remarks

1

res_list

List<SensorResponse>

SensorResponse

No

Name

Type

Unit

Remarks

1

success

bool

 

success or fail

2

target_id

string

 

vehicle ID

3

sensor_id

string

 

sensor ID

RemoveSensor

No

Name

Type

Unit

Remarks

1

unique_id

string

 

vehicle ID

2

sensor_id

string

 

sensor ID

SetGroundTruthSensorList

list of SetGroundTruthSensor

No

Name

Type

Unit

Remarks

1

req_list

List<SetGroundTruthSensor>

SetGroundTruthSensor

No

Name

Type

Unit

Remarks

1

unique_id

string

 

vehicle ID

2

sensor_id

string

 

sensor ID

3

gt_setting

struct

 

GT sensor setting parameters

4

viz_range

bool

m

Whether GT sensor is visualized as detectable area.

TargetSensorList

list of TargetSensor

No

Name

Type

Unit

Remarks

1

req_list

List<TargetSensor>

TargetSensor

No

Name

Type

Unit

Remarks

1

unique_id

string

 

vehicle ID

2

sensor_id

string

 

sensor ID


Ground Truth

GT_setting

No

Name

Type

Unit

Remarks

1

shape_type

enum GTShapeType

 

 

2

cylinder_setting

GTCylinderSetting

 

 

3

cone_setting

GTConeSetting

 

 

4

filter

enum ObstacleObjType

 

None = 0,
Vehicle = 1,
Pedestrian = 2,
EgoVehicle = 3,
Obstacle = 4,
SpawnPoint = 5,
MovingObject = 6,
ExtraObstacle = 7,
SSAFYSpawnPoint = 8,
DestinationPoint = 9,
StopoverPoint = 10,
PedSpawnPoint = 11,
ShadedArea = 12,
MapObject = 13,
MAX = 14

5

max_count

int

 

maximum # of objects,
once it is set as -1, then it is unlimited

GTCylinderSetting

No

Name

Type

Unit

Remarks

1

segments

int

 

top plane figure

2

vertical_fov

float

deg

Field of View

3

range

float

m

cylinder length

GTConeSetting

No

Name

Type

Unit

Remarks

1

segments

int

 

top plane figure

2

vertical_fov

float

deg

Field of View

3

horizontal_fov

float

deg

Field of View

4

range_min

float

m

Detection range = {range_max - range_min, range_max}

5

range_max

float

m

6

resolution

int

 

smoothness degree of the surface of the cone(number of vertex)
maximum resolution == 10,
minimum resolution == 2

GroundTruthList

list of GroundTruth

No

Name

Type

Unit

Remarks

1

res_list

List<GroundTruth>

GroundTruth

No

Name

Type

Unit

Remarks

1

success

bool

2

data

List<ObjectStatus>


SpawnPoint

CreateSpawnPointList

list of CreateSpawnPoint

No

Name

Type

Unit

Remarks

1

req_list

List<CreateSpawnPoint>

CreateSpawnPoint

No

Name

Type

Unit

Remarks

1

unique_id

string

 

spawn point unique id

2

position

Vector3

 

spawn point position coordinates

3

sub_category

enum ScenarioETC.SUBCATEGORY

 

ex)
ScenarioETC.SPAWN_POINT

EnableSpawnPointList

list of EnableSpawnPoint

No

Name

Type

Unit

Remarks

1

req_list

List<EnableSpawnPoint>

EnableSpawnPoint

No

Name

Type

Unit

Remarks

1

unique_id

string

spawn point / pedestrian spawn point unique id

2

is_active

bool

True : enable
False : diable

SetSpawnPointList

list of SetSpawnPoint

No

Name

Type

Unit

Remarks

1

req_list

List<SetSpawnPoint>

SetSpawnPoint

No

Name

Type

Unit

Remarks

1

unique_id

string

 

unique id of spawn point

2

info

SpawnPointInfo

 

 

3

spawn_object_name

string

 

model name of spawn object

4

pause

bool

 

 

SpawnPointInfo

No

Name

Type

Unit

Remarks

1

list_vehicle_length_type

enum VehicleClass.VehicleLengthType

 

ex)
VehicleClass.VehicleLengthType.MINI

2

is_close_loop

bool

 

spawn vehicle path option

3

is_lane_change

bool

 

spawn vehicle path option

4

parameter_type

enum DesiredVelocityType.ParameterType

 

ex)
DesiredVelocityType.ParameterType.CONSTANT

5

maximum_spawn_vehicle

int32

 

maximum number of spawn vehicle

6

min_spawn_period

float

sec

spawn cycle setting

7

max_spawn_period

float

sec

spawn cycle setting

8

spawn_velocity_type

enum CruiseModeType.VelocityType

 

ex)
CruiseModeType.VelocityType.CUSTOM_VELOCITY

9

min_spawn_velocity_custom

float

km/s

set the initial speed of spawn vehicles

10

max_spawn_velocity_custom

float

km/s

set the initial speed of spawn vehicles

11

min_spawn_velocity_link

float

%

set the initial speed of spawn vehicles

12

max_spawn_velocity_link

float

%

set the initial speed of spawn vehicles

13

desired_velocity_type

enum CruiseModeType.VelocityType

 

ex)
CruiseModeType.VelocityType.CUSTOM_VELOCITY

14

min_desired_velocity_custom

float

km/s

set the target speed of spawn vehicle

15

max_desired_velocity_custom

float

km/s

set the target speed of spawn vehicle

16

min_desired_velocity_link

float

%

set the target speed of spawn vehicle

17

max_desired_velocity_link

float

%

set the target speed of spawn vehicle

18

destination_obj_unique_id

int32

 

unique id of destination

19

start_link_info

LinkInfo

 

link information of the starting point of driving

20

end_link_info

LinkInfo

 

link information of driving completion point

21

lateral_bias_mode

enum BiasMode.LatBiasMode

 

set lateral bias
ex)
BiasMode.LatBiasMode.FIX

22

min_lateral_bias

float

%

set lateral bias

23

max_lateral_bias

float

%

set lateral bias


PedestrianSpawnPoint

SetPedestrianSpawnPointList

list of SetPedestrianSpawnPoint

No

Name

Type

Unit

Remarks

1

req_list

List<SetPedestrianSpawnPoint>

SetPedestrianSpawnPoint

No

Name

Type

Unit

Remarks

1

unique_id

string

 

unique id of spawn point

2

info

PedestrianSpawnPointInfo

 

 

3

spawn_object_name

string

 

model name of spawn object

4

pause

pause

 

 

PedestrianSpawnPointInfo

No

Name

Type

Unit

Remarks

1

list_pedestrian_desination

List<PedestrianDestinationPointInfo>

 

pedestrian destination setting

2

pedestrian_random_mode

bool

 

spawn random model

3

select_mode

enum PedestrianBehavior.CHARACTER_MODE

 

ex)
PedestrianBehavior.CHARACTER_MODE.STAND

4

min_count

int32

 

minimum number of spawn

5

max_count

int23

 

maximum number of spawn

6

spawn_time

float

sec

spawn cycle

PedestrianDestinationPointInfo

No

Name

Type

Unit

Remarks

1

position

Vector3

2

rotation

Vector3

3

scale

Vector3


TrafficLight

TLInfo

No

Name

Type

Unit

Remarks

1

success

bool

2

tl_id

string

traffic light unique id

3

tl_color

enum TrafficLight.LightColor

ex)
TrafficLight.LightColor.SG

TLInfoList

list of TLInfo

No

Name

Type

Unit

Remarks

1

res_list

List<TLInfo>

TLStateParamList

list of TLStateParam

No

Name

Type

Unit

Remarks

1

req_list

List<TLStateParam>

TLStateParam

No

Name

Type

Unit

Remarks

1

tl_id

string

 

unique id of traffic light

2

tl_color

enum TrafficLight.LightColor

 

ex)
TrafficLight.LightColor.SG

3

is_impulse

bool

 

True : temporarily change traffic light color
False : permanent traffic light color change

4

set_sibling

bool

 

True : Change the color of traffic lights located on the same entry road as tl_id.
Fasle : Only change the color of traffic lights corresponding to tl_id


Intersection

IntscnStateParamList

list of IntscnStateParam

No

Name

Type

Unit

Remarks

1

req_list

List<IntscnStateParam>

IntscnStateParam

No

Name

Type

Unit

Remarks

1

intscn_id

string

 

unique id of intersection

2

state_idx

int32

 

set the state of intersection

IntscnScheduleParamList

list of IntscnScheduleParam

No

Name

Type

Unit

Remarks

1

req_list

List<IntscnScheduleParam>

IntscnScheduleParam

No

Name

Type

Unit

Remarks

1

intscn_id

string

unique id of intersection

2

tl_schedule

List<TrafficLight.TLSchedule>

3

yellow_duration

List<TrafficLight.YellowSchedule>

4

ps_schedule

List<TrafficLight.PSSchedule>

TrafficLight.TLSchedule

No

Name

Type

Unit

Remarks

1

duration

int32

sec

state duration of traffic light

2

str_light_color_list

List<string>

 

The color list that should appear in that state of traffic light

TrafficLight.YellowSchedule

No

Name

Type

Unit

Remarks

1

duration

int32

sec

duration of yellow light during state transition

TrafficLight.PSSchedule

No

Name

Type

Unit

Remarks

1

tl_state_idx

int32

 

state index

2

synced_tl_idx

int32

 

synchronized traffic light index where pedestrian traffic lights turn green together

3

before_sec

int32

sec

 

4

green_light_sec

int32

sec

duration of green light

5

flicker_light_sec

int32

sec

duration of flashing green light


FaultInjection

FaultInjectionCtrlList

list of FaultInjectionCtrl

No

Name

Type

Unit

Remarks

1

req_list

List<FaultInjectionCtrl>

FaultInjectionCtrl

No

Name

Type

Unit

Remarks

1

unique_id

string

 

unique id of vehicle

2

fault_location

int32

 

vehicle’s fault location
{2 : Accel, 3 : BRAKE, 4 : STEERING}

3

fault_class

int32

 

fault major category
{1 : Timing, 2 : Data, 3 : Hardware}

4

fault_subclass

int32

 

fault small category
The highest digit of each number below must match the fault class.
{101 : LOSS_AND_TIMEOUT,
102 : DELAYED,
201 : OPEN,
202 : SHORT,
203 : OFFSET,
204 : STUCK_IN_RANGE,
205 : OUT_OF_DATA,
206 : DRIFT_AND_OSCILLATION,
301 : PUNCTURE,
302 : TRANSFORM
}

FaultInjectionTireList

list of FaultInjectionTire

No

Name

Type

Unit

Remarks

1

req_list

List<FaultInjectionTire>

FaultInjectionTire

No

Name

Type

Unit

Remarks

1

unique_id

string

2

tire_index

int32

3

fault_class

int32

4

fault_subclass

int32

FaultInjectionSensorList

list of FaultInjectionSensor

No

Name

Type

Unit

Remarks

1

req_list

List<FaultInjectionSensor>

FaultInjectionSensor

No

Name

Type

Unit

Remarks

1

unique_id

string

2

sensor_id

string

3

fault_class

int32

4

fault_subclass

int32

5

local_position_offset

Vector3

6

local_rotation_offset

Vector3


Obstacle / Object

ObstacleSpawnList

list of ObstacleSpawn

No

Name

Type

Unit

Remarks

1

req_list

List<ObstacleSpawn>

ObstacleSpawn

No

Name

Type

Unit

Remarks

1

unique_id

string

Obstacle ID

2

position

Vector3

3

rotation

Vector3

4

scale

Vector3

5

obstacle_name

string

model name

CategoryObstacles

No

Name

Type

Unit

Remarks

1

vehicle

bool

2

pedestrian

bool

3

obstacle

bool

4

spawn_point

bool

5

map_object

bool

CreateMapObjectList

list of CreateMapObject

No

Name

Type

Unit

Remarks

1

req_list

List<CreateMapObject>

CreateMapObject

No

Name

Type

Unit

Remarks

1

unique_id

string

2

position

Vector3

3

rotation

Vector3

4

spawn_object_name

string

ObjectStatus

No

Name

Type

Unit

Remarks

1

unique_id

string

차량 ID

2

type

int

vehicle = 1,
pedestrian = 2,
obstacle = 4

3

name

string

model name

4

heading

double

deg

5

position

vector3

6

acceleration

vector3

m/s2

7

velocity

vector3

8

size

vector3

ObjectPauseList

list of ObjectPause

No

Name

Type

Unit

Remarks

1

req_list

List<ObjectPause>

ObjectPause

No

Name

Type

Unit

Remarks

1

unique_id

string

object의 unique id

2

obj_type

enum Type

set vehicle type

3

set_pause

bool

True : pause
False : Resume

TargetUniqueIdList

list of TargetUniqueId

No

Name

Type

Unit

Remarks

1

id_list

List<TargetUniqueId>

 

Object’s unique id value

TargetUniqueId

No

Name

Type

Unit

Remarks

1

unique_id

string

 

Object’s unique id value


Friction

FrctionControlAreaList

list of FrictionControlArea

No

Name

Type

Unit

Remarks

1

req_list

List<FrictionControlArea>

FrictionControlArea

No

Name

Type

Unit

Remarks

1

unique_id

string

2

vertical_radius

float

deg

3

horizontal_radius

float

deg

4

height

float

m

5

multiplier

float


Enum Type Definition

Velocity

No

Name

Type

Unit

Remarks

1

_Begin

 

 

 

2

LINK

 

 

(Link Speed Limit * drive at link_speed_ratio)

3

CONSTANT

 

 

drive at (target driving speed)

4

_End

 

 

 

Type

No

Name

Type

Unit

Remarks

1

_Begin

2

EGO

3

MULTIEGO

4

_End

VehicleType

No

Name

Type

Unit

Remarks

1

_Begin

2

EGO

3

MULTIEGO

4

_End

ERROR_CODE

No

Name

Type

Unit

Remarks

1

SUCCESS

2

FAILED

3

NULL_EXCEPTION

4

NOT_FOUND_UNIQUE_ID

5

NOT_CREATE_OBJECT

6

EMPTY_LIST

7

NOT_EGO_CRUISE_MODE

8

NOT_FOUND_LINK_ID

9

NOT_FOUND_PATH

10

DIFFERENT_START_LINK

OffsetType

No

Name

Type

Unit

Remarks

1

_Begin

 

 

 

2

FIX

 

 

fixed to a set value

3

RANDOM_GAUSSIAN

 

 

Gaussian distribution

4

_END

 

 

 

SensorType

No

Name

Type

Unit

Remarks

1

None

 

 

 

2

Camera

 

 

 

3

Lidar3D

 

 

 

4

Lidar2D

 

 

 

5

GPS

 

 

 

6

IMU

 

 

 

7

Radar

 

 

 

8

Ultrasonic

 

 

 

9

GroundTruth

 

 

get Ground Truth information

10

END

 

 

 

GTShapeType

No

Name

Type

Unit

Remarks

1

_BEGIN

2

Cylinder

3

Cone

4

_End

ScenarioETC.SUBCATEGORY

No

Name

Type

Unit

Remarks

1

_BEGIN

 

 

 

2

SPAWN_POINT

 

 

vehicle spawn point

3

PED_SPAWN_POINT

 

 

pedestrian spawn point

4

_END

 

 

 

VehicleClass.VehicleLengthType

No

Name

Type

Unit

Remarks

1

MINI

 

 

vehicle size

2

COMPACT

 

 

vehicle size

3

MIDDLE_SIZE

 

 

vehicle size

4

LARGE

 

 

vehicle size

DesiredVelocityType.ParameterType

No

Name

Type

Unit

Remarks

1

_BEGIN

 

 

 

2

CONSTANT

 

 

follow a specified target speed

3

VARIABLE

 

 

[MIN, MAX] range speed

4

_END

 

 

 

CruiseModeType.VelocityType

No

Name

Type

Unit

Remarks

1

_BEGIN

 

 

 

2

LINK_VELOCITY

 

 

Drive at (Link speed limit *link_speed_ratio)

3

CUSTOM_VELOCITY

 

 

driving at (target speed)

4

_END

 

 

 

BiasMode.LatBiasMode

No

Name

Type

Unit

Remarks

1

_BEGIN

 

 

 

2

FIX

 

 

fixed to a set value

3

RANDOM_GAUSSIAN

 

 

Gaussian distribution

4

_END

 

 

 

PedestrianBehavior.CHARACTER_MODE

No

Name

Type

Unit

Remarks

1

_BEGIN

2

ONCE

3

CLOSED_LOOP

4

REPEAT

5

LOOP

6

NEW_PATH

7

STAND

8

_END

TrafficLight.LightColor

No

Name

Type

Unit

Remarks

1

_BEGIN

2

R

Red

3

Y

Yellow

4

SG

StraightGreen

5

LG

Left

6

RG

Right Green

7

UTG

UTurnGreen

8

ULG

UpperLeftGreen

9

URG

UpperRightGreen

10

LLG

LowerLeftGreen

11

LRG

LowerRightGreen

12

R_WITH_Y

Red_WITH_Yellow

13

Y_WITH_G

Yellow_WITH_Green

14

Y_WITH_GLEFT

Yellow_WITH_GreenLEFT

15

G_WITH_GLEFT

Green_WITH_GreenLEFT

16

R_WITH_GLEFT

Red_WITH_GreenLEFT

17

LLG_SG

LowerLeftGreen_StraightGreen

18

R_LLG

Red_LowerLeftGreen

19

ULG_URG

UpperLeftGreen_UpperRightGreen

20

UNDEFINED

Traffic light does not get initialized

21

NOT_DETECTED

JavaScript errors detected

Please note, these errors can depend on your browser setup.

If this problem persists, please contact our support.