diff --git a/Docs/python_api.md b/Docs/python_api.md
index df14b688a..ffe1144e1 100644
--- a/Docs/python_api.md
+++ b/Docs/python_api.md
@@ -504,6 +504,61 @@ No changes applied to the image.
---
+## carla.DVSEvent
+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).
+
+
Instance Variables
+- **x** (_int_)
+X pixel coordinate.
+- **y** (_int_)
+Y pixel coordinate.
+- **t** (_int_)
+Timestamp of the moment the event happened.
+- **pol** (_bool_)
+Polarity of the event. __True__ for positive and __False__ for negative.
+
+Methods
+
+Dunder methods
+- **\__str__**(**self**)
+
+---
+
+## carla.DVSEventArray
+Class that defines a stream of events in [[carla.DVSEvent](#carla.DVSEvent)](#[carla.DVSEvent](#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).
+
+Instance Variables
+- **fov** (_float_)
+Horizontal field of view of the image in degrees.
+- **height** (_int_)
+Image height in pixels.
+- **width** (_int_)
+Image width in pixels.
+- **raw_data** (_bytes_)
+
+Methods
+- **to_image**(**self**)
+Converts the image following this pattern: blue indicates positive events, red indicates negative events.
+- **to_array**(**self**)
+Converts the stream of events to an array of int values in the following order [x, y, t, pol]
.
+- **to_array_x**(**self**)
+Returns an array with X pixel coordinate of all the events in the stream.
+- **to_array_y**(**self**)
+Returns an array with Y pixel coordinate of all the events in the stream.
+- **to_array_t**(**self**)
+Returns an array with the timestamp of all the events in the stream.
+- **to_array_pol**(**self**)
+Returns an array with the polarity of all the events in the stream.
+
+Dunder methods
+- **\__getitem__**(**self**, **pos**=int)
+- **\__iter__**(**self**)
+- **\__len__**(**self**)
+- **\__setitem__**(**self**, **pos**=int, **color**=[carla.Color](#carla.Color))
+- **\__str__**(**self**)
+
+---
+
## carla.DebugHelper
Helper class part of [carla.World](#carla.World) that defines methods for creating debug shapes. By default, shapes last one second. They can be permanent, but take into account the resources needed to do so. Check out this [recipe](ref_code_recipes.md#debug-bounding-box-recipe) where the user takes a snapshot of the world and then proceeds to draw bounding boxes for traffic lights.
@@ -2769,58 +2824,4 @@ Links another command to be executed right after. It allows to ease very common
- **Parameters:**
- `command` (_any carla Command_) – a Carla command.
-
----
-
-## carla.DVSEvent
-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 of the event. Learn more about them [here](ref_sensors.md).
-
-Instance Variables
-- **x** (_int_)
-X pixel coordinate.
-- **y** (_int_)
-Y pixel coordinate.
-- **t** (_int_)
-Timestamp.
-- **pol** (_bool_)
-Polarity of the event in boolean. True for positive and False for negative.
-
-Dunder methods
-- **\__str__**(**self**)
-
----
-
-## carla.DVSEventArray
-Class that defines a stream of events in [carla.DVSEvent](#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).
-
-Instance Variables
-- **fov** (_float_)
-Horizontal field of view of the image in degrees.
-- **height** (_int_)
-Image height in pixels.
-- **width** (_int_)
-Image width in pixels.
-- **raw_data** (_bytes_)
-
-Methods
-- **to_image**(**self**)
-Converts the image following this pattern: blue indicates positive events, red indicates negative events.
-- **to_array**(**self**)
-Convert the stream of events to an array of integer values in the following order [x, y, t, pol].
-- **to_array_x**(**self**)
-Return an array with X pixel coordinate of all the events in the stream.
-- **to_array_y**(**self**)
-Return an array with Y pixel coordinate of all the events in the stream.
-- **to_array_t**(**self**)
-Return an array with the timestamp of all the events in the stream.
-- **to_array_pol**(**self**)
-Return an array with the polarity of all the events in the stream.
-
-Dunder methods
-- **\__getitem__**(**self**, **pos**=int)
-- **\__iter__**(**self**)
-- **\__len__**(**self**)
-- **\__setitem__**(**self**, **pos**=int, **color**=[carla.Color](#carla.Color))
-- **\__str__**(**self**)
-
---
\ No newline at end of file
diff --git a/Docs/ref_sensors.md b/Docs/ref_sensors.md
index a9f6c7bff..73cb297de 100644
--- a/Docs/ref_sensors.md
+++ b/Docs/ref_sensors.md
@@ -1419,59 +1419,39 @@ The following tags are currently available:
* __Output:__ [carla.DVSEventArray](python_api.md#carla.DVSEventArray) per step (unless `sensor_tick` says otherwise).
-A Dynamic Vision Sensor (DVS) or Event camera is a sensor that works
-radically differently from a conventional camera. Instead of capturing
-intensity images at a fixed rate, event cameras measure changes of intensity
-asynchronously, in the form of a stream of events, which encode per-pixel
-brightness changes. Event cameras possess outstanding properties when
-compared to standard cameras. They have a very high dynamic range (140 dB
-versus 60 dB), no motion blur, and high temporal resolution (in the order of
-microseconds). Event cameras are thus sensors that can provide high-quality
-visual information even in challenging high-speed scenarios and high dynamic
-range environments, enabling new application domains for vision-based
+A Dynamic Vision Sensor (DVS) or Event camera is a sensor that works radically differently from a conventional camera. Instead of capturing
+intensity images at a fixed rate, event cameras measure changes of intensity asynchronously, in the form of a stream of events, which encode per-pixel
+brightness changes. Event cameras possess outstanding properties when compared to standard cameras. They have a very high dynamic range (140 dB
+versus 60 dB), no motion blur, and high temporal resolution (in the order of microseconds). Event cameras are thus sensors that can provide high-quality
+visual information even in challenging high-speed scenarios and high dynamic range environments, enabling new application domains for vision-based
algorithms.
-The DVS camera outputs a stream of events. An event $e=(x,y,t,pol)$ is
-triggered at a pixel $x$, $y$ at a timestamp $t$ when the change in
-logarithmic intensity $L$ reaches a predefined constant threshold $C$
-(typically between 15% and 30%),
+The DVS camera outputs a stream of events. An event `e=(x,y,t,pol)` is triggered at a pixel `x`, `y` at a timestamp `t` when the change in
+logarithmic intensity `L` reaches a predefined constant threshold `C` (typically between 15% and 30%).
-$$
+``
L(x,y,t) - L(x,y,t-\delta t) = pol C
-$$
+``
-where $t-\delta t$ is the time when the last event at that pixel was
-triggered and $pol$ is the polarity of the event according to the sign of the
-brightness change. The polarity is positive $+1$ when there is increment in
-brightness and negative $-1$ when a decrement in brightness occurs. The
-working principles depicted in the following figure. The standard
-camera outputs frames at a fixed rate, thus sending redundant information
-when no motion is present in the scene. In contrast, event cameras are
-data-driven sensors that respond to brightness changes with microsecond
-latency. At the plot, a positive (resp. negative) event (blue dot, resp. red
-dot) is generated whenever the (signed) brightness change exceeds the
-contrast threshold $C$ for one dimension $x$ over time $t$. Observe how the
-event rate grows when the signal changes rapidly.
+`t-\delta t` is the time when the last event at that pixel was triggered and `pol` is the polarity of the event according to the sign of the
+brightness change. The polarity is positive `+1` when there is increment in brightness and negative `-1` when a decrement in brightness occurs. The
+working principles depicted in the following figure. The standard camera outputs frames at a fixed rate, thus sending redundant information
+when no motion is present in the scene. In contrast, event cameras are data-driven sensors that respond to brightness changes with microsecond
+latency. At the plot, a positive (resp. negative) event (blue dot, resp. red dot) is generated whenever the (signed) brightness change exceeds the
+contrast threshold `C` for one dimension `x` over time `t`. Observe how the event rate grows when the signal changes rapidly.
![DVSCameraWorkingPrinciple](img/sensor_dvs_scheme.jpg)
-The current implementation of the DVS camera works in a uniform sampling
-manner between two consecutive synchronous frames. Therefore, in order to
-emulate the high temporal resolution (order of microseconds) of a real event
-camera, the sensor requires to execute at a high frequency (much higher
-frequency than a conventional camera). Effectively, the number of events
-increases as faster a Carla car drives. Therefore, the sensor frequency
-should increase accordingly with the dynamic of the scene. The user should find
-their balance between time accuracy and computational cost.
+The current implementation of the DVS camera works in a uniform sampling manner between two consecutive synchronous frames. Therefore, in order to
+emulate the high temporal resolution (order of microseconds) of a real event camera, the sensor requires to execute at a high frequency (much higher
+frequency than a conventional camera). Effectively, the number of events increases as faster a CARLA car drives. Therefore, the sensor frequency
+should increase accordingly with the dynamic of the scene. The user should find their balance between time accuracy and computational cost.
-The provided script `manual_control.py` uses the DVS camera in order to show
-how to configure the sensor, how to get the stream of events and how to depict such
-events in an image format, usually called event frame.
+The provided script `manual_control.py` uses the DVS camera in order to show how to configure the sensor, how to get the stream of events and how to depict such events in an image format, usually called event frame.
![DVSCameraWorkingPrinciple](img/sensor_dvs.gif)
-DVS is a camera and therefore has all the attributes available in the RGB camera. Nevertheless, there are few attributes
-exclusive to the working principle of an Event camera.
+DVS is a camera and therefore has all the attributes available in the RGB camera. Nevertheless, there are few attributes exclusive to the working principle of an Event camera.
#### DVS camera attributes
@@ -1497,12 +1477,12 @@ exclusive to the working principle of an Event camera.
sigma_positive_threshold |
float |
0 |
-White noise standard deviation for positive events (0-1) |
+White noise standard deviation for positive events (0-1). |
sigma_negative_threshold |
float |
0 |
-White noise standard deviation for negative events (0-1) |
+White noise standard deviation for negative events (0-1). |
refractory_period_ns |
int |
@@ -1517,7 +1497,7 @@ exclusive to the working principle of an Event camera.
log_eps |
float |
0.001 |
-Epsilon value used to convert images to log: L = log(eps + I / 255.0). Where I is the grayscale value of the RGB image I = 0.2989*R + 0.5870*G + 0.1140*B. |
+Epsilon value used to convert images to log: L = log(eps + I / 255.0) . Where I is the grayscale value of the RGB image:
I = 0.2989*R + 0.5870*G + 0.1140*B . |
diff --git a/PythonAPI/docs/sensor_data.yml b/PythonAPI/docs/sensor_data.yml
index 71ae80f4f..a4e87f0f2 100644
--- a/PythonAPI/docs/sensor_data.yml
+++ b/PythonAPI/docs/sensor_data.yml
@@ -469,4 +469,101 @@
- 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](#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
+ 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: 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__
+ # --------------------------------------
+ - def_name: __len__
+ # --------------------------------------
+ - def_name: __setitem__
+ params:
+ - param_name: pos
+ type: int
+ - param_name: color
+ type: carla.Color
+ # --------------------------------------
+ - def_name: __str__
+ # --------------------------------------
...