---
- 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 sensor: carla.GnssMeasurement.
- IMU sensor: carla.IMUMeasurement.
- Lane invasion detector: carla.LaneInvasionEvent.
- LIDAR sensor: carla.LidarMeasurement.
- Obstacle detector: carla.ObstacleDetectionEvent.
- Radar sensor: carla.RadarMeasurement.
- RSS sensor: carla.RssResponse.
- Semantic LIDAR sensor: carla.SemanticLidarMeasurement.
# - PROPERTIES -------------------------
instance_variables:
- var_name: frame
type: int
doc: >
Frame count when the data was generated.
- var_name: timestamp
type: float
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 float 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 sensor.camera.semantic_segmentation.
# - PROPERTIES -------------------------
instance_variables:
- var_name: CityScapesPalette
doc: >
Converts the image to a segmentated map using tags provided by the blueprint library. Used by the [semantic segmentation camera](ref_sensors.md#semantic-segmentation-camera).
- var_name: Depth
doc: >
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: >
No changes applied to the image. Used by the [RGB camera](ref_sensors.md#rgb-camera).
- class_name: CityObjectLabel
# - DESCRIPTION ------------------------
doc: >
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.
# - 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
- 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
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
# - 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 Raw will make no changes.
doc: >
Saves the image to disk using a converter pattern stated as `color_converter`. The default conversion pattern is Raw that will make no changes to the image.
# --------------------------------------
- def_name: __getitem__
params:
- param_name: pos
type: int
# --------------------------------------
- def_name: __iter__
doc: >
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
# - 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
parent: carla.SensorData
# - DESCRIPTION ------------------------
doc: >
Class that defines the LIDAR data retrieved by a sensor.lidar.ray_cast. 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
var_units: radians
doc: >
Horizontal angle the LIDAR is rotated at the time of the measurement.
# --------------------------------------
- var_name: raw_data
type: bytes
doc: >
Received list of 4D points. Each point consists of [x,y,z] coordiantes plus the intensity computed for that point.
# - METHODS ----------------------------
methods:
- def_name: save_to_disk
params:
- param_name: path
type: str
doc: >
Saves the point cloud to disk as a .ply 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__
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 asociated intensity.
# - PROPERTIES -------------------------
instance_variables:
- var_name: point
type: carla.Location
var_units: meters
doc: >
Point in xyz coordinates.
# --------------------------------------
- var_name: intensity
type: float
doc: >
Computed intensity for this point as a scalar value between [0.0 , 1.0].
# - METHODS ----------------------------
methods:
- def_name: __str__
# --------------------------------------
- class_name: SemanticLidarMeasurement
parent: carla.SensorData
# - DESCRIPTION ------------------------
doc: >
Class that defines the semantic LIDAR data retrieved by a sensor.lidar.ray_cast_semantic. This essentially simulates a rotating LIDAR using ray-casting. Learn more about this [here](ref_sensors.md#semanticlidar-raycast-sensor).
# - PROPERTIES -------------------------
instance_variables:
- var_name: channels
type: int
doc: >
Number of lasers shot.
# --------------------------------------
- var_name: horizontal_angle
type: float
var_units: radians
doc: >
Horizontal angle the LIDAR is rotated at the time of the measurement.
# --------------------------------------
- var_name: raw_data
type: bytes
doc: >
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.
# - METHODS ----------------------------
methods:
- def_name: save_to_disk
params:
- param_name: path
type: str
doc: >
Saves the point cloud to disk as a .ply 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__
doc: >
Iterate over the carla.SemanticLidarDetection retrieved as data.
# --------------------------------------
- def_name: __len__
# --------------------------------------
- def_name: __setitem__
params:
- param_name: pos
type: int
- param_name: detection
type: carla.SemanticLidarDetection
# --------------------------------------
- def_name: __str__
# --------------------------------------
- class_name: SemanticLidarDetection
# - DESCRIPTION ------------------------
doc: >
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.
# - PROPERTIES -------------------------
instance_variables:
- var_name: point
type: carla.Location
var_units: meters
doc: >
[x,y,z] coordinates of the point.
# --------------------------------------
- var_name: cos_inc_angle
type: float
doc: >
Cosine of the incident angle between the ray, and the normal of the hit object.
# --------------------------------------
- var_name: object_idx
type: uint
doc: >
ID of the actor hit by the ray.
# --------------------------------------
- var_name: object_tag
type: uint
doc: >
[Semantic tag](https://carla.readthedocs.io/en/latest/ref_sensors/#semantic-segmentation-camera) of the component hit by the ray.
# - METHODS ----------------------------
methods:
- def_name: __str__
# --------------------------------------
- class_name: CollisionEvent
parent: carla.SensorData
# - DESCRIPTION ------------------------
doc: >
Class that defines a collision data for sensor.other.collision. 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
var_units: N*s
doc: >
Normal impulse resulting of the collision.
- class_name: ObstacleDetectionEvent
parent: carla.SensorData
# - DESCRIPTION ------------------------
doc: >
Class that defines the obstacle data for sensor.other.obstacle. 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
var_units: meters
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 sensor.other.lane_invasion. 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 sensor.other.gnss. It essentially reports its position with the position of the sensor and an OpenDRIVE geo-reference.
# - PROPERTIES -------------------------
instance_variables:
- var_name: altitude
type: float
var_units: meters
doc: >
Height regarding ground level.
- var_name: latitude
type: float
var_units: degrees
doc: >
North/South value of a point on the map.
- var_name: longitude
type: float
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 sensor.other.imu, 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/s2
doc: >
Linear acceleration.
- var_name: compass
type: float
var_units: radians
doc: >
Orientation with regard to the North ([0.0, -1.0, 0.0] in Unreal Engine).
- var_name: gyroscope
type: carla.Vector3D
var_units: rad/s
doc: >
Angular velocity.
# - METHODS ----------------------------
methods:
- def_name: __str__
# --------------------------------------
- class_name: RadarMeasurement
parent: carla.SensorData
# - DESCRIPTION ------------------------
doc: >
Class that defines and gathers the measures registered by a sensor.other.radar, 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 **\__str__()**.
# --------------------------------------
- def_name: __getitem__
params:
- param_name: pos
type: int
# --------------------------------------
- def_name: __iter__
doc: >
Iterate over the carla.RadarDetection retrieved as data.
# --------------------------------------
- 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 sensor.other.radar registers and contains the distance, angle and velocity in relation to the radar.
# - PROPERTIES -------------------------
instance_variables:
- var_name: altitude
type: float
var_units: radians
doc: >
Altitude angle of the detection.
# --------------------------------------
- var_name: azimuth
type: float
var_units: radians
doc: >
Azimuth angle of the detection.
# --------------------------------------
- var_name: depth
type: float
var_units: meters
doc: >
Distance from the sensor to the detection position.
# --------------------------------------
- var_name: velocity
type: float
var_units: m/s
doc: >
The velocity of the detected object towards the sensor.
# - 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: ad.rss.state.ProperResponse
doc: >
The proper response that the RSS calculated for the vehicle.
# --------------------------------------
- var_name: rss_state_snapshot
type: ad.rss.state.RssStateSnapshot
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: ad.rss.world.WorldModel
doc: >
World model used for calculations.
# --------------------------------------
- var_name: situation_snapshot
type: ad.rss.situation.SituationSnapshot
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:
- var_name: ego_speed
type: ad.physics.Speed
doc: >
The ego vehicle's speed.
# --------------------------------------
- var_name: min_stopping_distance
type: ad.physics.Distance
doc: >
The current minimum stopping distance.
# --------------------------------------
- var_name: ego_center
type: ad.map.point.ENUPoint
doc: >
The considered enu position of the ego vehicle.
# --------------------------------------
- var_name: ego_heading
type: ad.map.point.ENUHeading
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: ad.map.point.ENUHeading
doc: >
The considered heading of the route.
# --------------------------------------
- var_name: route_nominal_center
type: ad.map.point.ENUPoint
doc: >
The considered nominal center of the current route.
# --------------------------------------
- var_name: heading_diff
type: ad.map.point.ENUHeading
doc: >
The considered heading diff towards the route.
# --------------------------------------
- var_name: route_speed_lat
type: ad.physics.Speed
doc: >
The ego vehicle's speed component _lat_ regarding the route.
# --------------------------------------
- var_name: route_speed_lon
type: ad.physics.Speed
doc: >
The ego vehicle's speed component _lon_ regarding the route.
# --------------------------------------
- var_name: route_accel_lat
type: ad.physics.Acceleration
doc: >
The ego vehicle's acceleration component _lat_ regarding the route.
# --------------------------------------
- var_name: route_accel_lon
type: ad.physics.Acceleration
doc: >
The ego vehicle's acceleration component _lon_ regarding the route.
# --------------------------------------
- var_name: avg_route_accel_lat
type: ad.physics.Acceleration
doc: >
The ego vehicle's acceleration component _lat_ regarding the route smoothened by an average filter.
# --------------------------------------
- var_name: avg_route_accel_lon
type: ad.physics.Acceleration
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: ad.map.match.Object
doc: >
The ego map matched information.
# --------------------------------------
- var_name: ego_route
type: ad.map.route.FullRoute
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: ad.map.match.Object
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 ad.rss.world.ObjectType.ArtificialObject
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: ad.rss.map.RssMode
doc: >
The calculation mode to be applied with the actor.
# --------------------------------------
- var_name: restrict_speed_limit_mode
type: ad.rss.map.RestrictSpeedLimitMode
doc: >
The mode for restricting speed limit.
# --------------------------------------
- var_name: ego_vehicle_dynamics
type: ad.rss.world.RssDynamics
doc: >
The RSS dynamics to be applied for the ego vehicle.
# --------------------------------------
- var_name: actor_object_type
type: ad.rss.world.ObjectType
doc: >
The RSS object type to be used for the actor.
# --------------------------------------
- var_name: actor_dynamics
type: ad.rss.world.RssDynamics
doc: >
The RSS dynamics to be applied for the actor.
# - METHODS ----------------------------
methods:
- def_name: __str__
# --------------------------------------
- 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).
# - 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.
# --------------------------------------
- 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).
# - 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
# - 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 [x, y, t, pol]
.
# --------------------------------------
- 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__
doc: >
Iterate over the carla.DVSEvent retrieved as data.
# --------------------------------------
- def_name: __len__
# --------------------------------------
- def_name: __setitem__
params:
- param_name: pos
type: int
- param_name: color
type: carla.Color
# --------------------------------------
- def_name: __str__
# --------------------------------------
...