Updated optical flow documentation. Added OpticalFlowPixel class.
This commit is contained in:
parent
0948b4a451
commit
d93aaf7624
|
@ -1547,6 +1547,59 @@ If __True__, Pedestrian navigation will be enabled using Recast tool. For very l
|
|||
|
||||
---
|
||||
|
||||
## carla.OpticalFlowImage<a name="carla.OpticalFlowImage"></a>
|
||||
<small style="display:block;margin-top:-20px;">Inherited from _[carla.SensorData](#carla.SensorData)_</small></br>
|
||||
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
|
||||
- <a name="carla.OpticalFlowImage.fov"></a>**<font color="#f8805a">fov</font>** (_float<small> – degrees</small>_)
|
||||
Horizontal field of view of the image.
|
||||
- <a name="carla.OpticalFlowImage.height"></a>**<font color="#f8805a">height</font>** (_int_)
|
||||
Image height in pixels.
|
||||
- <a name="carla.OpticalFlowImage.width"></a>**<font color="#f8805a">width</font>** (_int_)
|
||||
Image width in pixels.
|
||||
- <a name="carla.OpticalFlowImage.raw_data"></a>**<font color="#f8805a">raw_data</font>** (_bytes_)
|
||||
|
||||
### Methods
|
||||
|
||||
##### Getters
|
||||
- <a name="carla.OpticalFlowImage.get_color_coded_flow"></a>**<font color="#7fb800">get_color_coded_flow</font>**(<font color="#00a6ed">**self**</font>)
|
||||
Visualization helper. Converts the optical flow image to an RGB image.
|
||||
- **Return:** _[carla.Image](#carla.Image)_
|
||||
|
||||
##### Dunder methods
|
||||
- <a name="carla.OpticalFlowImage.__getitem__"></a>**<font color="#7fb800">\__getitem__</font>**(<font color="#00a6ed">**self**</font>, <font color="#00a6ed">**pos**=int</font>)
|
||||
- <a name="carla.OpticalFlowImage.__iter__"></a>**<font color="#7fb800">\__iter__</font>**(<font color="#00a6ed">**self**</font>)
|
||||
Iterate over the [carla.OpticalFlowPixel](#carla.OpticalFlowPixel) that form the image.
|
||||
- <a name="carla.OpticalFlowImage.__len__"></a>**<font color="#7fb800">\__len__</font>**(<font color="#00a6ed">**self**</font>)
|
||||
- <a name="carla.OpticalFlowImage.__setitem__"></a>**<font color="#7fb800">\__setitem__</font>**(<font color="#00a6ed">**self**</font>, <font color="#00a6ed">**pos**=int</font>, <font color="#00a6ed">**color**=[carla.Color](#carla.Color)</font>)
|
||||
- <a name="carla.OpticalFlowImage.__str__"></a>**<font color="#7fb800">\__str__</font>**(<font color="#00a6ed">**self**</font>)
|
||||
|
||||
---
|
||||
|
||||
## carla.OpticalFlowPixel<a name="carla.OpticalFlowPixel"></a>
|
||||
Class that defines a 2 dimensional vector representing an optical flow pixel.
|
||||
|
||||
### Instance Variables
|
||||
- <a name="carla.OpticalFlowPixel.x"></a>**<font color="#f8805a">x</font>** (_float_)
|
||||
Optical flow in the x component.
|
||||
- <a name="carla.OpticalFlowPixel.y"></a>**<font color="#f8805a">y</font>** (_float_)
|
||||
Optical flow in the y component.
|
||||
|
||||
### Methods
|
||||
- <a name="carla.OpticalFlowPixel.__init__"></a>**<font color="#7fb800">\__init__</font>**(<font color="#00a6ed">**self**</font>, <font color="#00a6ed">**x**=0</font>, <font color="#00a6ed">**y**=0</font>)
|
||||
Initializes the Optical Flow Pixel. Zero by default.
|
||||
- **Parameters:**
|
||||
- `x` (_float_)
|
||||
- `y` (_float_)
|
||||
|
||||
##### Dunder methods
|
||||
- <a name="carla.OpticalFlowPixel.__eq__"></a>**<font color="#7fb800">\__eq__</font>**(<font color="#00a6ed">**self**</font>, <font color="#00a6ed">**other**=[carla.OpticalFlowPixel](#carla.OpticalFlowPixel)</font>)
|
||||
- <a name="carla.OpticalFlowPixel.__ne__"></a>**<font color="#7fb800">\__ne__</font>**(<font color="#00a6ed">**self**</font>, <font color="#00a6ed">**other**=[carla.OpticalFlowPixel](#carla.OpticalFlowPixel)</font>)
|
||||
- <a name="carla.OpticalFlowPixel.__str__"></a>**<font color="#7fb800">\__str__</font>**(<font color="#00a6ed">**self**</font>)
|
||||
|
||||
---
|
||||
|
||||
## carla.Osm2Odr<a name="carla.Osm2Odr"></a>
|
||||
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).
|
||||
|
||||
|
@ -3665,27 +3718,7 @@ if vehicle_actor.is_at_traffic_light():
|
|||
<img src="/img/snipets_images/carla.TrafficLight.set_state.gif">
|
||||
|
||||
</div>
|
||||
|
||||
<div id ="carla.Vehicle.set_wheel_steer_direction-snipet" style="display: none;">
|
||||
<p class="SnipetFont">
|
||||
Snippet for carla.Vehicle.set_wheel_steer_direction
|
||||
</p>
|
||||
<div id="carla.Vehicle.set_wheel_steer_direction-code" class="SnipetContent">
|
||||
|
||||
```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)
|
||||
|
||||
|
||||
```
|
||||
<button id="button1" class="CopyScript" onclick="CopyToClipboard('carla.Vehicle.set_wheel_steer_direction-code')">Copy snippet</button> <button id="button1" class="CloseSnipet" onclick="CloseSnipet()">Close snippet</button><br><br>
|
||||
|
||||
</div>
|
||||
|
||||
<div id ="carla.DebugHelper.draw_string-snipet" style="display: none;">
|
||||
<div id ="carla.World.unload_map_layer-snipet" style="display: none;">
|
||||
<p class="SnipetFont">
|
||||
Snippet for carla.World.unload_map_layer
|
||||
|
@ -3788,6 +3821,25 @@ Snippet for carla.Client.__init__
|
|||
|
||||
</div>
|
||||
|
||||
<div id ="carla.Vehicle.set_wheel_steer_direction-snipet" style="display: none;">
|
||||
<p class="SnipetFont">
|
||||
Snippet for carla.Vehicle.set_wheel_steer_direction
|
||||
</p>
|
||||
<div id="carla.Vehicle.set_wheel_steer_direction-code" class="SnipetContent">
|
||||
|
||||
```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)
|
||||
|
||||
|
||||
```
|
||||
<button id="button1" class="CopyScript" onclick="CopyToClipboard('carla.Vehicle.set_wheel_steer_direction-code')">Copy snippet</button> <button id="button1" class="CloseSnipet" onclick="CloseSnipet()">Close snippet</button><br><br>
|
||||
|
||||
</div>
|
||||
|
||||
<div id ="carla.Sensor.listen-snipet" style="display: none;">
|
||||
<p class="SnipetFont">
|
||||
Snippet for carla.Sensor.listen
|
||||
|
|
|
@ -97,6 +97,16 @@ void export_blueprint() {
|
|||
.def(self_ns::str(self_ns::self))
|
||||
;
|
||||
|
||||
class_<csd::OpticalFlowPixel>("OpticalFlowPixel")
|
||||
.def(init<float, float>(
|
||||
(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_<cc::ActorAttribute>("ActorAttribute", no_init)
|
||||
.add_property("id", CALL_RETURNING_COPY(cc::ActorAttribute, GetId))
|
||||
.add_property("type", &cc::ActorAttribute::GetType)
|
||||
|
|
|
@ -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 ------------------------
|
||||
|
|
|
@ -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: >
|
||||
|
|
Loading…
Reference in New Issue