diff --git a/Docs/python_api.md b/Docs/python_api.md
index 832e3d3f4..50376b0f1 100644
--- a/Docs/python_api.md
+++ b/Docs/python_api.md
@@ -308,14 +308,16 @@ Parses the identifiers for every blueprint to string.
---
## carla.BoundingBox
-Helper class defining a box location and its dimensions that will later be used by [carla.DebugHelper](#carla.DebugHelper) or a [carla.Client](#carla.Client) to draw shapes and detect collisions. Bounding boxes normally act for object colliders. 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.
+Bounding boxes contain the geometry of an actor or an element in the scene. They can be used by [carla.DebugHelper](#carla.DebugHelper) or a [carla.Client](#carla.Client) to draw their shapes for debugging. 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.
Instance Variables
- **extent** (_[carla.Vector3D](#carla.Vector3D) – meters_)
Vector from the center of the box to one vertex. The value in each axis equals half the size of the box for that axis.
`extent.x * 2` would return the size of the box in the X-axis.
- **location** (_[carla.Location](#carla.Location) – meters_)
-The center of the bounding box relative to its parent actor.
+The center of the bounding box.
+- **rotation** (_[carla.Rotation](#carla.Rotation)_)
+The orientation of the bounding box.
Methods
- **\__init__**(**self**, **location**, **extent**)
@@ -352,6 +354,36 @@ Parses the location and extent of the bounding box to string.
---
+## carla.CityObjectLabel
+Enum declaration that contains the different tags available to filter the bounding boxes returned by [carla.World.get_level_bbs](#carla.World.get_level_bbs)(). These values correspond to the [semantic tag](https://[carla.readthedocs.io](#carla.readthedocs.io)/en/latest/ref_sensors/#semantic-segmentation-camera) that the elements in the scene have.
+
+Instance Variables
+- **None**
+- **Buildings**
+- **Fences**
+- **Other**
+- **Pedestrians**
+- **Poles**
+- **RoadLines**
+- **Roads**
+- **Sidewalks**
+- **TrafficSigns**
+- **Vegetation**
+- **Vehicles**
+- **Walls**
+- **Sky**
+- **Ground**
+- **Bridge**
+- **RailTrack**
+- **GuardRail**
+- **TrafficLight**
+- **Static**
+- **Dynamic**
+- **Water**
+- **Terrain**
+
+---
+
## carla.Client
The Client connects CARLA to the server which runs the simulation. Both server and client contain a CARLA library (libcarla) with some differences that allow communication between them. Many clients can be created and each of these will connect to the RPC server inside the simulation to send commands. The simulation runs server-side. Once the connection is established, the client will only receive data retrieved from the simulation. Walkers are the exception. The client is in charge of managing pedestrians so, if you are running a simulation with multiple clients, some issues may arise. For example, if you spawn walkers through different clients, collisions may happen, as each client is only aware of the ones it is in charge of.
@@ -2173,7 +2205,7 @@ Returns the axis values for the vector parsed as string.
Instance Variables
- **bounding_box** (_[carla.BoundingBox](#carla.BoundingBox)_)
-The vehicle's collider volume.
+Bounding box containing the geometry of the vehicle. Its location and rotation are relative to the vehicle it is attached to.
Methods
- **apply_control**(**self**, **control**)
@@ -2357,7 +2389,7 @@ VehiclePhysicsControl constructor.
Instance Variables
- **bounding_box** (_[carla.BoundingBox](#carla.BoundingBox)_)
-The walker's collider defined by a bounding box.
+Bounding box containing the geometry of the walker. Its location and rotation are relative to the walker it is attached to.
Methods
- **apply_control**(**self**, **control**)
@@ -2699,6 +2731,11 @@ Returns a list of actor blueprints available to ease the spawn of these into the
- **get_vehicles_light_states**(**self**)
Returns a dict where the keys are [carla.Actor](#carla.Actor) IDs and the values are [carla.VehicleLightState](#carla.VehicleLightState) of that vehicle.
- **Return:** _dict_
+- **get_level_bbs**(**self**, **actor_type**=None)
+Returns an array of bounding boxes with location and rotation in world space. The function returns all the bounding boxes in the level by default, but the result can be filtered using semantic tags with the argument `actor_type`.
+ - **Parameters:**
+ - `actor_type` (_[carla.CityObjectLabel](#carla.CityObjectLabel)_) – Semantic tag of the elements contained in the bounding boxes that are returned.
+ - **Return:** _array([carla.BoundingBox](#carla.BoundingBox))_
- **get_lightmanager**(**self**)
Returns an instance of [carla.LightManager](#carla.LightManager) that can be used to handle the lights in the scene.
- **Return:** _[carla.LightManager](#carla.LightManager)_
diff --git a/PythonAPI/docs/actor.yml b/PythonAPI/docs/actor.yml
index 21e9285f1..361b84ed6 100644
--- a/PythonAPI/docs/actor.yml
+++ b/PythonAPI/docs/actor.yml
@@ -220,7 +220,7 @@
- var_name: bounding_box
type: carla.BoundingBox
doc: >
- The vehicle's collider volume.
+ Bounding box containing the geometry of the vehicle. Its location and rotation are relative to the vehicle it is attached to.
# - METHODS ----------------------------
methods:
- def_name: apply_control
@@ -309,7 +309,7 @@
- var_name: bounding_box
type: carla.BoundingBox
doc: >
- The walker's collider defined by a bounding box.
+ Bounding box containing the geometry of the walker. Its location and rotation are relative to the walker it is attached to.
# - METHODS ----------------------------
methods:
- def_name: apply_control
diff --git a/PythonAPI/docs/geom.yml b/PythonAPI/docs/geom.yml
index 9ccc3f7da..29e92d9a9 100644
--- a/PythonAPI/docs/geom.yml
+++ b/PythonAPI/docs/geom.yml
@@ -383,7 +383,7 @@
- class_name: BoundingBox
# - DESCRIPTION ------------------------
doc: >
- Helper class defining a box location and its dimensions that will later be used by carla.DebugHelper or a carla.Client to draw shapes and detect collisions. Bounding boxes normally act for object colliders. 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.
+ Bounding boxes contain the geometry of an actor or an element in the scene. They can be used by carla.DebugHelper or a carla.Client to draw their shapes for debugging. 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.
# - PROPERTIES -------------------------
instance_variables:
- var_name: extent
@@ -397,7 +397,11 @@
type: carla.Location
var_units: meters
doc: >
- The center of the bounding box relative to its parent actor.
+ The center of the bounding box.
+ - var_name: rotation
+ type: carla.Rotation
+ doc: >
+ The orientation of the bounding box.
# - METHODS ----------------------------
methods:
- def_name: __init__
diff --git a/PythonAPI/docs/sensor_data.yml b/PythonAPI/docs/sensor_data.yml
index 4ea1c3e86..fc5166fcf 100644
--- a/PythonAPI/docs/sensor_data.yml
+++ b/PythonAPI/docs/sensor_data.yml
@@ -52,6 +52,37 @@
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](https://carla.readthedocs.io/en/latest/ref_sensors/#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
+
- class_name: Image
parent: carla.SensorData
# - DESCRIPTION ------------------------
diff --git a/PythonAPI/docs/world.yml b/PythonAPI/docs/world.yml
index 5cb3503fb..02f9a2b18 100644
--- a/PythonAPI/docs/world.yml
+++ b/PythonAPI/docs/world.yml
@@ -330,6 +330,17 @@
doc: >
Returns a dict where the keys are carla.Actor IDs and the values are carla.VehicleLightState of that vehicle.
# --------------------------------------
+ - def_name: get_level_bbs
+ params:
+ - param_name: actor_type
+ type: carla.CityObjectLabel
+ default: None
+ doc: >
+ Semantic tag of the elements contained in the bounding boxes that are returned.
+ return: array(carla.BoundingBox)
+ doc: >
+ Returns an array of bounding boxes with location and rotation in world space. The function returns all the bounding boxes in the level by default, but the result can be filtered using semantic tags with the argument `actor_type`.
+ # --------------------------------------
- def_name: get_lightmanager
return: carla.LightManager
doc: >