Setting up a ROS Network

To support custom ROS messages, the message source code must be built within the Linux development environment. MORAI SIM specific messages are distributed at the following link:

https://github.com/morai-developergroup/morai_msgs

For more detailed instructions in setting up the ROS environment, please refer to the ROS manual and the ROS quickstart guide.

Within the simulator, go to the Network Settings panel, select ROS from the drop-down menu for both Cmd Control and Publisher/Subscriber/Service tabs, then configure the rosbridge IP, topic names, and signal frequency.

Interface Details and Message Structure

ROS messages follow a Publish-Subscribe model, or a Service model, and are organized as such in this interface sheet.

Certain message components follow the common_msgs types maintained by ROS and are noted as such in each table’s type field.

Ego Ctrl Cmd

  • MoraiCmdController sends command messages to the ego-vehicle.

  • ROS message details

    • Message Type: morai_msg/CtrlCmd

    • Default Topic: /ctrl_cmd

No

Name

Type

Unit

Remarks

1

longCmdType

int32

Determines the control type.
1: Throttle control, 2: Velocity control, 3: Acceleration control

2

accel

float64

-

Accelerator pedal input ranges from 0 to 1

3

brake

float64

-

Brake pedal input ranges from 0 to 1

4

steering

float64

rad

Front wheel angle input in radians

5

velocity

float64

km/h

(Only active if CmdType == 2)

6

acceleration

float64

m/s2

(Only active if CmdType == 3)

Ego Vehicle Status

  • MoraiInfoPublisher returns the current state values of the ego-vehicle (simulator → user).

  • ROS message details

    • Message Type: morai_msgs/EgoVehicleStatus

    • Default Topic: /Ego_topic

    • NOTE Vehicle position is expressed in the geographic reference frame, following the ENU coordinate system (x: east, y: north, z: up)

No

Name

Type

Unit

Remarks

1

header

Header

-

Message header

2

unique_id

int32

-

Unique identifier number of the object

3

acceleration

Vector3

Current ego-vehicle acceleration

4

position

Vector3

m

Current ego-vehicle position

5

velocity

Vector3

Current ego-vehicle velocity

6

heading

float64

deg

Current heading angle value

7

accel

float32

-

Accelerator pedal input ranges from 0 to 1

8

brake

float32

-

Brake pedal input ranges from 0 to 1

9

wheel_angle

float32

rad

Current wheel angle of the front wheels

Object Info

  • MoraiObjectInfoPublisher contains information about each object placed in the scene (simulator → user).

  • ROS message details

    • Message Type: morai_msgs/ObjectStatusList

    • Default Topic: /Object_topic

No

Name

Type

Unit

Remarks

1

header

Header

-

2

num_of_npcs

int32

-

Total number of NPC vehicles placed in the scene

3

num_of_pedestrian

int32

-

Total number of pedestrians placed in the scene

4

num_of_obstacle

int32

-

Total number of obstacles (static objects) placed in the scene

5

npc_list

ObjectStatus

-

Full list of NPC vehicles

6

pedestrian_list

ObjectStatus

-

Full list of pedestrians

7

obstacle_list

ObjectStatus

-

Full list of obstacles (static objects)

Object Status

The ObjectStatus type is a message type for the object lists used in MoraiObjectInfoPublisher and does not have its own ROS topic.

  • ROS message details

    • Message Type: morai_msgs/ObjectStatus

    • NOTE Vehicle position is expressed in the geographic reference frame, following the ENU coordinate system (x: east, y: north, z: up)

No

Name

Type

Unit

Remarks

1

unique_id

int32

-

Unique identifier number of the object

2

type

int32

-

0: Pedestrian, 1: NPC vehicle, 2: Static object (obstacle), -1: Ego-vehicle

3

name

string

-

The given name of the object

4

heading

float64

-

Heading angle of the object

5

velocity

Vector3

Current object velocity

6

acceleration

Vector3

Current object acceleration

7

size

Vector3

m

Object size (width, length, height)

8

position

Vector3

m

Current object position

Multi Ego Setting

  • MultiEgoTransformHandler enables the simulator to set multiple egovehicles in the same scene, outputting all egovehicle-related variables for each unique ego-vehicle (user → simulator).

  • ROS message details

    • Message Type: morai_msgs/MultiEgoSetting

    • Default Topic: /ego_setting

No

Name

Type

Unit

Remarks

1

number_of_ego_vehicle

int32

-

The number of egovehicles to be controlled through MutliEgoSetting

2

camera_index

int32

-

The ID of the vehicle the camera is currently centered on

3

ego_index

int32[]

-

Unique identifier number of the ego-vehicle

4

global_position_x

float64[]

X-axis coordinate value of the current position

5

global_position_y

float64[]

Y-axis value of the current position

6

global_position_z

float64[]

Z-axis value of the current position (elevation)

7

global_roll

float32[]

Current roll angle value

8

global_pitch

float32[]

Current pitch angle value

9

global_yaw

float32[]

Current heading angle value

10

velocity

float32[]

Current vehicle speed

11

gear

int8[]

-

1: Parking, 2: Reverse, 3: Neutral, 4: Drive

12

ctrl_mode

int8[]

-

1: keyboard mode, 16: automode

Collision Data

  • CollisionData alerts and logs any data on ego-vehicle collision events that occur in the scene.

  • ROS message details

    • Message Type: morai_msgs/CollisionData

    • Default Topic: /CollisionData

No

Name

Type

Unit

Remarks

1

header

Header

-

2

global_offset_x

float32

The x-axis position of the collided object w.r.t the map coordinate syste

3

global_offset_y

float32

The y-axis position of the collided object w.r.t the map coordinate system

4

global_offset_z

float32

The z-axis position of the collided object w.r.t the map coordinate system

5

collision_object

ObjectStatus[]

-

Details of the collided object

NPC Vehicle Collision Data

  • VehicleCollisionInfoPublisher returns collision information between NPC vehicles.

  • ROS message details

    • Message Type: morai_msgs/VehicleCollisionData

    • Default Topic: /VehicleCollisionData

No

Name

Type

Unit

Remarks

1

header

Header

-

2

collisions

VehicleCollision[]

-

Contains a list of NPC vehicles involved in a collision

Vehicle Collision List

The VehicleCollision type is a message type for the collisions lists used in VehicleCollisionInfoPublisher and does not have its own ROS topic.

  • ROS message details

    • Message Type: morai_msgs/VehicleCollision

No

Name

Type

Unit

Remarks

1

crashed_vehicles

ObjectStatus[]

-

Full list of crashed NPC vehicles

Get Traffic Light Status

  • TLCtrlPublisher reports the current state of a traffic light.

  • ROS message details

    • Message Type: morai_msgs/GetTrafficLightStatus

    • Default Topic: /GetTrafficLightStatus

No

Name

Type

Unit

Remarks

1

header

Header

-

2

trafficLightIndex

string

-

Unique identifier string for each traffic light

3

trafficLightType

int16

-

Defines the traffic light type and configuration

0: Red/Yellow/Green
1: Red/Yellow/Green_with_left_arrow
2: Red/Yellow/Green_with_left_arrow/Green
100: Yellow/Yellow/Yellow

4

trafficLightStatus

int16

-

Defines which light is currently lit

1: Red
4: Yellow
16: Green
32: Green_with_left_arrow
-1: default (not lit)

Combined lights (multiple lights on simultaneously) can be applied using standard bitwise operations

Set Traffic Light Control

  • TLCtrlSubscriber transmits traffic light control commands.

  • ROS message details

    • Message Type: morai_msgs/SetTrafficLight

    • Default Topic: /SetTrafficLight

No

Name

Type

Unit

Remarks

1

trafficLightIndex

string

-

Unique identifier string for each traffic light

2

trafficLightStatus

int16

-

Defines which light is currently lit

1: Red
4: Yellow
16: Green
32: Green_with_left_arrow
-1: default (not lit)

Get Intersection Status

  • IntersectionStatusPublisher reports the current status of any custom intersections.

  • ROS message details

    • Message Type: morai_msgs/IntersectionStatus

    • Default Topic: /InsnStatus

No

Name

Type

Unit

Remarks

1

header

Header

-

2

intersection_index

string

-

Unique identifier string for each intersection

3

intersection_status

int16

-

Current intersection status

4

intersection_status_time

float32

-

The amount of time the intersection has maintained its current state

Set Intersection Control

  • IntersectionControlSubscriber sends control commands to the intersections for V2X applications.

  • ROS message details

    • Message Type: morai_msgs/IntersectionControl

    • Default Topic: /InsnControl

No

Name

Type

Unit

Remarks

1

header

Header

-

2

intersection_index

string

-

Unique identifier string for each intersection

3

intersection_status

int16

-

Current intersection status

4

intersection_status_time

float32

-

The amount of time the intersection has maintained its current state

Scenario Load

  • MORAISLSubscriber instructs the simulator to load specific pre-built scenarios. Users may set options to load only desired features.

  • ROS message details

    • Message Type: morai_msgs/ScenarioLoad

    • Default Topic: /ScenarioLoad

No

Name

Type

Unit

Remarks

1

file_name

string

-

The scenario file to be loaded

2

delete_all

bool

-

If True, deletes all agents in the scene before loading

3

load_network_connection_data

bool

-

If True, loads network connection settings

4

load_ego_vehicle_data

bool

-

If True, loads ego-vehicle settings data

5

load_surrounding_vehicle_data

bool

-

If True, loads NPC vehicle scenario settings data

6

load_pedestrian_data

bool

-

If True, loads pedestiran scenario settings data

7

load_object_data

bool

-

If True, loads object scenario data

8

set_pause

bool

-

Determines whether to immediately pause the simulation after the scenario loads

Save Sensor Data

  • SensorSyncDataSubscriber saves sensor data for the current simulation frame.

  • ROS message details

    • Message Type: morai_msgs/SaveSensorData

    • Default Topic: /SaveSensorData

No

Name

Type

Unit

Remarks

1

is_custom_file_name

bool

-

Determines if the save file name is custom input by the user

2

custom_file_name

string

-

The custom save file name input by the user

3

file_dir

string

-

The full path string of the save file

Turn Signal Lamp Control

  • Lamps controls the turn signal lights of the vehicle.

  • ROS message details

    • Message Type: morai_msgs/Lamps

    • Default Topic: /lamps

No

Name

Type

Unit

Remarks

1

header

Header

-

2

turnSignal

int8

-

0: No signal, 1: Left turn signal, 2: Right turn signal

3

emergencySignal

int8

-

0: No signal, 1: Emergency lamps on

Replay Info Publisher

  • MoraiReplayInfoPublisher publishes all vehicle movements when the Replay feature is used. Data is published to the user from the simulator.

  • ROS message details

    • Message Type: morai_msgs/ReplayInfo

    • Default Topic: /ReplayInfo_topic

No

Name

Type

Unit

Remarks

1

header

Header

-

2

ego_acc

float64

-

Accelerator pedal input ranges from 0 to 1

3

ego_brake

float64

-

Brake pedal input ranges from 0 to 1

4

ego_steer

float64

deg

Current wheel angle of the front wheels

5

orientation

Quaternion

-

Current orientation

6

linear_acceleration

Vector3

Current acceleration

7

angular_velocity

Vector3

Current angular velocity

8

num_of_npcs

int32

-

Total number of NPC vehicles placed in the scene

9

num_of_pedestrian

int32

-

Total number of pedestrians placed in the scene

10

num_of_obstacle

int32

-

Total number of obstacles (static objects) placed in the scene

11

npc_list

ObjectStatus

-

Full list of NPC vehicles

12

pedestrian_list

ObjectStatus

-

Full list of pedestrians

13

obstacle_list

ObjectStatus

-

Full list of obstacles (static objects)

Simulation Process Status Publisher

  • MoraiSimProcStatusPublisher

  • ROS message details

    • Message Type: morai_msgs/MoraiSimProcStatus

    • Default Topic: /sim/process/state/msg/MoraiSimProcStatus

No

Name

Type

Unit

Remarks

1

header

Header

-

2

latest_command_time

Time

-

Latest time measurement to be received by the simulation process handler

3

command_result

int8

-

0x00: initial, 0x01: success, 0x10: command failed, 0x20: failed rosbag file load, 0x30: loaded rosbag but failed

4

current_mode

int8

-

0x01: simulation mode, 0x10: replay mode

5

current_status

int8

-

0x01: running, 0x10: paused, 0x20: paused and reached end of rosbag file

Sensor Pose Subscriber

  • SensorPoseSubscriber controls the position and orientation of a designated sensor according to input commands.

  • ROS message details

    • Message Type: morai_msgs/SensorPosControl

    • Default Topic: /SensorPosControl

No

Name

Type

Unit

Remarks

1

sensor_index

int16

-

Unique identifer number of the sensor

2

pose_x

float32

m

3

pose_y

float32

m

4

pose_z

float32

m

5

roll

float32

rad

Sensor roll angle

6

pitch

float32

rad

Sensor pitch angle

7

yaw

float32

rad

Sensor yaw angle

Service Response

  • MoraiServiceResponse

  • ROS message details

    • Message Type: morai_msgs/MoraiSrvResponse

No

Name

Type

Unit

Remarks

1

result

bool

-

Simulator Network

Simulator Network

Simulator Network configurations are as above. Refer to all the attributes shown in the picture before connecting to the server. This includes the type of Publisher, Subscriber, Service, Frame Rate Setting, Bridge Setting, and Scenario Setting.

ROS Service Types

MORAI SIM can also use Service Types within ROS to control the simulation.

Data Replay Service

  • MoraiSimProcServiceProvider

  • ROS service details

    • Service: morai_msgs/srv/MoraiSimProcSrv

    • Service Name: /Morai_SimProc

No

Name

Type

Unit

Remarks

1

request

MoraiSimProcHandle

-

2

response

MoraiSrvResponse

-

Contains a simple boolean with the resposne

Scenario Load

  • MoraiSLServiceProvider

  • ROS service details

    • Service: morai_msgs/srv/MoraiScenarioLoadSrv

    • Service Name; /Service_MoraiSL

No

Name

Type

Unit

Remarks

1

request

ScenarioLoad

-

2

response

MoraiSrvResponse

-

Traffic Light Call

  • MoraiSLServiceProvider

  • ROS service details

    • Service: morai_msgs/srv/MoraiTLInfoSrv

    • Service Name: /Morai_TLSrv

No

Name

Type

Unit

Remarks

1

request

MoraiTLIndex

-

2

response

MoraiTLInfo

-

Event Control Request

  • MoraiEventCmdServiceProvider

  • ROS service details

    • Service: morai_msgs/srv/MoraiEventCmdSrv

    • Service Name: /Service_MoraiEventCmd

No

Name

Type

Unit

Remarks

1

request

EventInfo

-

2

response

MoraiEventCmdSrv

-

Vehicle Specification Request

  • Morai Vehicle Spec Service Provider

  • ROS service details

    • Service: morai_msgs/srv/MoraiVehicleSpecSrv

    • Service Name: /Service_MoraiVehicleSpec

No

Name

Type

Unit

Remarks

1

request

VehicleSpecIndex

-

2

response

VehicleSpec

-

Map Data Request

  • Morai Map Spec Service Provider

  • ROS service details

    • Service morai_msgs/srv/MoraiMapSpecSrv

    • Service Name: /Service_MoraiMapSpec

No

Name

Type

Unit

Remarks

1

request

MapSpecIndex

-

2

response

MapSpec

-