carla/PythonAPI/docs/sensor_data.yml

939 lines
39 KiB
YAML
Raw Normal View History

2019-05-03 18:18:02 +08:00
---
- module_name: carla
# - CLASSES ------------------------------
2019-05-03 18:18:02 +08:00
classes:
- class_name: SensorData
2019-05-03 18:18:02 +08:00
# - DESCRIPTION ------------------------
doc: >
2020-09-02 22:15:58 +08:00
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.<br>
- Cameras (RGB, depth and semantic segmentation): carla.Image.<br>
- Collision detector: carla.CollisionEvent.<br>
- GNSS sensor: carla.GnssMeasurement.<br>
- IMU sensor: carla.IMUMeasurement.<br>
- Lane invasion detector: carla.LaneInvasionEvent.<br>
- LIDAR sensor: carla.LidarMeasurement.<br>
- Obstacle detector: carla.ObstacleDetectionEvent.<br>
- Radar sensor: carla.RadarMeasurement.<br>
- RSS sensor: carla.RssResponse.<br>
2020-07-31 19:16:12 +08:00
- Semantic LIDAR sensor: carla.SemanticLidarMeasurement.
2019-05-03 18:18:02 +08:00
# - PROPERTIES -------------------------
instance_variables:
- var_name: frame
type: int
doc: >
Frame count when the data was generated.
- var_name: timestamp
type: float
2020-09-14 22:58:48 +08:00
var_units: seconds
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 at the snipet in carla.Sensor.listen 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 segmented map using tags provided by the blueprint library. Used by the [semantic segmentation camera](ref_sensors.md#semantic-segmentation-camera).
- var_name: Depth
doc: >
2020-09-21 22:44:03 +08:00
Converts the image to a linear depth map. Used by the [depth camera](ref_sensors.md#depth-camera).
- 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: >
2020-09-21 22:44:03 +08:00
No changes applied to the image. Used by the [RGB camera](ref_sensors.md#rgb-camera).
2020-09-16 23:33:51 +08:00
- class_name: CityObjectLabel
# - DESCRIPTION ------------------------
doc: >
2021-01-28 18:58:39 +08:00
Enum declaration that contains the different tags available to filter the bounding boxes returned by carla.World.get_level_bbs(). These values correspond to the [semantic tag](ref_sensors.md#semantic-segmentation-camera) that the elements in the scene have.
2020-09-16 23:33:51 +08:00
# - PROPERTIES -------------------------
instance_variables:
- var_name: None
- var_name: Buildings
- var_name: Fences
- var_name: Other
- var_name: Pedestrians
- var_name: Poles
- var_name: RoadLines
- var_name: Roads
- var_name: Sidewalks
- var_name: TrafficSigns
- var_name: Vegetation
- var_name: Vehicles
- var_name: Walls
- var_name: Sky
- var_name: Ground
- var_name: Bridge
- var_name: RailTrack
- var_name: GuardRail
- var_name: TrafficLight
- var_name: Static
- var_name: Dynamic
- var_name: Water
- var_name: Terrain
- var_name: Any
2020-09-16 23:33:51 +08:00
- class_name: Image
2019-06-05 21:05:57 +08:00
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
2020-09-14 22:58:48 +08:00
var_units: degrees
doc: >
2020-09-14 22:58:48 +08:00
Horizontal field of view of the image.
- 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
doc: >
Flattened array of pixel data, use reshape to create an image array.
# - 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__
2020-10-02 23:08:50 +08:00
doc: >
2020-10-08 15:45:19 +08:00
Iterate over the carla.Color that form the image.
# --------------------------------------
- def_name: __len__
# --------------------------------------
- def_name: __setitem__
params:
- param_name: pos
type: int
- param_name: color
type: carla.Color
# --------------------------------------
- def_name: __str__
# --------------------------------------
- class_name: OpticalFlowImage
parent: carla.SensorData
# - DESCRIPTION ------------------------
doc: >
Class that defines an optical flow image of 2-Dimension float (32-bit) vectors representing the optical flow detected in the field of view. The components of the vector represents the displacement of an object in the image plane. Each component outputs values in the normalized range [-2,2] which scales to [-2 size, 2 size] with size being the total resolution in the corresponding component.
# - PROPERTIES -------------------------
instance_variables:
- var_name: fov
type: float
var_units: degrees
doc: >
Horizontal field of view of the image.
- 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
doc: >
Flattened array of pixel data, use reshape to create an image array.
# - METHODS ----------------------------
methods:
- def_name: get_color_coded_flow
return: carla.Image
doc: >
Visualization helper. Converts the optical flow image to an RGB image.
# --------------------------------------
- def_name: __getitem__
params:
- param_name: pos
type: int
# --------------------------------------
- def_name: __iter__
doc: >
Iterate over the carla.OpticalFlowPixel that form the image.
# --------------------------------------
- def_name: __len__
# --------------------------------------
- def_name: __setitem__
params:
- param_name: pos
type: int
- param_name: color
type: carla.Color
# --------------------------------------
- def_name: __str__
# --------------------------------------
- class_name: LidarMeasurement
2019-06-05 21:05:57 +08:00
parent: carla.SensorData
# - DESCRIPTION ------------------------
doc: >
2020-07-31 19:16:12 +08:00
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
2020-09-14 22:58:48 +08:00
var_units: radians
doc: >
2020-09-14 22:58:48 +08:00
Horizontal angle the LIDAR is rotated at the time of the measurement.
# --------------------------------------
- var_name: raw_data
type: bytes
2019-05-03 18:18:02 +08:00
doc: >
Received list of 4D points. Each point consists of [x,y,z] coordinates plus the intensity computed for that point.
2019-05-03 18:18:02 +08:00
# - 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__
2020-10-02 23:08:50 +08:00
doc: >
Iterate over the carla.LidarDetection retrieved as data.
# --------------------------------------
- def_name: __len__
# --------------------------------------
- def_name: __setitem__
params:
- param_name: pos
type: int
- param_name: detection
type: carla.LidarDetection
# --------------------------------------
- def_name: __str__
# --------------------------------------
- class_name: LidarDetection
# - DESCRIPTION ------------------------
doc: >
Data contained inside a carla.LidarMeasurement. Each of these represents one of the points in the cloud with its location and its associated intensity.
# - PROPERTIES -------------------------
instance_variables:
- var_name: point
type: carla.Location
2020-09-14 22:58:48 +08:00
var_units: meters
doc: >
Point in xyz coordinates.
# --------------------------------------
- var_name: intensity
type: float
doc: >
2020-09-14 22:58:48 +08:00
Computed intensity for this point as a scalar value between [0.0 , 1.0].
# - METHODS ----------------------------
methods:
- def_name: __str__
# --------------------------------------
2020-07-31 07:14:52 +08:00
- class_name: SemanticLidarMeasurement
2020-07-30 21:38:18 +08:00
parent: carla.SensorData
# - DESCRIPTION ------------------------
doc: >
2020-07-31 19:16:12 +08:00
Class that defines the semantic LIDAR data retrieved by a <b>sensor.lidar.ray_cast_semantic</b>. This essentially simulates a rotating LIDAR using ray-casting. Learn more about this [here](ref_sensors.md#semanticlidar-raycast-sensor).
2020-07-30 21:38:18 +08:00
# - PROPERTIES -------------------------
instance_variables:
- var_name: channels
type: int
doc: >
Number of lasers shot.
# --------------------------------------
2020-07-30 21:38:18 +08:00
- var_name: horizontal_angle
type: float
2020-09-15 21:40:57 +08:00
var_units: radians
2020-07-30 21:38:18 +08:00
doc: >
2020-09-15 21:40:57 +08:00
Horizontal angle the LIDAR is rotated at the time of the measurement.
# --------------------------------------
2020-07-30 21:38:18 +08:00
- var_name: raw_data
type: bytes
doc: >
2020-07-31 19:16:12 +08:00
Received list of raw detection points. Each point consists of [x,y,z] coordinates plus the cosine of the incident angle, the index of the hit actor, and its semantic tag.
2020-07-30 21:38:18 +08:00
# - METHODS ----------------------------
methods:
- def_name: save_to_disk
params:
- param_name: path
type: str
doc: >
2020-07-31 19:16:12 +08:00
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.
2020-07-30 21:38:18 +08:00
# --------------------------------------
- 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__
2020-10-02 23:08:50 +08:00
doc: >
Iterate over the carla.SemanticLidarDetection retrieved as data.
2020-07-30 21:38:18 +08:00
# --------------------------------------
- def_name: __len__
# --------------------------------------
- def_name: __setitem__
params:
- param_name: pos
type: int
- param_name: detection
2020-07-31 07:14:52 +08:00
type: carla.SemanticLidarDetection
2020-07-30 21:38:18 +08:00
# --------------------------------------
- def_name: __str__
# --------------------------------------
2020-07-31 07:14:52 +08:00
- class_name: SemanticLidarDetection
2020-07-30 21:38:18 +08:00
# - DESCRIPTION ------------------------
doc: >
2020-07-31 19:16:12 +08:00
Data contained inside a carla.SemanticLidarMeasurement. Each of these represents one of the points in the cloud with its location, the cosine of the incident angle, index of the object hit, and its semantic tag.
2020-07-30 21:38:18 +08:00
# - PROPERTIES -------------------------
instance_variables:
- var_name: point
type: carla.Location
2020-09-14 22:58:48 +08:00
var_units: meters
2020-07-30 21:38:18 +08:00
doc: >
2020-07-31 19:16:12 +08:00
[x,y,z] coordinates of the point.
2020-07-30 21:38:18 +08:00
# --------------------------------------
- var_name: cos_inc_angle
type: float
doc: >
2020-07-31 19:16:12 +08:00
Cosine of the incident angle between the ray, and the normal of the hit object.
2020-07-30 21:38:18 +08:00
# --------------------------------------
- var_name: object_idx
type: uint
doc: >
2020-09-15 21:40:57 +08:00
ID of the actor hit by the ray.
2020-07-30 21:38:18 +08:00
# --------------------------------------
- var_name: object_tag
type: uint
doc: >
2020-09-15 21:40:57 +08:00
[Semantic tag](https://carla.readthedocs.io/en/latest/ref_sensors/#semantic-segmentation-camera) of the component hit by the ray.
2020-07-30 21:38:18 +08:00
# - METHODS ----------------------------
methods:
- def_name: __str__
# --------------------------------------
- class_name: CollisionEvent
2019-06-05 21:05:57 +08:00
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
2020-09-17 19:10:57 +08:00
var_units: N*s
doc: >
Normal impulse resulting of the collision.
- class_name: ObstacleDetectionEvent
2019-06-05 21:05:57 +08:00
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
2020-09-14 22:58:48 +08:00
var_units: meters
doc: >
Distance between `actor` and `other`.
# - METHODS ----------------------------
methods:
- def_name: __str__
# --------------------------------------
- class_name: LaneInvasionEvent
2019-06-05 21:05:57 +08:00
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
2019-06-05 21:05:57 +08:00
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
2020-09-14 22:58:48 +08:00
var_units: meters
doc: >
Height regarding ground level.
- var_name: latitude
type: float
2020-09-14 22:58:48 +08:00
var_units: degrees
doc: >
North/South value of a point on the map.
- var_name: longitude
type: float
2020-09-14 22:58:48 +08:00
var_units: degrees
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
var_units: m/s<sup>2</sup>
doc: >
2020-09-14 22:58:48 +08:00
Linear acceleration.
- var_name: compass
type: float
2020-09-14 22:58:48 +08:00
var_units: radians
doc: >
2020-09-14 22:58:48 +08:00
Orientation with regard to the North ([0.0, -1.0, 0.0] in Unreal Engine).
- var_name: gyroscope
type: carla.Vector3D
2020-09-14 22:58:48 +08:00
var_units: rad/s
doc: >
2020-09-14 22:58:48 +08:00
Angular velocity.
# - METHODS ----------------------------
methods:
- def_name: __str__
# --------------------------------------
2019-12-09 22:54:53 +08:00
- 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).
2019-12-09 22:54:53 +08:00
# - PROPERTIES -------------------------
instance_variables:
- var_name: raw_data
type: bytes
doc: >
The complete information of the carla.RadarDetection the radar has registered.
2019-12-09 22:54:53 +08:00
# - METHODS ----------------------------
methods:
- def_name: get_detection_count
doc: >
Retrieves the number of entries generated, same as **<font color="#7fb800">\__str__()</font>**.
2019-12-09 22:54:53 +08:00
# --------------------------------------
- def_name: __getitem__
params:
- param_name: pos
type: int
# --------------------------------------
- def_name: __iter__
2020-10-02 23:08:50 +08:00
doc: >
Iterate over the carla.RadarDetection retrieved as data.
# --------------------------------------
- def_name: __len__
# --------------------------------------
2019-12-09 22:54:53 +08:00
- 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.
2019-12-09 22:54:53 +08:00
# - PROPERTIES -------------------------
instance_variables:
- var_name: altitude
2019-12-09 22:54:53 +08:00
type: float
2020-09-14 22:58:48 +08:00
var_units: radians
2019-12-09 22:54:53 +08:00
doc: >
2020-09-14 22:58:48 +08:00
Altitude angle of the detection.
2019-12-09 22:54:53 +08:00
# --------------------------------------
- var_name: azimuth
type: float
2020-09-14 22:58:48 +08:00
var_units: radians
2019-12-09 22:54:53 +08:00
doc: >
2020-09-14 22:58:48 +08:00
Azimuth angle of the detection.
2019-12-09 22:54:53 +08:00
# --------------------------------------
- var_name: depth
2019-12-09 22:54:53 +08:00
type: float
2020-09-14 22:58:48 +08:00
var_units: meters
2019-12-09 22:54:53 +08:00
doc: >
2020-09-14 22:58:48 +08:00
Distance from the sensor to the detection position.
2019-12-09 22:54:53 +08:00
# --------------------------------------
- var_name: velocity
2019-12-09 22:54:53 +08:00
type: float
2020-09-14 22:58:48 +08:00
var_units: m/s
2019-12-09 22:54:53 +08:00
doc: >
2020-09-14 22:58:48 +08:00
The velocity of the detected object towards the sensor.
2019-12-09 22:54:53 +08:00
# - 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">ad.rss.state.ProperResponse</a>
doc: >
The proper response that the RSS calculated for the vehicle.
# --------------------------------------
- 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">ad.rss.state.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.
# --------------------------------------
- var_name: world_model
type: <a href="https://intel.github.io/ad-rss-lib/doxygen/ad_rss/structad_1_1rss_1_1world_1_1WorldModel.html">ad.rss.world.WorldModel</a>
doc: >
World model used for calculations.
# --------------------------------------
- var_name: situation_snapshot
type: <a href="https://intel.github.io/ad-rss-lib/doxygen/ad_rss/structad_1_1rss_1_1situation_1_1SituationSnapshot.html">ad.rss.situation.SituationSnapshot</a>
doc: >
Detailed RSS situations extracted from the world model.
# - 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:
## ** Missing timestamp and time_since_epoch_check_start_ms
- 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">ad.physics.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">ad.physics.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">ad.map.point.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">ad.map.point.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">ad.map.point.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">ad.map.point.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">ad.map.point.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">ad.physics.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">ad.physics.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">ad.physics.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">ad.physics.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">ad.physics.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">ad.physics.Acceleration</a>
doc: >
The ego acceleration component _lon_ regarding the route smoothened by an average filter.
# - METHODS ----------------------------
methods:
- def_name: __str__
# --------------------------------------
- class_name: RssActorConstellationData
# - DESCRIPTION ------------------------
doc: >
Data structure that is provided within the callback registered by RssSensor.register_actor_constellation_callback().
# - PROPERTIES -------------------------
instance_variables:
- var_name: ego_match_object
type: <a href="https://ad-map-access.readthedocs.io/en/latest/ad_map_access/apidoc/html/structad_1_1map_1_1match_1_1Object.html">ad.map.match.Object</a>
doc: >
The ego map matched information.
# --------------------------------------
- var_name: ego_route
type: <a href="https://ad-map-access.readthedocs.io/en/latest/ad_map_access/apidoc/html/structad_1_1map_1_1route_1_1FullRoute.html">ad.map.route.FullRoute</a>
doc: >
The ego route.
# --------------------------------------
- var_name: ego_dynamics_on_route
type: carla.RssEgoDynamicsOnRoute
doc: >
Current ego vehicle dynamics regarding the route.
# --------------------------------------
- var_name: other_match_object
type: <a href="https://ad-map-access.readthedocs.io/en/latest/ad_map_access/apidoc/html/structad_1_1map_1_1match_1_1Object.html">ad.map.match.Object</a>
doc: >
The other object's map matched information. This is only valid if 'other_actor' is not 'None'.
# --------------------------------------
- var_name: other_actor
type: carla.Actor
doc: >
The other actor. This is 'None' in case of query of default parameters or articial objects of kind <a href="https://intel.github.io/ad-rss-lib/doxygen/ad_rss/namespacead_1_1rss_1_1world.html#a6432f1ef8d0657b4f21ed5966aca1625">ad.rss.world.ObjectType.ArtificialObject</a>
with no dedicated 'carla.Actor' (as e.g. for the [road boundaries](ref_sensors.md#rss-sensor) at the moment)
# - METHODS ----------------------------
methods:
- def_name: __str__
# --------------------------------------
- class_name: RssActorConstellationResult
# - DESCRIPTION ------------------------
doc: >
Data structure that should be returned by the callback registered by RssSensor.register_actor_constellation_callback().
# - PROPERTIES -------------------------
instance_variables:
- var_name: rss_calculation_mode
type: <a href="https://intel.github.io/ad-rss-lib/doxygen/ad_rss_map_integration/namespacead_1_1rss_1_1map.html#adcb01232986ed83a0c540cd5d03ef495">ad.rss.map.RssMode</a>
doc: >
The calculation mode to be applied with the actor.
# --------------------------------------
- var_name: restrict_speed_limit_mode
type: <a href="https://intel.github.io/ad-rss-lib/doxygen/ad_rss_map_integration/classad_1_1rss_1_1map_1_1RssSceneCreation.html#a403aae6dce3c77a8aec01dd9808dd964">ad.rss.map.RestrictSpeedLimitMode</a>
doc: >
The mode for restricting speed limit.
# --------------------------------------
- var_name: ego_vehicle_dynamics
type: <a href="https://intel.github.io/ad-rss-lib/doxygen/ad_rss/structad_1_1rss_1_1world_1_1RssDynamics.html">ad.rss.world.RssDynamics</a>
doc: >
The RSS dynamics to be applied for the ego vehicle.
# --------------------------------------
- var_name: actor_object_type
type: <a href="https://intel.github.io/ad-rss-lib/doxygen/ad_rss/namespacead_1_1rss_1_1world.html#a6432f1ef8d0657b4f21ed5966aca1625">ad.rss.world.ObjectType</a>
doc: >
The RSS object type to be used for the actor.
# --------------------------------------
- var_name: actor_dynamics
type: <a href="https://intel.github.io/ad-rss-lib/doxygen/ad_rss/structad_1_1rss_1_1world_1_1RssDynamics.html">ad.rss.world.RssDynamics</a>
doc: >
The RSS dynamics to be applied for the actor.
# - METHODS ----------------------------
methods:
- def_name: __str__
# --------------------------------------
2020-05-08 22:57:44 +08:00
- class_name: DVSEvent
# - DESCRIPTION ------------------------
doc: >
Class that defines a DVS event. An event is a quadruple, so a tuple of 4 elements, with `x`, `y` pixel coordinate location, timestamp `t` and polarity `pol` of the event. Learn more about them [here](ref_sensors.md).
2020-05-08 22:57:44 +08:00
# - PROPERTIES -------------------------
instance_variables:
- var_name: x
type: int
doc: >
X pixel coordinate.
# --------------------------------------
- var_name: 'y'
type: int
doc: >
Y pixel coordinate.
# --------------------------------------
- var_name: t
type: int
doc: >
Timestamp of the moment the event happened.
2020-05-08 22:57:44 +08:00
# --------------------------------------
- var_name: pol
type: bool
doc: >
Polarity of the event. __True__ for positive and __False__ for negative.
# - METHODS ----------------------------
methods:
- def_name: __str__
# --------------------------------------
- class_name: DVSEventArray
# - DESCRIPTION ------------------------
doc: >
Class that defines a stream of events in carla.DVSEvent. Such stream is an array of arbitrary size depending on the number of events. This class also stores the field of view, the height and width of the image and the timestamp from convenience. Learn more about them [here](ref_sensors.md).
2020-05-08 22:57:44 +08:00
# - PROPERTIES -------------------------
instance_variables:
- var_name: fov
type: float
2020-09-14 22:58:48 +08:00
var_units: degrees
2020-05-08 22:57:44 +08:00
doc: >
2020-09-14 22:58:48 +08:00
Horizontal field of view of the image.
2020-05-08 22:57:44 +08:00
# --------------------------------------
- var_name: height
type: int
doc: >
Image height in pixels.
2020-05-08 22:57:44 +08:00
# --------------------------------------
- var_name: width
type: int
doc: >
Image width in pixels.
2020-05-08 22:57:44 +08:00
# --------------------------------------
- var_name: raw_data
type: bytes
# - METHODS ----------------------------
methods:
- def_name: to_image
doc: >
Converts the image following this pattern: blue indicates positive events, red indicates negative events.
# --------------------------------------
- def_name: to_array
doc: >
Converts the stream of events to an array of int values in the following order <code>[x, y, t, pol]</code>.
# --------------------------------------
- def_name: to_array_x
doc: >
Returns an array with X pixel coordinate of all the events in the stream.
# --------------------------------------
- def_name: to_array_y
doc: >
Returns an array with Y pixel coordinate of all the events in the stream.
# --------------------------------------
- def_name: to_array_t
doc: >
Returns an array with the timestamp of all the events in the stream.
# --------------------------------------
- def_name: to_array_pol
doc: >
Returns an array with the polarity of all the events in the stream.
# --------------------------------------
- def_name: __getitem__
params:
- param_name: pos
type: int
# --------------------------------------
- def_name: __iter__
2020-10-02 23:08:50 +08:00
doc: >
Iterate over the carla.DVSEvent retrieved as data.
2020-05-08 22:57:44 +08:00
# --------------------------------------
- def_name: __len__
# --------------------------------------
- def_name: __setitem__
params:
- param_name: pos
type: int
- param_name: color
type: carla.Color
# --------------------------------------
- def_name: __str__
# --------------------------------------
Merge GBuffer features. (#5960) * Add Misc/GBuffer * Add EnqueueRenderSceneImmediateWithGBuffer. * Modified ASceneCaptureSensor to allow gbuffer recording. * Minor GBuffer progress. * More GBuffer changes. * Removed unnecessary files. * Add FRHITexture* functions to FPixelReader + temporarily disabled non-gbuffer rendering in ASceneCaptureSensor. * Add missing FPixelReader functions. * Minor changes (Switching to Windows). * Remove FRHITexture functions from FPixelReader, added the file ImageUtil. * Remove FRHITexture functions from FPixelReader, added the file ImageUtil. (2) * Added API to listen GBuffer data. * Added gbuffer serializer classes * Temporarily remove ViewRect hack. * Add USceneCaptureComponent* derived classes. * Disable USceneCaptureComponent*_CARLA and add initial FRHIGPUTextureReadBack-based code. * Fix and re-enable custom SceneCaptureComponents. * Fully switch to FRHIGPUTextureReadback. * Remove unnecessary call to FlushRenderingCommands. * Minor API changes. * Add support for PF_DepthStencil in ImageUtil. * More API progress... * More API progress... (2) * Removed testing code. * Minor changes for testing. * GBuffer API fixes. * Improve GBuffer capture code. * Fixed SceneDepth transfer issues and added SceneStencil, CustomDepth and CustomStencil to the GBuffer capture. * Fix compilation error due to the usage of C++17 features. * Removed major memory leak and added manual_control_gbuffer.py. * Fixed a silly mistake. * Minor changes to manual_control_gbuffer and SceneCaptureSensor. * Fix compilation error on some versions of Ubuntu. * Disable TAA when reading GBuffers to avoid jitter. * Improve memory usage. * Progress towards automatically detecting when a GBuffer stream is unused. * Fix includes in SceneCaptureSensor + minor change in manual_control_gbuffer.py * Progress on automatically detecting which GBuffers aren't needed. * Remove unneeded __declspec. * Revert ASensor changes + fix tutorial_gbuffer.py * Update CHANGELOG.md * Apply requested changes for the PR, add gitignore for the file OptionalModules.ini and add a GBufferTextureID enum to the Python API. * Remove OptionalModules.ini. * Fix indentation. * Fix indentation (2). * Fix indentation (3). * Add documentation and more indentation fixes. * Remove commented includes. * Add missing line break. * Fix memory leak + remove unneeded files. * Add .uproject again, fix EngineAssociation. * Remove unneeded ENQUEUE_RENDER_COMMAND. * Fix manual_control_gbuffer.py. * Add `stop_gbuffer` to the Python API. * Minor fixes. * Fix performance bug. Previously, when a client requested a gbuffer that is unused it would stay open, even after stopping it explicitly. This commit fixes this issue. * Fix indentation. * Add missing braces, more indentation fixes and simplify some of the code. * Update sensor.yml docs. * Update docs. * Remove unnecessary UE_Log + changed one verbosity level. Co-authored-by: Axel <axellopez92@outlook.com> Co-authored-by: Axel1092 <35765780+Axel1092@users.noreply.github.com>
2022-11-29 18:24:26 +08:00
- class_name: GBufferTextureID
# - DESCRIPTION ------------------------
doc: >
Defines the identifiers of each GBuffer texture (See the method `carla.Sensor.listen_to_gbuffer`).
# - PROPERTIES -------------------------
instance_variables:
- var_name: SceneColor
doc: >
The texture "SceneColor" contains the final color of the image.
- var_name: SceneDepth
doc: >
The texture "SceneDepth" contains the depth buffer - linear in world units.
- var_name: SceneStencil
doc: >
The texture "SceneStencil" contains the stencil buffer.
- var_name: GBufferA
doc: >
The texture "GBufferA" contains the world-space normal vectors in the RGB channels. The alpha channel contains "per-object data".
- var_name: GBufferB
doc: >
The texture "GBufferB" contains the metallic, specular and roughness in the RGB channels, respectively. The alpha channel contains a mask where the lower 4 bits indicate the shading model and the upper 4 bits contain the selective output mask.
- var_name: GBufferC
doc: >
The texture "GBufferC" contains the diffuse color in the RGB channels, with the indirect irradiance in the alpha channel.<br>
If static lightning is not allowed, the alpha channel will contain the ambient occlusion instead.
- var_name: GBufferD
doc: >
The contents of the "GBufferD" varies depending on the rendered object's material shading model (GBufferB):<br>
- MSM_Subsurface (2), MSM_PreintegratedSkin (3), MSM_TwoSidedFoliage (6):<br>
RGB: Subsurface color.<br>
A: Opacity.<br>
- MSM_ClearCoat (4):<br>
R: Clear coat.<br>
G: Roughness.<br>
- MSM_SubsurfaceProfile (5):<br>
RGB: Subsurface profile.<br>
- MSM_Hair (7):<br>
RG: World normal.<br>
B: Backlit value.<br>
- MSM_Cloth (8):<br>
RGB: Subsurface color.<br>
A: Cloth value.<br>
- MSM_Eye (9):<br>
RG: Eye tangent.<br>
B: Iris mask.<br>
A: Iris distance.
- var_name: GBufferE
doc: >
The texture "GBufferE" contains the precomputed shadow factors in the RGBA channels. This texture is unavailable if the selective output mask (GBufferB) does not have its 4th bit set.
- var_name: GBufferF
doc: >
The texture "GBufferF" contains the world-space tangent in the RGB channels and the anisotropy in the alpha channel. This texture is unavailable if the selective output mask (GBufferB) does not have its 5th bit set.
- var_name: Velocity
doc: >
The texture "Velocity" contains the screen-space velocity of the scene objects.
- var_name: SSAO
doc: >
The texture "SSAO" contains the screen-space ambient occlusion texture.
- var_name: CustomDepth
doc: >
The texture "CustomDepth" contains the Unreal Engine custom depth data.
- var_name: CustomStencil
doc: >
The texture "CustomStencil" contains the Unreal Engine custom stencil data.
# --------------------------------------
2019-05-03 18:18:02 +08:00
...