Sensors List#
This page details the different available sensors and the configuration options possible. For more on how to build sensor plugins, please see Sensor Plugins.
Table of Contents
- Examples
- How to Specify a Sensor
- Clock
- Color Camera
- Depth Camera
- Segmentation Camera
- LiDAR
- 3D Ground Truth
- Apollo Perception Visualizer 3D
- CAN-Bus
- GPS Device
- GPS Odometry
- GPS-INS Status
- LGSVL Control
- Apollo Control
- Differential Drive Control
- Keyboard Control
- Wheel Control
- Cruise Control
- IMU
- 2D Ground Truth
- Radar
- Ultrasonic
- Control Calibration
- Transform Sensor
- Signal Sensor
- Video Recording Sensor
- Comfort Sensor
- Stop Line Sensor
- Vehicle Odometry
- Vehicle State
- HUD Keyboard Control
- AutowareAI Control
- Lane-line Sensor
- Lane Following
Examples top#
Example JSON configurations are available here:
- Apollo 5.0 JSON
- Apollo 3.0 JSON
- Autoware.AI
- Autoware.Auto
- Some LiDAR sensor JSONs:
How to Specify a Sensor top#
A vehicle configuration is in the following format:
[
SENSOR,
SENSOR,
SENSOR
]
A SENSOR
is defined in the JSON configuration in the following format:
{
"type": STRING,
"name": STRING,
"params": {PARAMS},
"parent": STRING,
"transform": {
"x": FLOAT,
"y": FLOAT,
"z": FLOAT,
"pitch": FLOAT,
"yaw": FLOAT,
"roll": FLOAT,
}
}
type
is the type of sensor.name
is the name of the sensor. This is how the sensor will be identified.params
are the explicitly specified parameters. If a parameter is not set, the Default Value in the sensor definition will be used.- ex.
{"Width": 1920, "Height": 1080}
-
There are 2 parameters that all sensors have
Parameter Description Default Value Topic
defines the topic that the sensor will subscribe/publish to null
Frame
defines the frame_id if the sensor publishes a ROS message. See ROS Header Message for more information null
-
parent
(OPTIONAL) a sensor'stransform
can be relative to another sensor.STRING
is thename
of the base sensor transform to which this sensor is relative. -
If omitted, the
transform
is relative to the origin of the vehicle. transform
is the location and rotation of the sensor relative to the local position of the vehicle. The Unity left-hand coordinate system is used (+x right, +y up, +z forward, +pitch tilts the front down, +yaw rotates clockwise when viewed from above, +roll tilts the left side down).x
is the position of the sensor along the x-axisy
is the position of the sensor along the y-axisz
is the position of the sensor along the z-axispitch
is the rotation around the x-axisyaw
is the rotation around the y-axisroll
is the rotation around the z-axis
Clock top#
This sensor outputs simulated time to ROS as rosgraph_msgs/Clock message, or to CyberRT as clock message. The only parameter to use is topic/channel name.
For ROS, you can add <param name="/use_sim_time" value="true">
to their ROS launch file, or use rosparam set /use_sim_time true
in command line, to have a ROS node use simulation time according to the /clock
topic. For more details please refer to this page.
For CyberRT, you can set clock_mode
in cyber.pb.conf as MODE_MOCK
to have CyberRT use simulation time according to the /clock
topic.
{
"type": "ClockSensor",
"name": "Clock Sensor",
"params": {
"Topic": "/clock"
}
}
Color Camera top#
This is the type of sensor that would be used for the Main Camera
in Apollo or other AD stacks.
(For questions about camera matrix, please refer to this FAQ.)
Parameter | Description | Unit | Type | Default Value | Minimum | Maximum |
---|---|---|---|---|---|---|
Width |
defines the width of the image output | pixels | Int | 1920 | 1 | 1920 |
Height |
defines the height of the image output | pixels | Int | 1080 | 1 | 1080 |
Frequency |
defines the maximum rate that messages will be published | Hertz | Int | 15 | 1 | 100 |
JpegQuality |
defines the quality if the image output | % | Int | 75 | 0 | 100 |
FieldOfView |
defines the vertical angle that the camera sees | degrees | Float | 60 | 1 | 90 |
MinDistance |
defines how far an object must be from the sensor for it to be detected | meters | Float | 0.1 | 0.01 | 1000 |
MaxDistance |
defines how close an object must be to the sensor for it to be detected | meters | Float | 2000 | 0.01 | 2000 |
Distorted |
defines if the image is distorted | Bool | false |
|||
DistortionParameters |
parameters used by distortion * | List of Float | empty list | |||
Fisheye |
defines if the camera has fisheye lens | Bool | false |
|||
Xi |
parameter used by fisheye distortion ** | Float | 0.0 | |||
CubemapSize |
size of the cubemap used by fisheye distortion *** | pixels | Int | 1024 | 512 | 2048 |
* If Distorted
is true
, DistortionParameters
must be an empty list or a list of FOUR floats.
The values in this list should come from calibration result of real camera. Setting arbitrary values may cause undefined result.
If Distorted
is false
, DistortionParameters
, Fisheye
and Xi
are ignored.
** If Fisheye
is true
, Xi
should be a value from calibration result of real camera. Setting arbitrary value may cause undefined result.
If Fisheye
is false
, Xi
is ignored.
*** CubemapSize
should only be 512, 1024, or 2048.
{
"type": "ColorCameraSensor",
"name": "Main Camera",
"params": {
"Width": 1920,
"Height": 1080,
"Frequency": 15,
"JpegQuality": 75,
"FieldOfView": 50,
"MinDistance": 0.1,
"MaxDistance": 2000,
"Topic": "/simulator/main_camera",
"Frame": "camera",
"Distorted": true,
"DistortionParameters": [
-0.25349, 0.11868, 0, 0
],
"Postprocessing": [
]
},
"transform": {
"x": 0,
"y": 1.7,
"z": -0.2,
"pitch": 0,
"yaw": 0,
"roll": 0
}
}
Sensor Effects top#
Color Camera has multiple post processing sensor effects that can be added to the Postprocessing
field in params
. Effects can be combined with an array of Postprocessing
fields but order is hard coded.
SunFlare - creates a sun flare effect
Parameter | Description | Type | Default Value | Min | Max |
---|---|---|---|---|---|
type |
postprocessing sensor effect name | String | |||
sunIntensity |
defines the intensity of the sun flare | Float | 1 | 0 | 10 |
haloIntensity |
defines the intensity of the sun flare halo | Float | 1 | 0 | 10 |
ghostingIntensity |
defines the intensity of the mirror effect | Float | 1 | 0 | 10 |
"Postprocessing": [
{
"type": "SunFlare",
"sunIntensity": 1,
"haloIntensity": 1,
"ghostingIntensity": 1
}
]
Rain - creates rain drops on the lens
Parameter | Description | Type | Default Value | Min | Max |
---|---|---|---|---|---|
type |
postprocessing sensor effect name | String | |||
size |
defines the size of the drops | Float | 1 | 0 | 1 |
"Postprocessing": [
{
"type": "Rain",
"size": 1
}
]
GreyScale - converts color to grey scale
Parameter | Description | Type | Default Value | Min | Max |
---|---|---|---|---|---|
type |
postprocessing sensor effect name | String | |||
intensity |
defines the intensity of the grey scale | Float | 1 | 0 | 1 |
"Postprocessing": [
{
"type": "GreyScale",
"intensity": 1
}
]
VideoArtifacts - creates jpeg compression artifacts
Parameter | Description | Type | Default Value | Min | Max |
---|---|---|---|---|---|
type |
postprocessing sensor effect name | String | |||
intensity |
defines the intensity of the effect | Float | 0.25 | 0 | 1 |
blockSize |
defines the size of the affected block | Int | 32 | 1 | 128 |
"Postprocessing": [
{
"type": "VideoArtifacts",
"intensity": 0.25,
"blockSize": 32
}
]
Depth Camera top#
This sensor returns an image where the shades on the grey-scale correspond to the depth of objects.
Parameter | Description | Unit | Type | Default Value | Minimum | Maximum |
---|---|---|---|---|---|---|
Width |
defines the width of the image output | pixels | Int | 1920 | 1 | |
Height |
defines the height of the image output | pixels | Int | 1080 | 1 | 1080 |
Frequency |
defines the maximum rate that messages will be published | Hertz | Int | 5 | 1 | 100 |
JpegQuality |
defines the quality if the image output | % | Int | 100 | 0 | 100 |
FieldOfView |
defines the vertical angle that the camera sees | degrees | Float | 60 | 1 | 90 |
MinDistance |
defines how far an object must be from the sensor for it to be detected | meters | Float | 0.1 | 0.01 | 1000 |
MaxDistance |
defines how close an object must be to the sensor for it to be detected | meters | Float | 2000 | 0.01 | 2000 |
Distorted |
defines if the image is distorted | Bool | false |
|||
DistortionParameters |
parameters used by distortion* | List of Float | empty list | |||
Fisheye |
defines if the camera has fisheye lens | Bool | false |
|||
Xi |
parameter used by fisheye distortion ** | Float | 0.0 | |||
CubemapSize |
size of the cubemap used by fisheye distortion *** | pixels | Int | 1024 | 512 | 2048 |
* See notes on DistortionParameters
for Color Camera.
** See notes on Xi
for Color Camera.
*** See notes on CubemapSize
for Color Camera.
{
"type": "DepthCameraSensor",
"name": "Depth Camera",
"params": {
"Width": 1920,
"Height": 1080,
"Frequency": 15,
"JpegQuality": 75,
"FieldOfView": 50,
"MinDistance": 0.1,
"MaxDistance": 2000,
"Topic": "/simulator/depth_camera"
},
"transform": {
"x": 0,
"y": 1.7,
"z": -0.2,
"pitch": 0,
"yaw": 0,
"roll": 0
}
}
Segmentation Camera top#
This sensor returns an image where objects are colored corresponding to their tag:
Tag | Color | Hex Value |
---|---|---|
Car | Blue | #120E97 |
Road | Purple | #7A3F83 |
Sidewalk | Orange | #BA8350 |
Vegetation | Green | #71C02F |
Obstacle | White | #FFFFFF |
TrafficLight | Yellow | #FFFF00 |
Building | Turquoise | #238688 |
Sign | Dark Yellow | #C0C000 |
Shoulder | Pink | #FF00FF |
Pedestrian | Red | #FF0000 |
Curb | Dark Purple | #4A254F |
If a tag is included in "InstanceSegmentationTags", each instance of objects with that tag is colored differently, but all will have same hue (e.g. all cars will be bluish and all pedestrians will be reddish).
Parameter | Description | Unit | Type | Default Value | Minimum | Maximum |
---|---|---|---|---|---|---|
Width |
defines the width of the image output | pixels | Int | 1920 | 1 | 1920 |
Height |
defines the height of the image output | pixels | Int | 1080 | 1 | 1080 |
Frequency |
defines the maximum rate that messages will be published | Hertz | Int | 15 | 1 | 100 |
FieldOfView |
defines the vertical angle that the camera sees | degrees | Float | 60 | 1 | 90 |
MinDistance |
defines how far an object must be from the sensor for it to be detected | meters | Float | 0.1 | 0.01 | 1000 |
MaxDistance |
defines how close an object must be to the sensor for it to be detected | meters | Float | 2000 | 0.01 | 2000 |
Distorted |
defines if the image is distorted | Bool | false |
|||
DistortionParameters |
parameters used by distortion* | List of Float | empty list | |||
Fisheye |
defines if the camera has fisheye lens | Bool | false |
|||
Xi |
parameter used by fisheye distortion ** | Float | 0.0 | |||
CubemapSize |
size of the cubemap used by fisheye distortion *** | pixels | Int | 1024 | 512 | 2048 |
InstanceSegmentationTags |
define tags with instance segmentation | List of String | empty list |
* See notes on DistortionParameters
for Color Camera.
** See notes on Xi
for Color Camera.
*** See notes on CubemapSize
for Color Camera.
{
"type": "SegmentationCameraSensor",
"name": "Segmentation Camera",
"params": {
"Width": 1920,
"Height": 1080,
"Frequency": 15,
"FieldOfView": 50,
"MinDistance": 0.1,
"MaxDistance": 2000,
"InstanceSegmentationTags": [
],
"Topic": "/simulator/segmentation_camera"
},
"transform": {
"x": 0,
"y": 1.7,
"z": -0.2,
"pitch": 0,
"yaw": 0,
"roll": 0
}
}
Example of Instance Segmentation Tags. Be aware that this effects performance greatly.
"InstanceSegmentationTags": [
"Car",
"Pedestrian",
"Obstacle",
"Building"
],
LiDAR top#
This sensor returns a point cloud after 1 revolution.
Parameter | Description | Unit | Type | Default Value | Minimum | Maximum |
---|---|---|---|---|---|---|
VerticalRayAngles |
defines vertical angle for each laser beam* | List of Float | empty list | |||
LaserCount |
defines how many vertically stacked laser beams there are | Int | 32 | 1 | 128 | |
FieldOfView |
defines the vertical angle between bottom and top ray | degrees | Float | 41.33 | 1 | 45 |
CenterAngle |
defines the center of the FieldOfView cone to the horizon (+ means below horizon) | degrees | Float | 10 | -45 | 45 |
MinDistance |
defines how far an object must be from the sensor for it to be detected | meters | Float | 0.5 | 0.01 | 1000 |
MaxDistance |
defines how close an object must be to the sensor for it to be detected | meters | Float | 100 | 0.01 | 2000 |
RotationFrequency |
defines how fast the sensor rotates | Hertz | Float | 10 | 1 | 30 |
MeasurementsPerRotation |
defines how many measurements each beam takes per rotation | Int | 1500 | 18 | 6000 | |
Compensated |
defines whether or not the point cloud is compensated for the movement of the vehicle | Bool | true |
|||
PointSize |
defines how large of points are visualized | pixels | Float | 2 | 1 | 10 |
PointColor |
defines the color of visualized points | rgba in hex | Color | #FF0000FF |
* If VerticalRayAngles
is not empty, LaserCount
will be automatically set to the length of VerticalRayAngles
, and FieldOfView
and CenterAngle
will be ignored.
A sample of uniformly distributed angles:
{
"type": "LidarSensor",
"name": "Lidar-Uniform",
"params": {
"LaserCount": 32,
"FieldOfView": 41.33,
"CenterAngle": 10,
"MinDistance": 0.5,
"MaxDistance": 100,
"RotationFrequency": 10,
"MeasurementsPerRotation": 360,
"Compensated": true,
"PointColor": "#ff000000",
"Topic": "/point_cloud",
"Frame": "velodyne"
},
"transform": {
"x": 0,
"y": 2.312,
"z": -0.3679201,
"pitch": 0,
"yaw": 0,
"roll": 0
}
}
A sample of non-uniformly distributed angles:
{
"type": "LidarSensor",
"name": "Lidar-NonUniform",
"params": {
"VerticalRayAngles": [
-25.0, -1.0, -1.667, -15.639,
-11.31, 0.0, -0.667, -8.843,
-7.254, 0.333, -0.333, -6.148,
-5.333, 1.333, 0.667, -4.0,
-4.667, 1.667, 1.0, -3.667,
-3.333, 3.333, 2.333, -2.667,
-3.0, 7.0, 4.667, -2.333,
-2.0, 15.0, 10.333, -1.333
],
"MinDistance": 0.5,
"MaxDistance": 100,
"RotationFrequency": 10,
"MeasurementsPerRotation": 360,
"Compensated": true,
"PointColor": "#ff000000",
"Topic": "/point_cloud",
"Frame": "velodyne"
},
"transform": {
"x": 0,
"y": 2.312,
"z": -0.3679201,
"pitch": 0,
"yaw": 0,
"roll": 0
}
}
3D Ground Truth top#
This sensor returns 3D ground truth data for training and creates bounding boxes around the detected objects. The color of the object corresponds to the object's type:
Object | Color |
---|---|
Car | Green |
Pedestrian | Yellow |
Bicycle | Cyan |
Unknown | Magenta |
Parameter | Description | Unit | Type | Default Value | Minimum | Maximum |
---|---|---|---|---|---|---|
Frequency |
defines the maximum rate that messages will be published | Hertz | Float | 10 | 1 | 100 |
MaxDistance |
defines the how close an object must be to the sensor to be detected | meters | Float | 100 | 1 | 1000 |
{
"type": "PerceptionSensor3D",
"name": "3D Ground Truth",
"params": {
"Frequency": 10,
"Topic": "/simulator/ground_truth/3d_detections"
},
"transform": {
"x": 0,
"y": 1.975314,
"z": -0.3679201,
"pitch": 0,
"yaw": 0,
"roll": 0
}
}
Apollo Perception Visualizer 3D top#
This sensor will visualize 3D bounding boxes on objects as detected by Apollo. It does not publish any data and instead subscribes to the perception topic from Apollo. The color of the boxes are:
Object | Color |
---|---|
Car | Green |
Pedestrian | Yellow |
Bicycle | Cyan |
Unknown | Magenta |
{
"type": "ApolloPerceptionVisualizer3D",
"name": "Apollo Perception Visualizer 3D Sensor",
"params": {
"Topic": "/apollo/perception/obstacles"
},
"transform": {
"x": 0,
"y": 0,
"z": 0,
"pitch": 0,
"yaw": 0,
"roll": 0
}
}
CAN-Bus top#
This sensor sends data about the vehicle chassis. The data includes:
- Speed [m/s]
- Throttle [%]
- Braking [%]
- Steering [+/- %]
- Parking Brake Status [bool]
- High Beam Status [bool]
- Low Beam Status [bool]
- Hazard Light Status [bool]
- Fog Light Status [bool]
- Left Turn Signal Status [bool]
- Right Turn Signal Status [bool]
- Wiper Status [bool]
- Reverse Gear Status [bool]
- Selected Gear [Int]
- Engine Status [bool]
- Engine RPM [RPM]
- GPS Latitude [Latitude]
- GPS Longitude [Longitude]
- Altitude [m]
- Orientation [3D Vector of Euler angles]
- Velocity [3D Vector of m/s]
Parameter | Description | Unit | Type | Default Value | Minimum | Maximum |
---|---|---|---|---|---|---|
Frequency |
defines the maximum rate that messages will be published | Hertz | Float | 10 | 1 | 100 |
{
"type": "CanBusSensor",
"name": "CAN Bus",
"params": {
"Frequency": 10,
"Topic": "/canbus"
},
"transform": {
"x": 0,
"y": 0,
"z": 0,
"pitch": 0,
"yaw": 0,
"roll": 0
}
}
GPS Device top#
This sensor outputs the GPS location of the vehicle in Longitude/Latitude and Northing/Easting coordintates.
Parameter | Description | Unit | Type | Default Value | Minimum | Maximum |
---|---|---|---|---|---|---|
Frequency |
defines the maximum rate that messages will be published | Hertz | Float | 12.5 | 1 | 100 |
IgnoreMapOrigin |
defines whether or not the actual GPS position is returned. If true , then the Unity world position is returned (as if the MapOrigin were (0,0)) |
Bool | false |
{
"type": "GpsSensor",
"name": "GPS",
"params": {
"Frequency": 12.5,
"Topic": "/gps",
"Frame": "gps",
"IgnoreMapOrigin": true
},
"transform": {
"x": 0,
"y": 0,
"z": 0,
"pitch": 0,
"yaw": 0,
"roll": 0
}
}
GPS Odometry top#
This sensor outputs the GPS location of the vehicle in Longitude/Latitude and Northing/Easting coordintates and the vehicle velocity.
Parameter | Description | Unit | Type | Default Value | Minimum | Maximum |
---|---|---|---|---|---|---|
Frequency |
defines the maximum rate that messages will be published | Hertz | Float | 12.5 | 1 | 100 |
ChildFrame |
used by Autoware | |||||
IgnoreMapOrigin |
defines whether or not the actual GPS position is returned. If true , then the Unity world position is returned (as if the MapOrigin were (0,0)) |
Bool | false |
{
"type": "GpsOdometrySensor",
"name": "GPS Odometry",
"params": {
"Frequency": 12.5,
"Topic": "/gps_odometry",
"Frame": "gps",
"IgnoreMapOrigin": true
},
"transform": {
"x": 0,
"y": 0,
"z": 0,
"pitch": 0,
"yaw": 0,
"roll": 0
}
}
GPS-INS Status top#
This sensor outputs the status of the GPS correction due to INS. The Simulator is an ideal environment in which GPS is always corrected.
Parameter | Description | Unit | Type | Default Value | Minimum | Maximum |
---|---|---|---|---|---|---|
Frequency |
defines the maximum rate that messages will be published [Hertz] | Float | 12.5 | 1 | 100 |
{
"type": "GpsInsSensor",
"name": "GPS INS Status",
"params": {
"Frequency": 12.5,
"Topic": "/gps_ins_stat",
"Frame": "gps"
},
"transform": {
"x": 0,
"y": 0,
"z": -1.348649,
"pitch": 0,
"yaw": 0,
"roll": 0
}
}
LGSVL Control top#
This sensor is required for a vehicle to subscribe to a control topic published in ROS or ROS2 with message type lgsvl_msgs/VehicleControlData
.
{
"type": "LGSVLControlSensor",
"name": "AD Car Control",
"params": {
"Topic": "/vehicle_cmd"
}
}
Apollo Control top#
This sensor is required for a vehicle to subscribe to the control topic from Apollo using the CyberRT bridge.
{
"type": "ApolloControlSensor",
"name": "Apollo Car Control",
"params": {
"Topic": "/apollo/control"
}
}
The sensor also demonstrates how a user can check when SVL Simulator receives the first control message from the AD stack like Apollo. Based on this time, you can start the rest of the simulation or do some other interesting things.
To wait for control message from apollo in a Python script, you can call on_custom()
of the ego agent. For example, the following code set isControlReceived
of agent self.ego
to be True
when the simulator first receives a message of the /apollo/control topic.
def on_control_received(agent, kind, context):
if kind == "checkControl":
agent.isControlReceived = True
log.info("Control message recieved")
self.ego.on_custom(on_control_received)
Differential Drive Control top#
The sensor allows an ego vehicle (robot) with a differential drive setup to subscribe to control commands using the Ros2 bridge to drive the robot. Internally, the sensor track wheel movement and calculates an odometry pose based on wheel motion which can be published to a topic. The wheel motion is also used as feedback in a PID controller internal to the sensor which can be tuned using sensor parameters.
This sensor requires a path to be defined to each of the two drive wheels under RightWheelLinkPath
and LeftWheelLinkPath
as seen below.
The Topic
parameter is the name of the topic which the sensor subscribes to in order to receive control commands. The OdometryTopic
provides the name of the topic odometry is to be published to and Frame
and OdometryChildFrame
populate the frame and odometry frame of the odometry message. For more information on the odometry frame in ROS see REP 105.
{
"params": {
"OdometryTopic": "/odom",
"Topic": "/cmd_vel",
"OdometryChildFrame": "odom",
"Frame": "base_footprint",
"RightWheelLinkPath": "link_MainBody/SuspensionRight/link/wheel_right/link",
"LeftWheelLinkPath": "link_MainBody/SuspensionLeft/link/wheel_left/link"
},
"name": "Differential Drive Control Sensor",
"type": "DifferentialDriveControlSensor"
}
Keyboard Control top#
This sensor is required for a vehicle to accept keyboard control commands. Parameters are not required.
{
"type": "KeyboardControlSensor",
"name": "Keyboard Car Control"
}
Wheel Control top#
This sensor is required for a vehicle to accept Logitech G920 wheel control commands. Parameters are not required.
{
"type": "WheelControlSensor",
"name": "Wheel Car Control"
}
Cruise Control top#
This sensor causes the vehicle to accelerate to the desired speed and then maintain the desired speed.
Parameter | Description | Unit | Type | Default Value | Minimum | Maximum |
---|---|---|---|---|---|---|
CruiseSpeed |
defines the desired speed | meters/second | Float | 0 | 0 | 200 |
{
"type": "CruiseControlSensor",
"name": "AD Car Control",
"params": {
"CruiseSpeed": 10
}
}
IMU top#
This sensor output at a fixed rate of 100 Hz. IMU publishes data on topics where the 2nd topic has corrected IMU data.
Parameter | Description |
---|---|
CorectedTopic |
defines the 2nd topic that the data is published to |
CorrectedFrame |
defines the 2nd frame for the ROS header |
{
"type": "ImuSensor",
"name": "IMU",
"params": {
"Topic": "/imu",
"Frame": "imu"
},
"transform": {
"x": 0,
"y": 0,
"z": 0,
"pitch": 0,
"yaw": 0,
"roll": 0
}
}
2D Ground Truth top#
This sensor outputs an image where objects are encased in a box. The color of the box depends on the type of object.
Object | Color |
---|---|
Car | Green |
Pedestrian | Yellow |
Bicycle | Cyan |
Unknown | Magenta |
Parameter | Description | Unit | Type | Default Value | Minimum | Maximum |
---|---|---|---|---|---|---|
Frequency |
defines the maximum rate that messages will be published | Hertz | Float | 10 | 1 | 100 |
Width |
defines the width of the image | pixels | Int | 1920 | 1 | 1920 |
Height |
defines the height of the iamge | pixels | Int | 1080 | 1 | 1080 |
FieldOfView |
defines the vertical angle that the camera sees | degrees | Float | 60 | 1 | 90 |
MinDistance |
defines how far an object must be from the sensor to be in the image | meters | Float | 0.1 | 0.01 | 1000 |
MaxDistance |
defines how close an object must be to the sensor to be in the image | meters | Float | 2000 | 0.01 | 2000 |
DetectionRange |
defines how close an object must be to be given a bounding box | meters | Float | 100 | 0.01 | 2000 |
{
"type": "PerceptionSensor2D",
"name": "2D Ground Truth",
"params": {
"Frequency": 10,
"Topic": "/simulator/ground_truth/2d_detections"
},
"transform": {
"x": 0,
"y": 1.7,
"z": -0.2,
"pitch": 0,
"yaw": 0,
"roll": 0
}
}
Radar top#
This sensor outputs the objects detected by the radar. Detected objects are visualized with a box colored by their type:
Type | Color |
---|---|
Car | Green |
Agent | Magenta |
Bicycle | Cyan |
Parameter | Description | Unit | Type | Default Value | Minimum | Maximum |
---|---|---|---|---|---|---|
Frequency |
defines the maximum rate that messages will be published | Hertz | Float | 13.4 | 1 | 100 |
{
"type": "RadarSensor",
"name": "Radar",
"params": {
"Frequency": 13.4,
"Topic": "/radar"
},
"transform": {
"x": 0,
"y": 0.689,
"z": 2.272,
"pitch": 0,
"yaw": 0,
"roll": 0
}
}
Ultrasonic top#
This sensor outputs the distance (to the center of the sensor) of the closest point within the sensor's FOV.
Parameter | Description | Unit | Type | Default Value | Minimum | Maximum |
---|---|---|---|---|---|---|
Width |
defines the width of the image output | pixels | Int | 400 | 1 | 1920 |
Height |
defines the height of the image output | pixels | Int | 160 | 1 | 1080 |
Frequency |
defines the maximum rate that messages will be published | Hertz | Int | 15 | 1 | 100 |
JpegQuality |
defines the quality if the image output | % | Int | 75 | 0 | 100 |
FieldOfView |
defines the vertical angle that the camera sees | degrees | Float | 40 | 1 | 90 |
MinDistance |
defines how far an object must be from the sensor for it to be detected | meters | Float | 0.3 | 0.01 | 1000 |
MaxDistance |
defines how close an object must be to the sensor for it to be detected | meters | Float | 2.0 | 0.01 | 2000 |
{
"type": "UltrasonicSensor",
"name": "Ultrasonic Sensor",
"params": {
"Width": 400,
"Height": 160,
"Frequency": 15,
"JpegQuality": 75,
"FieldOfView": 50,
"MinDistance": 0.3,
"MaxDistance": 2,
"Topic": "/simulator/ultrasonic",
"Frame": "ultrasonic"
},
"transform": {
"x": 0,
"y": 0.5,
"z": 2.5,
"pitch": -13,
"yaw": 0,
"roll": 0
}
}
Control Calibration top#
This sensor outputs control calibration criteria collected by AD Stacks (Apollo, Autoware). It generates steering, throttle or brakes with gear commands between minimum and maximum of velocity during duration.
Parameter | Description | Unit | Type | Minimum | Maximum |
---|---|---|---|---|---|
min_velocity |
defines the minimum velocity when criterion is executed | meters/second | Float | 0 | 50.0 |
max_velocity |
defines the maximum velocity when criterion is executed | meters/second | Float | 0 | 50.0 |
throttle |
defines the throttle which makes acceleration | Percent | Float | 0 | 100.0 |
brakes |
defines the brakes which make deceleration | Percent | Float | 0 | 100.0 |
steering |
defines ego vehicle's steering | Percent | Float | -100.0 | 100.0 |
gear |
defines ego vehicle's direction (forward or reverse) | String | |||
duration |
defines criterion's execution time | second | Float | 0 |
{
"type": "ControlCalibrationSensor",
"name": "Control Calibration",
"params": {
"states": [{
"min_velocity": 0.2,
"max_velocity": 10.0,
"throttle": 23,
"brakes": 0,
"steering": 0,
"gear": "forward",
"duration": 4
},
{
"min_velocity": 0.2,
"max_velocity": 2.0,
"throttle": 22,
"brakes": 0,
"steering": 0,
"gear": "reverse",
"duration": 4
}
]
}
}
Total Control Calibration Criteria:
Transform Sensor top#
This sensor is specifically used to parent other sensors.
For example, if there is a cluster of sensors a Transform
sensor can be added at the location of the cluster
and then the individual sensors can have a transform that is relative to the location of the Transform
sensor`.
Example usage
{
"type": "TransformSensor",
"name": "Cluster Reference",
"transform": {
"x": 0.75,
"y": 1.7,
"z": 1,
"pitch": 0,
"yaw": 0,
"roll": 0
}
},
{
"type": "ColorCameraSensor",
"name": "Main Camera",
"params": {
"Width": 1920,
"Height": 1080,
"Frequency": 15,
"JpegQuality": 75,
"FieldOfView": 50,
"MinDistance": 0.1,
"MaxDistance": 2000,
"Topic": "/simulator/main_camera",
"Frame": "camera",
"Distorted": true,
"DistortionParameters": [
-0.25349, 0.11868, 0, 0
]
},
"parent": "Cluster Reference",
"transform": {
"x": 0.1,
"y": 0,
"z": -0.1,
"pitch": 0,
"yaw": 0,
"roll": 0
}
},
{
"type": "LidarSensor",
"name": "Lidar-Uniform",
"params": {
"LaserCount": 32,
"FieldOfView": 41.33,
"CenterAngle": 10,
"MinDistance": 0.5,
"MaxDistance": 100,
"RotationFrequency": 10,
"MeasurementsPerRotation": 360,
"Compensated": true,
"PointColor": "#ff000000",
"Topic": "/point_cloud",
"Frame": "velodyne"
},
"parent": "Cluster Reference",
"transform": {
"x": 0,
"y": 0.2,
"z": 0,
"pitch": 0,
"yaw": 0,
"roll": 0
}
}
Signal Sensor top#
This sensor returns ground truth data for traffic light signals connected to the current lane of ego vehicle and creates bounding boxes around the detected signals. The color of the bounding box corresponds to the signal's type:
Bounding Box | Signal |
---|---|
Green | Green |
Yellow | Yellow |
Red | Red |
Parameter | Description | Unit | Type | Default Value | Minimum | Maximum |
---|---|---|---|---|---|---|
Frequency |
defines the maximum rate that messages will be published | Hertz | Float | 10 | 1 | 100 |
MaxDistance |
defines how close a traffic light must be to the sensor to be detected | meters | Float | 100 | 1 | 1000 |
{
"type": "SignalSensor",
"name": "Signal Sensor",
"params": {
"Frequency": 10,
"MaxDistance": 100,
"Topic": "/simulator/ground_truth/signals"
},
"transform": {
"x": 0,
"y": 0,
"z": 0,
"pitch": 0,
"yaw": 0,
"roll": 0
}
}
Video Recording Sensor top#
This sensor records a video for test cases. For local simulations, the path to the recorded video will be shown in the Video Recording Sensor
section of the Test Results for each simulation.
Parameter | Description | Unit | Type | Default Value | Minimum | Maximum |
---|---|---|---|---|---|---|
Width |
defines the width of the video | pixels | Int | 1920 | 1 | 1920 |
Height |
defines the width of the video | pixels | Int | 1080 | 1 | 1080 |
Framerate |
defines the number of frames per second of the video | fps | Int | 15 | 1 | 15 |
Bitrate |
defines the average number of bits per second | Kbps | Int | 3000 | 1000 | 6000 |
MaxBitrate |
defines the maximum number of bits per second | Kbps | Int | 6000 | 1000 | 6000 |
Quality |
defines the target constant quality level for VBR rate control (0 to 51, 0 means automatic) | Int | 22 | 0 | 51 |
{
"type": "VideoRecordingSensor",
"name": "Video Recording Sensor",
"params": {
"Width": 1920,
"Height": 1080,
"Framerate": 15,
"Bitrate": 3000,
"MaxBitrate": 6000,
"Quality": 22
},
"transform": {
"x": 0,
"y": 10.0,
"z": -10.0,
"pitch": 30,
"yaw": 0,
"roll": 0
}
}
Comfort Sensor top#
Comfort Sensor will detect whether a vehicle's acceleration, rotation or other values are out of acceptable ranges. For more details, check github.
Parameter | Description | Unit | Type | Default Value | Minimum | Maximum |
---|---|---|---|---|---|---|
maxAccelAllowed |
Maximum acceleration allowed | m/s^2 | Int | |||
maxJerkAllowed |
Maximum jerk allowed | m/s^3 | Int | |||
maxAngularVelocityAllowed |
Maximum angular velocity allowed | deg/s | Int | |||
maxAngularAccelerationAllowed |
Maximum angular acceleration allowed | deg/s^2 | Int | |||
rollTolerance |
Maximum deg rotation on the x axis | deg | Int | |||
slipTolerance |
Maximum deg difference between vehicle's velocity and vehicle's forward | deg | Int |
{
"type" : "Comfort",
"name" : "Comfort Sensor",
"params": {
"maxAccelAllowed": 8,
"maxJerkAllowed": 4,
"maxAngularVelocityAllowed": 200,
"maxAngularAccelerationAllowed": 100,
"rollTolerance": 10,
"slipTolerance": 15
}
}
Stop Line Sensor top#
The Stop Line sensor is a sensor used purely for analyzing the results of a simulation when the Create test report option is enabled for the simulation (See here for more information on test reports). The sensor will allow the simulator to detect and report stop line violations.
{
"name": "Stop Line Sensor",
"type": "StopLineSensor"
}
Vehicle Odometry top#
The Vehicle Odometry sensor publishes information on the vehicle velocity and front and rear angles in ROS and ROS2 using the lgsvl_msgs/VehicleOdometry
message type.
{
"type": "VehicleOdometrySensor",
"name": "Vehicle Odometry Sensor",
"params": {
"Topic": "lgsvl/vehicle_odom",
},
}
Vehicle State top#
The Vehicle State sensor publishes information on the state of the vehicle that is not captured in the Can Bus sensor, such as the state of the headlights, blinkers, and wipers. The sensor publishes in ROS and ROS2 using the lgsvl_msgs/VehicleStateData
message type. See here for all the fields published by the sensor.
{
"type": "VehicleStateSensor",
"name": "Vehicle State Sensor",
"params": {
"Topic": "lgsvl/vehicle_state",
},
}
HUD Keyboard Control top#
The HUD Keyboard Control sensor is a Keyboard Control sensor with an additional Heads Up Display (HUD) that displays the following information:
- Speed (mph)
- Current gear
- Engine speed (rpm)
- Ignition status indicator
- Parking brake indicator
The HUD is shown by enabling the sensor visualization for the HUD Keyboard Sensor.
{
"type": "HUDKeyboardControlSensor",
"name": "HUD Keyboard Control Sensor"
}
AutowareAI Control top#
The AutowareAI Control sensor subscribes to the vehicle control topic from Autoware AI in ROS and allows the ego vehicle to react to control commands. The sensor subscribes to autoware_msgs/VehicleCmd
message type.
{
"type": "VehicleStateSensor",
"name": "Vehicle State Sensor",
"params": {
"Topic": "lgsvl/vehicle_state",
},
}
Lane-line Sensor top#
This sensor outputs lines data for the current lane in third-degree polynomial format, along with line type and color. More details are available on the lane-line sensor page.
Parameter | Description | Unit | Type | Default Value | Minimum | Maximum |
---|---|---|---|---|---|---|
Width |
The width of the image output * | pixels | Int | 1920 | 1 | 1920 |
Height |
The height of the image output * | pixels | Int | 1080 | 1 | 1080 |
Frequency |
The maximum rate that messages will be published | Hertz | Int | 15 | 1 | 100 |
FieldOfView |
The vertical angle that the camera sees | degrees | Float | 60 | 1 | 90 |
MinDistance |
The near plane of the preview camera * | meters | Float | 0.1 | 0.01 | 1000 |
MaxDistance |
The far plane of the preview camera * | meters | Float | 2000 | 0.01 | 2000 |
DetectionRange |
Defines how far from the sensor line will be sampled | meters | Float | 50 | 10 | 200 |
SampleDelta |
The distance between discrete line samples | meters | Float | 0.5 | 0.05 | 1 |
* These parameters only affect the preview, not the output data itself.
{
"type": "LaneLineSensor",
"name": "LaneLineSensor",
"params": {
"Width": 1920,
"Height": 1080,
"Frequency": 10,
"FieldOfView": 60,
"MinDistance": 0.1,
"MaxDistance": 2000,
"DetectionRange": 50,
"SampleDelta": 0.5,
"Topic": "/simulator/lane_line"
},
"transform": {
"x": 0,
"y": 1.7,
"z": 3.0,
"pitch": 0,
"yaw": 0,
"roll": 0
}
}
Lane Following top#
The Lane Following sensor is used to steer an ego vehicle using a deep learning model. The sensor subscribes to steering commands from the model which are sent as lgsvl_msgs/VehicleControlData
messages in ROS2 and applies them to the ego vehicle. Read this tutorial to learn more.
{
"type": "LaneFollowingSensor",
"name": "Lane Following Sensor",
"params": {
"Topic": "/lanefollowing/steering_cmd",
}
}