diff --git a/Docs/python_api.md b/Docs/python_api.md
index 7f97c1486b7..f9d2332902e 100644
--- a/Docs/python_api.md
+++ b/Docs/python_api.md
@@ -1547,6 +1547,59 @@ If __True__, Pedestrian navigation will be enabled using Recast tool. For very l
---
+## carla.OpticalFlowImage
+Inherited from _[carla.SensorData](#carla.SensorData)_
+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.
+
+### Instance Variables
+- **fov** (_float – degrees_)
+Horizontal field of view of the image.
+- **height** (_int_)
+Image height in pixels.
+- **width** (_int_)
+Image width in pixels.
+- **raw_data** (_bytes_)
+
+### Methods
+
+##### Getters
+- **get_color_coded_flow**(**self**)
+Visualization helper. Converts the optical flow image to an RGB image.
+ - **Return:** _[carla.Image](#carla.Image)_
+
+##### Dunder methods
+- **\__getitem__**(**self**, **pos**=int)
+- **\__iter__**(**self**)
+Iterate over the [carla.OpticalFlowPixel](#carla.OpticalFlowPixel) that form the image.
+- **\__len__**(**self**)
+- **\__setitem__**(**self**, **pos**=int, **color**=[carla.Color](#carla.Color))
+- **\__str__**(**self**)
+
+---
+
+## carla.OpticalFlowPixel
+Class that defines a 2 dimensional vector representing an optical flow pixel.
+
+### Instance Variables
+- **x** (_float_)
+Optical flow in the x component.
+- **y** (_float_)
+Optical flow in the y component.
+
+### Methods
+- **\__init__**(**self**, **x**=0, **y**=0)
+Initializes the Optical Flow Pixel. Zero by default.
+ - **Parameters:**
+ - `x` (_float_)
+ - `y` (_float_)
+
+##### Dunder methods
+- **\__eq__**(**self**, **other**=[carla.OpticalFlowPixel](#carla.OpticalFlowPixel))
+- **\__ne__**(**self**, **other**=[carla.OpticalFlowPixel](#carla.OpticalFlowPixel))
+- **\__str__**(**self**)
+
+---
+
## carla.Osm2Odr
Class that converts an OpenStreetMap map to OpenDRIVE format, so that it can be loaded in CARLA. Find out more about this feature in the [docs](tuto_G_openstreetmap.md).
@@ -3664,28 +3717,8 @@ if vehicle_actor.is_at_traffic_light():
-
-
-
-
-Snippet for carla.Vehicle.set_wheel_steer_direction
-
-
-
-```py
-
-# Sets the appearance of the vehicles front wheels to 40°. Vehicle physics will not be affected.
-
-vehicle.set_wheel_steer_direction(carla.VehicleWheelLocation.FR_Wheel, 40.0)
-vehicle.set_wheel_steer_direction(carla.VehicleWheelLocation.FL_Wheel, 40.0)
-
-
-```
-
-
-
Snippet for carla.World.unload_map_layer
@@ -3788,6 +3821,25 @@ Snippet for carla.Client.__init__
+
+
+Snippet for carla.Vehicle.set_wheel_steer_direction
+
+
+
+```py
+
+# Sets the appearance of the vehicles front wheels to 40°. Vehicle physics will not be affected.
+
+vehicle.set_wheel_steer_direction(carla.VehicleWheelLocation.FR_Wheel, 40.0)
+vehicle.set_wheel_steer_direction(carla.VehicleWheelLocation.FL_Wheel, 40.0)
+
+
+```
+
+
+
+
Snippet for carla.Sensor.listen
diff --git a/PythonAPI/carla/source/libcarla/Blueprint.cpp b/PythonAPI/carla/source/libcarla/Blueprint.cpp
index 009834c7885..1d1ffeb879f 100644
--- a/PythonAPI/carla/source/libcarla/Blueprint.cpp
+++ b/PythonAPI/carla/source/libcarla/Blueprint.cpp
@@ -97,6 +97,16 @@ void export_blueprint() {
.def(self_ns::str(self_ns::self))
;
+ class_("OpticalFlowPixel")
+ .def(init(
+ (arg("x")=0, arg("y")=0)))
+ .def_readwrite("x", &csd::OpticalFlowPixel::x)
+ .def_readwrite("y", &csd::OpticalFlowPixel::y)
+ .def("__eq__", &csd::OpticalFlowPixel::operator==)
+ .def("__ne__", &csd::OpticalFlowPixel::operator!=)
+ .def(self_ns::str(self_ns::self))
+ ;
+
class_("ActorAttribute", no_init)
.add_property("id", CALL_RETURNING_COPY(cc::ActorAttribute, GetId))
.add_property("type", &cc::ActorAttribute::GetType)
diff --git a/PythonAPI/docs/blueprint.yml b/PythonAPI/docs/blueprint.yml
index 66022306dab..29bbd0e33d2 100644
--- a/PythonAPI/docs/blueprint.yml
+++ b/PythonAPI/docs/blueprint.yml
@@ -68,6 +68,46 @@
# --------------------------------------
- def_name: __str__
# --------------------------------------
+
+ - class_name: OpticalFlowPixel
+ # - DESCRIPTION ------------------------
+ doc: >
+ Class that defines a 2 dimensional vector representing an optical flow pixel.
+ # - PROPERTIES -------------------------
+ instance_variables:
+ - var_name: x
+ type: float
+ doc: >
+ Optical flow in the x component.
+ - var_name: y
+ type: float
+ doc: >
+ Optical flow in the y component.
+ # - METHODS ----------------------------
+ methods:
+ - def_name: __init__
+ params:
+ - param_name: x
+ type: float
+ default: 0
+ - param_name: y
+ type: float
+ default: 0
+ doc: >
+ Initializes the Optical Flow Pixel. Zero by default.
+ # --------------------------------------
+ - def_name: __eq__
+ params:
+ - param_name: other
+ type: carla.OpticalFlowPixel
+ # --------------------------------------
+ - def_name: __ne__
+ params:
+ - param_name: other
+ type: carla.OpticalFlowPixel
+ # --------------------------------------
+ - def_name: __str__
+ # --------------------------------------
- class_name: ActorAttribute
# - DESCRIPTION ------------------------
diff --git a/PythonAPI/docs/sensor_data.yml b/PythonAPI/docs/sensor_data.yml
index 6a668b685bf..927a03954f1 100644
--- a/PythonAPI/docs/sensor_data.yml
+++ b/PythonAPI/docs/sensor_data.yml
@@ -150,6 +150,56 @@
- 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 ------------------------
@@ -209,6 +259,7 @@
- def_name: __str__
# --------------------------------------
+
- class_name: LidarDetection
# - DESCRIPTION ------------------------
doc: >