beamng_ros2.publishers.sensors module

Sensor publishers are connected to BeamNG vehicles using BeamNGpy and they periodically publish the sensor data on the ~/beamng/<vehicle name>/<sensor name> topic.

The default values of sensor attributes are located in the /config/sensors.json file, and you can use any arguments that the

Complete list of sensor types which are available in the BeamNG-ROS2 integration:

Sensor type

BeamNG-ROS2 publisher

BeamNGpy sensor

imu

AdvancedIMUPublisher

beamngpy.sensors.AdvancedIMU

camera

CameraPublisher

beamngpy.sensors.Camera

gps

GPSPublisher

beamngpy.sensors.GPS

idealradar

IdealRadarPublisher

beamngpy.sensors.IdealRadar

lidar

LidarPublisher

beamngpy.sensors.Lidar

mesh

MeshPublisher

beamngpy.sensors.Mesh

powertrain

PowertrainPublisher

beamngpy.sensors.PowertrainSensor

radar

RadarPublisher

beamngpy.sensors.Radar

roadssensor

RoadsSensorPublisher

beamngpy.sensors.RoadsSensor

ultrasonic

UltrasonicPublisher

beamngpy.sensors.Ultrasonic

damage

DamagePublisher

beamngpy.sensors.Damage

electrics

ElectricsPublisher

beamngpy.sensors.Electrics

gforces

GForcesPublisher

beamngpy.sensors.GForces

state

StatePublisher

beamngpy.sensors.State

timer

TimerPublisher

beamngpy.sensors.Timer

Some of the sensors support shared memory (with and without explicit polling), to enable it, set the following attributes of the sensors:

"is_using_shared_memory": true, // enable shared memory
"is_streaming": true, // enable streaming - updating the memory without sending a request to BeamNG

Sensor Publishers List

class beamng_ros2.publishers.sensors.AdvancedIMUPublisher(name: str, config: Dict[str, Any])

Bases: AutoSensorPublisher

IMU sensor publisher. Returns standard interfaces/msg/Imu messages.

Parameters:
  • name (str) – Name of the sensor.

  • config (Dict[str, Any]) – Arguments of the sensor passed to the BeamNGpy class.

get_data(time: Time) sensor_msgs.msg.Imu

Gets the data in the format publishable to the topic.

Parameters:

time (Time) – The ROS2 time to be used in the header of the message.

Return type:

sensor_msgs.msg.Imu

msg_type() Type

Returns the message type that this publisher publishes.

Return type:

Type

class beamng_ros2.publishers.sensors.AutoSensorPublisher(name: str, prototype: Callable, config: Dict[str, Any])

Bases: SensorPublisher

A base class for “automated” sensors, which require to be created after a vehicle is loaded and connected to the scenario.

Parameters:
  • name (str) – Name of the sensor.

  • prototype (Callable) – Constructor of the corresponding BeamNGpy sensor.

  • config (Dict[str, Any]) – Arguments of the sensor passed to the BeamNGpy class.

poll() Dict[str, Any]

Gets the raw data from the simulator. Needs to be implemented by derived classes.

Return type:

Dict[str, Any]

post_scenario_start(vehicle: Vehicle)

A hook function that is called for the connected vehicle after the scenario is loaded and started.

Parameters:

vehicle (Vehicle) – The vehicle instance connected to the simulator at the moment of calling this function.

remove()
class beamng_ros2.publishers.sensors.CameraPublisher(name: str, config: Dict[str, Any])

Bases: AutoSensorPublisher

Camera data publisher. Publishes one or multiple interfaces/msg/Image messages depending on the configuration:

  • ~/sensors/<CAM_NAME>/colour: color data if is_render_colours=True

  • ~/sensors/<CAM_NAME>/annotation: class semantic annotations if is_render_annotations=True

  • ~/sensors/<CAM_NAME>/instance: object semantic annotations if is_render_instance=True

  • ~/sensors/<CAM_NAME>/depth depth image if is_render_depth=True

Parameters:
  • name (str) – Name of the sensor.

  • config (Dict[str, Any]) – Arguments of the sensor passed to the BeamNGpy class.

create_publisher(node: Node) None

Creates an inner instance of the rclpy.publisher.Publisher for the node with the message type that is defined by the msg_type() function.

Parameters:

node (Node) – The node for which the publisher will be created.

Return type:

None

get_data(time: Time) None

Not implemented, the camera sensor uses custom logic to poll the data.

Parameters:

time (Time)

Return type:

None

msg_type() Type

Returns the message type that this publisher publishes.

Return type:

Type

publish(time: Time) None

Function that publishes the corresponding data using the inner instance of the ROS2 publisher. Needs to be implemented by derived classes.

Parameters:

time (Time)

Return type:

None

class beamng_ros2.publishers.sensors.ClassicalSensorPublisher(name: str, prototype: Callable, config: Dict[str, Any])

Bases: SensorPublisher

A base class for “classical” sensors, which are usually created before loading the scenario. Polling of all classical sensors is done in a centralized way using the beamngpy.Vehicle.sensors.poll() function and therefore is not included in this base class.

Parameters:
  • name (str) – Name of the sensor.

  • prototype (Callable) – Constructor of the corresponding BeamNGpy sensor.

  • config (Dict[str, Any]) – Arguments of the sensor passed to the BeamNGpy class.

poll() Dict[str, Any]

Gets the raw data from the simulator. Needs to be implemented by derived classes.

Return type:

Dict[str, Any]

pre_scenario_start(vehicle: Vehicle)

A hook function that is called for the connected vehicle before the scenario is loaded and started.

Parameters:

vehicle (Vehicle) – The vehicle instance not connected to the simulator at the moment of calling this function.

remove()
class beamng_ros2.publishers.sensors.DamagePublisher(name: str, config: Dict[str, Any])

Bases: ClassicalSensorPublisher

Damage sensor publisher publishing messages.

Parameters:
  • name (str) – Name of the sensor.

  • config (Dict[str, Any]) – Arguments of the sensor passed to the BeamNGpy class.

get_data(time: Time) DamageSensor

Gets the data in the format publishable to the topic.

Parameters:

time (Time) – The ROS2 time to be used in the header of the message.

Return type:

DamageSensor

msg_type() Type

Returns the message type that this publisher publishes.

Return type:

Type

class beamng_ros2.publishers.sensors.ElectricsPublisher(name: str, config: Dict[str, Any])

Bases: ClassicalSensorPublisher

Electrics sensor publisher publishing messages.

Parameters:
  • name (str) – Name of the sensor.

  • config (Dict[str, Any]) – Arguments of the sensor passed to the BeamNGpy class.

get_data(time: Time) ElectricsSensor

Gets the data in the format publishable to the topic.

Parameters:

time (Time) – The ROS2 time to be used in the header of the message.

Return type:

ElectricsSensor

msg_type()

Returns the message type that this publisher publishes.

class beamng_ros2.publishers.sensors.GForcesPublisher(name: str, config: Dict[str, Any])

Bases: ClassicalSensorPublisher

GForces sensor publisher publishing messages.

Parameters:
  • name (str) – Name of the sensor.

  • config (Dict[str, Any]) – Arguments of the sensor passed to the BeamNGpy class.

get_data(time: Time) GForceSensor

Gets the data in the format publishable to the topic.

Parameters:

time (Time) – The ROS2 time to be used in the header of the message.

Return type:

GForceSensor

msg_type()

Returns the message type that this publisher publishes.

class beamng_ros2.publishers.sensors.GPSPublisher(name: str, config: Dict[str, Any])

Bases: AutoSensorPublisher

GPS sensor publisher publishing interfaces/msg/NavSatFix messages.

Parameters:
  • name (str) – Name of the sensor.

  • config (Dict[str, Any]) – Arguments of the sensor passed to the BeamNGpy class.

get_data(time: Time) sensor_msgs.msg.NavSatFix

Gets the data in the format publishable to the topic.

Parameters:

time (Time) – The ROS2 time to be used in the header of the message.

Return type:

sensor_msgs.msg.NavSatFix

msg_type() Type

Returns the message type that this publisher publishes.

Return type:

Type

class beamng_ros2.publishers.sensors.IdealRadarPublisher(name: str, config: Dict[str, Any])

Bases: AutoSensorPublisher

GPS sensor publisher publishing messages.

Parameters:
  • name (str) – Name of the sensor.

  • config (Dict[str, Any]) – Arguments of the sensor passed to the BeamNGpy class.

get_data(time: Time) IdealRadarSensor

Gets the data in the format publishable to the topic.

Parameters:

time (Time) – The ROS2 time to be used in the header of the message.

Return type:

IdealRadarSensor

msg_type() Type

Returns the message type that this publisher publishes.

Return type:

Type

class beamng_ros2.publishers.sensors.LidarPublisher(name: str, config: Dict[str, Any])

Bases: AutoSensorPublisher

Lidar sensor publisher publishing interfaces/msg/PointCloud2 messages.

Parameters:
  • name (str) – Name of the sensor.

  • config (Dict[str, Any]) – Arguments of the sensor passed to the BeamNGpy class.

create_publisher(node: Node)

Creates an inner instance of the rclpy.publisher.Publisher for the node with the message type that is defined by the msg_type() function.

Parameters:

node (Node) – The node for which the publisher will be created.

get_data(time: Time) sensor_msgs.msg.PointCloud2

Gets the data in the format publishable to the topic.

Parameters:

time (Time) – The ROS2 time to be used in the header of the message.

Return type:

sensor_msgs.msg.PointCloud2

msg_type() Type

Returns the message type that this publisher publishes.

Return type:

Type

class beamng_ros2.publishers.sensors.MeshPublisher(name: str, config: Dict[str, Any])

Bases: AutoSensorPublisher

Mesh sensor publisher publishing messages.

Parameters:
  • name (str) – Name of the sensor.

  • config (Dict[str, Any]) – Arguments of the sensor passed to the BeamNGpy class.

get_data(time: Time) MeshSensor

Gets the data in the format publishable to the topic.

Parameters:

time (Time) – The ROS2 time to be used in the header of the message.

Return type:

MeshSensor

msg_type() Type

Returns the message type that this publisher publishes.

Return type:

Type

class beamng_ros2.publishers.sensors.PowertrainSensorPublisher(name: str, config: Dict[str, Any])

Bases: AutoSensorPublisher

Powertrain sensor publisher publishing messages.

Parameters:
  • name (str) – Name of the sensor.

  • config (Dict[str, Any]) – Arguments of the sensor passed to the BeamNGpy class.

get_data(time: Time) PowertrainSensor

Gets the data in the format publishable to the topic.

Parameters:

time (Time) – The ROS2 time to be used in the header of the message.

Return type:

PowertrainSensor

msg_type() Type

Returns the message type that this publisher publishes.

Return type:

Type

class beamng_ros2.publishers.sensors.RadarPublisher(name: str, config: Dict[str, Any])

Bases: AutoSensorPublisher

Radar sensor publisher publishing radar_msgs RadarReturn messages if the library is found, custom messages if not.

You can force the publisher to always send custom BeamNG message type by setting the use_beamng_msg_type=True argument in the sensor .json definition.

Parameters:
  • name (str) – Name of the sensor.

  • config (Dict[str, Any]) – Arguments of the sensor passed to the BeamNGpy class.

get_data(time: Time) RadarReturn

Gets the data in the format publishable to the topic.

Parameters:

time (Time) – The ROS2 time to be used in the header of the message.

Return type:

RadarReturn

msg_type() Type

Returns the message type that this publisher publishes.

Return type:

Type

class beamng_ros2.publishers.sensors.RoadsSensorPublisher(name: str, config: Dict[str, Any])

Bases: AutoSensorPublisher

Roads sensor publisher publishing messages.

Parameters:
  • name (str) – Name of the sensor.

  • config (Dict[str, Any]) – Arguments of the sensor passed to the BeamNGpy class.

get_data(time: Time) RoadsSensor | None

Gets the data in the format publishable to the topic.

Parameters:

time (Time) – The ROS2 time to be used in the header of the message.

Return type:

RoadsSensor | None

msg_type() Type

Returns the message type that this publisher publishes.

Return type:

Type

class beamng_ros2.publishers.sensors.SensorPublisher

Bases: VehiclePublisher

Base class for BeamNG sensor publishers, which have access to a connected beamngpy.Vehicle instance.

static create(name: str, type: str, parameters: Dict[str, Any]) SensorPublisher

Creates an instance of a specific sensor publishers based on the name, type and extra parameters which will be passed to the underlying BeamNGpy sensor.

Parameters:
  • name (str) – Name of the sensor. Has to be unique for a vehicle.

  • type (str) – Type of the sensor in the format of either “<TYPE>” or “<TYPE>.<CONFIGURATION>”.

  • parameters (Dict[str, Any]) – Extra parameters of the sensor, all fields included in this dictionary will override the parameters set up by the sensor type and configuration.

Return type:

SensorPublisher

create_publisher(node: Node)

Creates an inner instance of the rclpy.publisher.Publisher for the node with the message type that is defined by the msg_type() function.

Parameters:

node (Node) – The node for which the publisher will be created.

abstract get_data(time: Time) Any

Gets the data in the format publishable to the topic.

Parameters:

time (Time) – The ROS2 time to be used in the header of the message.

Return type:

Any

static get_sensor_config(sensor_type: str, sensor_config_name: str) Dict[str, Any]

Gets the default configuration of a sensor by its type. Configuration is a dictionary where keys are strings representing the attributes of the sensor.

Parameters:
  • sensor_type (str) – The sensor type (see the top for their comprehensive list).

  • sensor_config_name (str) – Some sensors include custom configurations setting multiple parameters at once. If empty, the default configuration will be used.

Returns:

The configuration of the sensor as a dictionary.

Return type:

Dict[str, Any]

static get_sensor_publisher(sensor_type: str) Callable[[str, Dict[str, Any]], SensorPublisher]

Gets the constructor of the specific publisher with the provided type. The constructor of all sensor publishers take two arguments: name and configuration.

Parameters:

sensor_type (str) – The sensor type (see the top for their comprehensive list).

Return type:

Callable[[str, Dict[str, Any]], SensorPublisher]

abstract poll() Dict[str, Any]

Gets the raw data from the simulator. Needs to be implemented by derived classes.

Return type:

Dict[str, Any]

publish(time: Time)

Function that publishes the corresponding data using the inner instance of the ROS2 publisher. Needs to be implemented by derived classes.

Parameters:

time (Time)

abstract remove()
class beamng_ros2.publishers.sensors.StatePublisher(name: str, config: Dict[str, Any])

Bases: ClassicalSensorPublisher

State publisher publishing messages.

Keep in mind this publisher is loaded by default for every vehicle and therefore you do not need to specify it in the configuration file of the scenario.

Parameters:
  • name (str) – Name of the sensor.

  • config (Dict[str, Any]) – Arguments of the sensor passed to the BeamNGpy class.

get_data(time: Time) StateSensor

Gets the data in the format publishable to the topic.

Parameters:

time (Time) – The ROS2 time to be used in the header of the message.

Return type:

StateSensor

msg_type() Type

Returns the message type that this publisher publishes.

Return type:

Type

pre_scenario_start(vehicle: Vehicle)

A hook function that is called for the connected vehicle before the scenario is loaded and started.

Parameters:

vehicle (Vehicle) – The vehicle instance not connected to the simulator at the moment of calling this function.

class beamng_ros2.publishers.sensors.TimerPublisher(name: str, config: Dict[str, Any])

Bases: ClassicalSensorPublisher

Time sensor publisher publishing messages.

The timer returns time since the start of scenario, which is not the same time that is used as the header of the published messages. You can use the messages to get the ROS2 time.

Parameters:
  • name (str) – Name of the sensor.

  • config (Dict[str, Any]) – Arguments of the sensor passed to the BeamNGpy class.

get_data(time: Time) TimeSensor

Gets the data in the format publishable to the topic.

Parameters:

time (Time) – The ROS2 time to be used in the header of the message.

Return type:

TimeSensor

msg_type()

Returns the message type that this publisher publishes.

class beamng_ros2.publishers.sensors.UltrasonicPublisher(name: str, config: Dict[str, Any])

Bases: AutoSensorPublisher

Ultrasonic sensor publisher publishing interfaces/msg/Range messages.

Parameters:
  • name (str) – Name of the sensor.

  • config (Dict[str, Any]) – Arguments of the sensor passed to the BeamNGpy class.

get_data(time: Time) sensor_msgs.msg.Range

Gets the data in the format publishable to the topic.

Parameters:

time (Time) – The ROS2 time to be used in the header of the message.

Return type:

sensor_msgs.msg.Range

msg_type() Type

Returns the message type that this publisher publishes.

Return type:

Type