Getting Started

BeamNG-ROS bridge needs to be configured to contain the correct IPv4 address of the machine hosting the simulation. Using it will start up a node that connects to the simulation and starts up a scenario as defined in the beamng_control/config/scenario/{scenario}.json. Other scenario specifications are available in the same directory.

  • Scenarios are defined through JSON objects, here is a list of possible keys and values.
Key Value Type Value Specification Entry Type
"version" String BeamnG ROS Integration version, f.ex. 1 Mandatory
"level" String BeamNG.tech level name, f.ex. "west_coast_usa". Mandatory
"mode" String Value Optional
"vehicles" Array At least one vehicle needs to be specified in order to obtain a valid scenario. Mandatory
See the table below for the Specification.
"name" String Name of the level. Mandatory
"time_of_day" Float Value between 0 and 1 where the range [0, .5] corresponds Optional
to the times between 12 a.m. and 12 p.m. and [.5], 1] corresponds to
the time range between 12 p.m. and 12 a.m.
"weather_presets" String Weather presets are level specific, ToDo Optional
  • Vehicles are also defined as JSON objectsin beamng_control/config/vehicles/{vehicle}.json.
Key Value Type Value Specification Entry Type
"name" String Name of the vehicle, used for identification Mandatory
"model" String Name of the vehicle type, f.ex. etk800 Mandatory
"position" Array Array of 3 floats, specifying the x, y, and x position of the vehicle. Mandatory
"rotation" Array Array of 4 floats, specifying the vehicle rotation quaternion. Mandatory
"sensors" Array Array of JSON objects, specifying the vehicles sensor parameters. Optional

Running BeamNG.Tech

After installing BemaNGpy , and setup BeamNG.Tech, you can run BeamNG.py from the Powershell as shown in the picture below.

Run BemaNG.Tech from BeamNGpy Run BemaNG.Tech from BeamNGpy

Running the ROS-bridge

  • Loading beamng_control node for loading the scenarios components i.e., level, vehicle, environemnt and sensors from example.launch file in the beamng_control package through the command:
roslaunch beamng_control example.launch

Running beamng_agent

  • Loading beamng_agent node for enabling the control from ROS side:
roslaunch beamng_agent example.launch 

The folloing topics for move/stop the vehicle in simulation and enable/disable keybard control from the simulation side:

  • Driving:
rostopic pub --once control beamng_msgs/VehicleControl 0 1 0 0 0 1
  • Stopping:
rostopic pub --once control beamng_msgs/VehicleControl 0 0 1 0 0 1
  • Release:
rostopic pub --once control beamng_msgs/VehicleControl 0 0 0 0 0 1
Calling ROS-services for controlling the Simulation

Various services to control the state of the simulation are available.

Name Type Purpose
/beamng_control/pause bng_msgs.srv.ChangeSmulationState Pause the simulation.
/beamng_control/resume bng_msgs.srv.ChangeSmulationState Resume the simulation.
  • Disable user keybaod and mouse control of the BeamNG.Tech game:
rosservice call /beamng_control/pause "{}"
  • terminal feedback should be:

success: True

  • Enable user keybaod and mouse control of the BeamNG.Tech game:
rosservice call /beamng_control/resume "{}" 
  • terminal feedback should be:

success: True

Vehicle Creation and Control
Name Type Purpose
/beamng_control/get_scenario_state bng_msgs.srv.GetScenarioState Determining the current state of the scenario.
/beamng_control/spawn_vehicle beamng_msgs.srv.SpawnVehicle Spawn new vehicle.
/beamng_control/teleport_vehicle beamng_msgs.srv.TeleportVehicle Teleport vehicle.
/beamng_control/start_scenario bng_msgs.srv.StartScenario Starting a loaded scenario.
/beamng_control/get_current_vehicles beamng_msgs.srv.GetCurrentVehiclesInfo Get the spawned vehicle information.
  • Clone a new vehicle :
rosservice call /beamng_control/spawn_vehicle 'ros' [0,5,10] [0,0,0,1] "/config/vehicles/etk800.json"
  • Laod a new scenario:
rosservice call /beamng_control/start_scenario "/config/scenarios/west_coast.json"
  • Reposition the current vehicle in west coast:
rosservice call /beamng_control/teleport_vehicle "ego_vehicle" [568.908,13.422,148.565] [0,0,0,1] 
  • Getting the scenario state:
rosservice call /beamng_control/get_scenario_state
  • Getting the get_current_vehicles:
rosservice call /beamng_control/get_current_vehicles
  • Getting the get_loggers:
rosservice call /beamng_control/get_loggers
Note:
  • if you got a feedback success: False for resume or pause services, that means your beamng_agent node isn’t active, and you will getting the following error message in the terminal of beamng_control node:
List of ROS-topics
  • ROS-visualization tool (Rviz) map:
/beamng_control/<vehicle_id>/marker

Rviz Map of road network West Coast, USA Rviz Map of road network West Coast, USA

  • Camera:

Contrary to other sensors, the Camera sensor may publish to multiple topics. If the camera sensor is configured to collect color, depth, annotation, and instance data, it is published to the respective topics:

/beamng_control/<vehicle_id>/<camera_id>/color

/beamng_control/<vehicle_id>/<camera_id>/depth

/beamng_control/<vehicle_id>/<camera_id>/annotation

/beamng_control/<vehicle_id>/<camera_id>/instance

The message type for all topics is sensor_msgs.msg.Image. Note that although the bounding_box option is given, this feature is still under development and will automatically be disabled.

Key Value Type Value Specification Entry Type
"type" String "Camera.default" Mandatory
"name" String Unique sensor id. Mandatory
"position" Array Array of 3 floats, specifying the x, y, and x position of the sensor. Mandatory
"orientation" Array Array of 4 floats, specifying the vehicle rotation quaternion Mandatory
"resolution" Array Tuple of ints, defining the x and y resolution of Optional
the resulting images.
"fov" Integer Camera field of view. Optional
"colour" Boolean Dis-/Enables color image generation. Optional
"depth" Boolean Dis-/Enables depth image generation. Optional
"annotation" Boolean Dis-/Enables ground truth generation for object type annotation. Optional
"instance" Boolean Dis-/Enables ground truth generation for instance annotation. Optional
"bounding_box" Boolean This feature is not supoprted at the moment Optional
and will be automatically disabled.

multiple camera filters rgb,depth,insthence,and annotation -starting from top-left to bottom-right multiple camera filters rgb,depth,insthence,and annotation -starting from top-left to bottom-right

  • LiDAR:

Message type: sensor_msgs.msg.PointCloud2

/beamng_control/<vehicle_id>/lidar0
Key Value Type Value Specification Entry Type
"type" String "Lidar.default" Mandatory
"name" String Unique sensor id. Mandatory
"position" Array Array of 3 floats, specifying the x, y, and x position of the sensor. Mandatory
"vertical_resolution" Integer Vertical resolution, i.e. how many lines are sampled vertically Optional
"vertical_angle" Float The vertical LiDAR sensor angle, in degrees. Optional
"hz" Integer The refresh rate of the LiDAR sensor, in Hz. Optional
"rps" Integer The rays per second emmited by the LiDAR sensor Optional
"angle" Integer horizontal range resolution, i.e. how many degrees are sampled horizontally Optional
"max_distance" Integer Maximal distance for data collection. Optional
"visualized" Integer Dis-/Enable in-simulation LiDAR visualization. Optional

3D-LiDAR sensor reading 3D-LiDAR sensor reading

  • Damage:

Message type: beamng_msgs.msg.DamagSensor

/beamng_control/<vehicle_id>/damage0
Key Value Type Value Specification Entry Type
"type" String "Damage" Mandatory
"name" String Unique sensor id. Mandatory

Vehicle-Damage reading Vehicle-Damage reading

  • time:

Message type: beamng_msgs.msg.TimeSensor

/beamng_control/<vehicle_id>/time0
Key Value Type Value Specification Entry Type
"type" String "Timer" Mandatory
"name" String Unique sensor id. Mandatory
  • Gforces:

Message type: beamng_msgs.msg.GForceSensor

/beamng_control/<vehicle_id>/gforce0
Key Value Type Value Specification Entry Type
"type" String "GForces" Mandatory
"name" String Unique sensor id. Mandatory
  • Electrics:

Message type: beamng_msgs.msg.ElectricsSensor

/beamng_control/<vehicle_id>/electrics0
Key Value Type Value Specification Entry Type
"type" String "Electrics" Mandatory
"name" String Unique sensor id. Mandatory
  • Imu pose:

Message type: beamng_msgs.msg.DamagSensor

/beamng_control/<vehicle_id>/position_imu
Key Value Type Value Specification Entry Type
"type" String "IMU" Mandatory
"name" String Unique sensor id. Mandatory
"position" Array Array of 3 floats, specifying the x, y, and x position of the sensor. Mandatory

IMU sensor reading IMU sensor reading

  • Parking sensor (ultrasonic):

Message type: beamng_msgs.msg.USSensor

/beamng_control/<vehicle_id>/parking_sensor
Key Value Type Value Specification Entry Type
"type" String "Ultrasonic.smallrange",and/or "Ultrasonic.midrange",and/or "Ultrasonic.largerange" Mandatory
"name" String Unique sensor id. Mandatory
"position" Array Array of 3 floats, specifying the x, y, and x position of the sensor. Mandatory
"rotation" Array Array of 3 floats, specifying the vehicle rotation quaternion Mandatory
"fov" Integer ultrasonic sensor field of view. Optional
"colour" Integer Dis-/Enables color image generation. Optional
"min_resolution" Integer Minimum distance for data collection. Optional
"min_distance" Integer Minimum range for data collection. Optional
"max_distance" Integer Maximal range for data collection. Optional
  • Vehicle state: Message type: beamng_msgs.msg.StateSensor
/beamng_control/<vehicle_id>/state
Last modified: 27/6/2022 14:16

Any further questions?

Join our discord