473 lines
20 KiB
YAML
473 lines
20 KiB
YAML
---
|
|
- module_name: carla
|
|
# - CLASSES ------------------------------
|
|
classes:
|
|
- class_name: SensorData
|
|
# - DESCRIPTION ------------------------
|
|
doc: >
|
|
Base class for all the objects containing data generated by a carla.Sensor. This objects should be the argument of the function said sensor is listening to, in order to work with them. Each of these sensors needs for a specific type of sensor data. Hereunder is a list of the sensors and their corresponding data.
|
|
- Cameras (RGB, depth and semantic segmentation): carla.Image.
|
|
- Collision detector: carla.CollisionEvent.
|
|
- Gnss detector: carla.GnssMeasurement.
|
|
- IMU detector: carla.IMUMeasurement.
|
|
- Lane invasion detector: carla.LaneInvasionEvent.
|
|
- Lidar raycast: carla.LidarMeasurement.
|
|
- Obstacle detector: carla.ObstacleDetectionEvent.
|
|
- Radar detector: carla.RadarMeasurement.
|
|
- RSS sensor: carla.RssResponse.
|
|
# - PROPERTIES -------------------------
|
|
instance_variables:
|
|
- var_name: frame
|
|
type: int
|
|
doc: >
|
|
Frame count when the data was generated.
|
|
- var_name: timestamp
|
|
type: float
|
|
doc: >
|
|
Simulation-time when the data was generated.
|
|
- var_name: transform
|
|
type: carla.Transform
|
|
doc: >
|
|
Sensor's transform when the data was generated.
|
|
# --------------------------------------
|
|
|
|
- class_name: ColorConverter
|
|
# - DESCRIPTION ------------------------
|
|
doc: >
|
|
Class that defines conversion patterns that can be applied to a carla.Image in order to show information provided by carla.Sensor. Depth conversions cause a loss of accuracy, as sensors detect depth as <b>float</b> that is then converted to a grayscale value between 0 and 255. Take a look a this [recipe](ref_code_recipes.md#converted-image-recipe) to see an example of how to create and save image data for <b>sensor.camera.semantic_segmentation</b>.
|
|
# - PROPERTIES -------------------------
|
|
instance_variables:
|
|
- var_name: CityScapesPalette
|
|
doc: >
|
|
Converts the image to a segmentated map using tags provided by the blueprint library. Used by <b>sensor.camera.semantic_segmentation</b>.
|
|
- var_name: Depth
|
|
doc: >
|
|
Converts the image to a linear depth map. Used by <b>sensor.camera.depth</b>.
|
|
- var_name: LogarithmicDepth
|
|
doc: >
|
|
Converts the image to a depth map using a logarithmic scale, leading to better precision for small distances at the expense of losing it when further away.
|
|
- var_name: Raw
|
|
doc: >
|
|
No changes applied to the image.
|
|
|
|
- class_name: Image
|
|
parent: carla.SensorData
|
|
# - DESCRIPTION ------------------------
|
|
doc: >
|
|
Class that defines an image of 32-bit BGRA colors that will be used as initial data retrieved by camera sensors. There are different camera sensors (currently three, RGB, depth and semantic segmentation) and each of these makes different use for the images. Learn more about them [here](ref_sensors.md).
|
|
# - PROPERTIES -------------------------
|
|
instance_variables:
|
|
- var_name: fov
|
|
type: float
|
|
doc: >
|
|
Horizontal field of view of the image in degrees.
|
|
- var_name: height
|
|
type: int
|
|
doc: >
|
|
Image height in pixels.
|
|
- var_name: width
|
|
type: int
|
|
doc: >
|
|
Image width in pixels.
|
|
- var_name: raw_data
|
|
type: bytes
|
|
# - METHODS ----------------------------
|
|
methods:
|
|
- def_name: convert
|
|
params:
|
|
- param_name: color_converter
|
|
type: carla.ColorConverter
|
|
doc: >
|
|
Converts the image following the `color_converter` pattern.
|
|
# --------------------------------------
|
|
- def_name: save_to_disk
|
|
params:
|
|
- param_name: path
|
|
type: str
|
|
doc: >
|
|
Path that will contain the image.
|
|
- param_name: color_converter
|
|
type: carla.ColorConverter
|
|
default: Raw
|
|
doc: >
|
|
Default <b>Raw</b> will make no changes.
|
|
doc: >
|
|
Saves the image to disk using a converter pattern stated as `color_converter`. The default conversion pattern is <b>Raw</b> that will make no changes to the image.
|
|
# --------------------------------------
|
|
- def_name: __getitem__
|
|
params:
|
|
- param_name: pos
|
|
type: int
|
|
# --------------------------------------
|
|
- def_name: __iter__
|
|
# --------------------------------------
|
|
- def_name: __len__
|
|
# --------------------------------------
|
|
- def_name: __setitem__
|
|
params:
|
|
- param_name: pos
|
|
type: int
|
|
- param_name: color
|
|
type: carla.Color
|
|
# --------------------------------------
|
|
- def_name: __str__
|
|
# --------------------------------------
|
|
|
|
- class_name: LidarMeasurement
|
|
parent: carla.SensorData
|
|
# - DESCRIPTION ------------------------
|
|
doc: >
|
|
Class that defines the lidar data retrieved by a <b>sensor.lidar.ray_cast</b>. This essentially simulates a rotating lidar using ray-casting. Learn more about this [here](ref_sensors.md#lidar-raycast-sensor).
|
|
# - PROPERTIES -------------------------
|
|
instance_variables:
|
|
- var_name: channels
|
|
type: int
|
|
doc: >
|
|
Number of lasers shot.
|
|
- var_name: horizontal_angle
|
|
type: float
|
|
doc: >
|
|
Horizontal angle the Lidar is rotated at the time of the measurement (in radians).
|
|
- var_name: raw_data
|
|
type: bytes
|
|
doc: >
|
|
List of 3D points received as data.
|
|
# - METHODS ----------------------------
|
|
methods:
|
|
- def_name: save_to_disk
|
|
params:
|
|
- param_name: path
|
|
type: str
|
|
doc: >
|
|
Saves the point cloud to disk as a <b>.ply</b> file describing data from 3D scanners. The files generated are ready to be used within [MeshLab](http://www.meshlab.net/), an open source system for processing said files. Just take into account that axis may differ from Unreal Engine and so, need to be reallocated.
|
|
# --------------------------------------
|
|
- def_name: get_point_count
|
|
params:
|
|
- param_name: channel
|
|
type: int
|
|
doc: >
|
|
Retrieves the number of points sorted by channel that are generated by this measure. Sorting by channel allows to identify the original channel for every point.
|
|
# --------------------------------------
|
|
- def_name: __getitem__
|
|
params:
|
|
- param_name: pos
|
|
type: int
|
|
# --------------------------------------
|
|
- def_name: __iter__
|
|
# --------------------------------------
|
|
- def_name: __len__
|
|
# --------------------------------------
|
|
- def_name: __setitem__
|
|
params:
|
|
- param_name: pos
|
|
type: int
|
|
- param_name: location
|
|
type: carla.Location
|
|
# --------------------------------------
|
|
- def_name: __str__
|
|
# --------------------------------------
|
|
|
|
- class_name: CollisionEvent
|
|
parent: carla.SensorData
|
|
# - DESCRIPTION ------------------------
|
|
doc: >
|
|
Class that defines a collision data for <b>sensor.other.collision</b>. The sensor creates one of this for every collision detected which may be many for one simulation step. Learn more about this [here](ref_sensors.md#collision-detector).
|
|
# - PROPERTIES -------------------------
|
|
instance_variables:
|
|
- var_name: actor
|
|
type: carla.Actor
|
|
doc: >
|
|
The actor the sensor is attached to, the one that measured the collision.
|
|
- var_name: other_actor
|
|
type: carla.Actor
|
|
doc: >
|
|
The second actor involved in the collision.
|
|
- var_name: normal_impulse
|
|
type: carla.Vector3D
|
|
doc: >
|
|
Normal impulse resulting of the collision.
|
|
|
|
- class_name: ObstacleDetectionEvent
|
|
parent: carla.SensorData
|
|
# - DESCRIPTION ------------------------
|
|
doc: >
|
|
Class that defines the obstacle data for <b>sensor.other.obstacle</b>. Learn more about this [here](ref_sensors.md#obstacle-detector).
|
|
# - PROPERTIES -------------------------
|
|
instance_variables:
|
|
- var_name: actor
|
|
type: carla.Actor
|
|
doc: >
|
|
The actor the sensor is attached to.
|
|
- var_name: other_actor
|
|
type: carla.Actor
|
|
doc: >
|
|
The actor or object considered to be an obstacle.
|
|
- var_name: distance
|
|
type: float
|
|
doc: >
|
|
Distance between `actor` and `other`.
|
|
# - METHODS ----------------------------
|
|
methods:
|
|
- def_name: __str__
|
|
# --------------------------------------
|
|
|
|
- class_name: LaneInvasionEvent
|
|
parent: carla.SensorData
|
|
# - DESCRIPTION ------------------------
|
|
doc: >
|
|
Class that defines lanes invasion for <b>sensor.other.lane_invasion</b>. It works only client-side and is dependant on OpenDRIVE to provide reliable information. The sensor creates one of this every time there is a lane invasion, which may be more than once per simulation step. Learn more about this [here](ref_sensors.md#lane-invasion-detector).
|
|
# - PROPERTIES -------------------------
|
|
instance_variables:
|
|
- var_name: actor
|
|
type: carla.Actor
|
|
doc: >
|
|
Gets the actor the sensor is attached to, the one that invaded another lane.
|
|
- var_name: crossed_lane_markings
|
|
type: list(carla.LaneMarking)
|
|
doc: >
|
|
List of lane markings that have been crossed and detected by the sensor.
|
|
# - METHODS ----------------------------
|
|
methods:
|
|
- def_name: __str__
|
|
# --------------------------------------
|
|
|
|
- class_name: GnssMeasurement
|
|
parent: carla.SensorData
|
|
# - DESCRIPTION ------------------------
|
|
doc: >
|
|
Class that defines the Gnss data registered by a <b>sensor.other.gnss</b>. It essentially reports its position with the position of the sensor and an OpenDRIVE geo-reference.
|
|
# - PROPERTIES -------------------------
|
|
instance_variables:
|
|
- var_name: altitude
|
|
type: float
|
|
doc: >
|
|
Height regarding ground level.
|
|
- var_name: latitude
|
|
type: float
|
|
doc: >
|
|
North/South value of a point on the map.
|
|
- var_name: longitude
|
|
type: float
|
|
doc: >
|
|
West/East value of a point on the map.
|
|
# - METHODS ----------------------------
|
|
methods:
|
|
- def_name: __str__
|
|
# --------------------------------------
|
|
|
|
- class_name: IMUMeasurement
|
|
parent: carla.SensorData
|
|
# - DESCRIPTION ------------------------
|
|
doc: >
|
|
Class that defines the data registered by a <b>sensor.other.imu</b>, regarding the sensor's transformation according to the current carla.World. It essentially acts as accelerometer, gyroscope and compass.
|
|
# - PROPERTIES -------------------------
|
|
instance_variables:
|
|
- var_name: accelerometer
|
|
type: carla.Vector3D
|
|
doc: >
|
|
Linear acceleration in m/s^2.
|
|
- var_name: compass
|
|
type: float
|
|
doc: >
|
|
Orientation with regard to the North ((0.0, -1.0, 0.0) in Unreal Engine) in radians.
|
|
- var_name: gyroscope
|
|
type: carla.Vector3D
|
|
doc: >
|
|
Angular velocity in rad/sec.
|
|
# - METHODS ----------------------------
|
|
methods:
|
|
- def_name: __str__
|
|
# --------------------------------------
|
|
|
|
- class_name: RadarMeasurement
|
|
parent: carla.SensorData
|
|
# - DESCRIPTION ------------------------
|
|
doc: >
|
|
Class that defines and gathers the measures registered by a <b>sensor.other.radar</b>, representing a wall of points in front of the sensor with a distance, angle and velocity in relation to it. The data consists of a carla.RadarDetection array. Learn more about this [here](ref_sensors.md#radar-sensor).
|
|
# - PROPERTIES -------------------------
|
|
instance_variables:
|
|
- var_name: raw_data
|
|
type: bytes
|
|
doc: >
|
|
The complete information of the carla.RadarDetection the radar has registered.
|
|
# - METHODS ----------------------------
|
|
methods:
|
|
- def_name: get_detection_count
|
|
doc: >
|
|
Retrieves the number of entries generated, same as **<font color="#7fb800">\__str__()</font>**.
|
|
# --------------------------------------
|
|
- def_name: __getitem__
|
|
params:
|
|
- param_name: pos
|
|
type: int
|
|
# --------------------------------------
|
|
- def_name: __iter__
|
|
# --------------------------------------
|
|
- def_name: __len__
|
|
# --------------------------------------
|
|
- def_name: __setitem__
|
|
params:
|
|
- param_name: pos
|
|
type: int
|
|
- param_name: detection
|
|
type: carla.RadarDetection
|
|
# --------------------------------------
|
|
- def_name: __str__
|
|
# --------------------------------------
|
|
|
|
- class_name: RadarDetection
|
|
# - DESCRIPTION ------------------------
|
|
doc: >
|
|
Data contained inside a carla.RadarMeasurement. Each of these represents one of the points in the cloud that a <b>sensor.other.radar</b> registers and contains the distance, angle and velocity in relation to the radar.
|
|
# - PROPERTIES -------------------------
|
|
instance_variables:
|
|
- var_name: altitude
|
|
type: float
|
|
doc: >
|
|
Altitude angle of the detection in radians.
|
|
# --------------------------------------
|
|
- var_name: azimuth
|
|
type: float
|
|
doc: >
|
|
Azimuth angle of the detection in radians.
|
|
# --------------------------------------
|
|
- var_name: depth
|
|
type: float
|
|
doc: >
|
|
Distance in meters from the sensor to the detection position.
|
|
# --------------------------------------
|
|
- var_name: velocity
|
|
type: float
|
|
doc: >
|
|
The velocity of the detected object towards the sensor in m/s.
|
|
# - METHODS ----------------------------
|
|
methods:
|
|
- def_name: __str__
|
|
# --------------------------------------
|
|
|
|
- class_name: RssResponse
|
|
parent: carla.SensorData
|
|
# - DESCRIPTION ------------------------
|
|
doc: >
|
|
Class that contains the output of a carla.RssSensor. This is the result of the RSS calculations performed for the parent vehicle of the sensor.
|
|
|
|
|
|
A carla.RssRestrictor will use the data to modify the carla.VehicleControl of the vehicle.
|
|
# - PROPERTIES -------------------------
|
|
instance_variables:
|
|
- var_name: response_valid
|
|
type: bool
|
|
doc: >
|
|
States if the response is valid. It is __False__ if calculations failed or an exception occured.
|
|
# --------------------------------------
|
|
- var_name: proper_response
|
|
type: <a href="https://intel.github.io/ad-rss-lib/doxygen/ad_rss/structad_1_1rss_1_1state_1_1ProperResponse.html">libad_rss_python.ProperResponse</a>
|
|
doc: >
|
|
The proper response that the RSS calculated for the vehicle.
|
|
# --------------------------------------
|
|
- var_name: acceleration_restriction
|
|
type: <a href="https://intel.github.io/ad-rss-lib/doxygen/ad_rss/structad_1_1rss_1_1world_1_1AccelerationRestriction.html">libad_rss_python.AccelerationRestriction</a>
|
|
doc: >
|
|
Acceleration restrictions to be applied, according to the RSS calculation.
|
|
# --------------------------------------
|
|
- var_name: rss_state_snapshot
|
|
type: <a href="https://intel.github.io/ad-rss-lib/doxygen/ad_rss/structad_1_1rss_1_1state_1_1RssStateSnapshot.html">libad_rss_python.RssStateSnapshot</a>
|
|
doc: >
|
|
Detailed RSS states at the current moment in time.
|
|
# --------------------------------------
|
|
- var_name: ego_dynamics_on_route
|
|
type: carla.RssEgoDynamicsOnRoute
|
|
doc: >
|
|
Current ego vehicle dynamics regarding the route.
|
|
# - METHODS ----------------------------
|
|
methods:
|
|
- def_name: __str__
|
|
# --------------------------------------
|
|
|
|
- class_name: RssEgoDynamicsOnRoute
|
|
# - DESCRIPTION ------------------------
|
|
doc: >
|
|
Part of the data contained inside a carla.RssResponse describing the state of the vehicle. The parameters include its current dynamics, and how it is heading regarding the target route.
|
|
# - PROPERTIES -------------------------
|
|
instance_variables:
|
|
- var_name: ego_speed
|
|
type: <a href="https://ad-map-access.readthedocs.io/en/latest/ad_physics/apidoc/html/classad_1_1physics_1_1Speed.html">libad_physics_python.Speed</a>
|
|
doc: >
|
|
The ego vehicle's speed.
|
|
# --------------------------------------
|
|
- var_name: min_stopping_distance
|
|
type: <a href="https://ad-map-access.readthedocs.io/en/latest/ad_physics/apidoc/html/classad_1_1physics_1_1Distance.html">libad_physics_python.Distance</a>
|
|
doc: >
|
|
The current minimum stopping distance.
|
|
# --------------------------------------
|
|
- var_name: ego_center
|
|
type: <a href="https://ad-map-access.readthedocs.io/en/latest/ad_map_access/apidoc/html/structad_1_1map_1_1point_1_1ENUPoint.html">libad_map_access_python.ENUPoint</a>
|
|
doc: >
|
|
The considered enu position of the ego vehicle.
|
|
# --------------------------------------
|
|
- var_name: ego_heading
|
|
type: <a href="https://ad-map-access.readthedocs.io/en/latest/ad_map_access/apidoc/html/classad_1_1map_1_1point_1_1ENUHeading.html">libad_map_access_python.ENUHeading</a>
|
|
doc: >
|
|
The considered heading of the ego vehicle.
|
|
# --------------------------------------
|
|
- var_name: ego_center_within_route
|
|
type: bool
|
|
doc: >
|
|
States if the ego vehicle's center is within the route.
|
|
# --------------------------------------
|
|
- var_name: crossing_border
|
|
type: bool
|
|
doc: >
|
|
States if the vehicle is already crossing one of the lane borders.
|
|
# --------------------------------------
|
|
- var_name: route_heading
|
|
type: <a href="https://ad-map-access.readthedocs.io/en/latest/ad_map_access/apidoc/html/classad_1_1map_1_1point_1_1ENUHeading.html">libad_map_access_python.ENUHeading</a>
|
|
doc: >
|
|
The considered heading of the route.
|
|
# --------------------------------------
|
|
- var_name: route_nominal_center
|
|
type: <a href="https://ad-map-access.readthedocs.io/en/latest/ad_map_access/apidoc/html/structad_1_1map_1_1point_1_1ENUPoint.html">libad_map_access_python.ENUPoint</a>
|
|
doc: >
|
|
The considered nominal center of the current route.
|
|
# --------------------------------------
|
|
- var_name: heading_diff
|
|
type: <a href="https://ad-map-access.readthedocs.io/en/latest/ad_map_access/apidoc/html/classad_1_1map_1_1point_1_1ENUHeading.html">libad_map_access_python.ENUHeading</a>
|
|
doc: >
|
|
The considered heading diff towards the route.
|
|
# --------------------------------------
|
|
- var_name: route_speed_lat
|
|
type: <a href="https://ad-map-access.readthedocs.io/en/latest/ad_physics/apidoc/html/classad_1_1physics_1_1Speed.html">libad_physics_python.Speed</a>
|
|
doc: >
|
|
The ego vehicle's speed component _lat_ regarding the route.
|
|
# --------------------------------------
|
|
- var_name: route_speed_lon
|
|
type: <a href="https://ad-map-access.readthedocs.io/en/latest/ad_physics/apidoc/html/classad_1_1physics_1_1Speed.html">libad_physics_python.Speed</a>
|
|
doc: >
|
|
The ego vehicle's speed component _lon_ regarding the route.
|
|
# --------------------------------------
|
|
- var_name: route_accel_lat
|
|
type: <a href="https://ad-map-access.readthedocs.io/en/latest/ad_physics/apidoc/html/classad_1_1physics_1_1Acceleration.html">libad_physics_python.Acceleration</a>
|
|
doc: >
|
|
The ego vehicle's acceleration component _lat_ regarding the route.
|
|
# --------------------------------------
|
|
- var_name: route_accel_lon
|
|
type: <a href="https://ad-map-access.readthedocs.io/en/latest/ad_physics/apidoc/html/classad_1_1physics_1_1Acceleration.html">libad_physics_python.Acceleration</a>
|
|
doc: >
|
|
The ego vehicle's acceleration component _lon_ regarding the route.
|
|
# --------------------------------------
|
|
- var_name: avg_route_accel_lat
|
|
type: <a href="https://ad-map-access.readthedocs.io/en/latest/ad_physics/apidoc/html/classad_1_1physics_1_1Acceleration.html">libad_physics_python.Acceleration</a>
|
|
doc: >
|
|
The ego vehicle's acceleration component _lat_ regarding the route smoothened by an average filter.
|
|
# --------------------------------------
|
|
- var_name: avg_route_accel_lon
|
|
type: <a href="https://ad-map-access.readthedocs.io/en/latest/ad_physics/apidoc/html/classad_1_1physics_1_1Acceleration.html">libad_physics_python.Acceleration</a>
|
|
doc: >
|
|
The ego acceleration component _lon_ regarding the route smoothened by an average filter.
|
|
# - METHODS ----------------------------
|
|
methods:
|
|
- def_name: __str__
|
|
# --------------------------------------
|
|
|
|
...
|