#Python API reference
This reference contains all the details the Python API. To consult a previous reference for a specific CARLA release, change the documentation version using the panel in the bottom right corner.
This will change the whole documentation to a previous state. Remember to go back to latest to get the details of the current state of CARLA.
child_location = Location(0,0,2)
).
---
## carla.BlueprintLibrary
A class that contains the blueprints provided for actor spawning. Its main application is to return [carla.ActorBlueprint](#carla.ActorBlueprint) objects needed to spawn actors. Each blueprint has an identifier and attributes that may or may not be modifiable. The library is automatically created by the server and can be accessed through [carla.World](#carla.World).
[Here](bp_library.md) is a reference containing every available blueprint and its specifics.
[x, y, t, pol]
.
- **to_array_pol**(**self**)
Returns an array with the polarity 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_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_image**(**self**)
Converts the image following this pattern: blue indicates positive events, red indicates negative events.
0
for permanent shapes.
- **draw_box**(**self**, **box**, **rotation**, **thickness**=0.1, **color**=(255,0,0), **life_time**=-1.0)
Draws a box, ussually to act for object colliders.
- **Parameters:**
- `box` (_[carla.BoundingBox](#carla.BoundingBox)_) – Object containing a location and the length of a box for every axis.
- `rotation` (_[carla.Rotation](#carla.Rotation) – degrees (pitch,yaw,roll)_) – Orientation of the box according to Unreal Engine's axis system.
- `thickness` (_float – meters_) – Density of the lines that define the box.
- `color` (_[carla.Color](#carla.Color)_) – RGB code to color the object. Red by default.
- `life_time` (_float – seconds_) – Shape's lifespan. By default it only lasts one frame. Set this to 0
for permanent shapes.
- **draw_line**(**self**, **begin**, **end**, **thickness**=0.1, **color**=(255,0,0), **life_time**=-1.0)
Draws a line in between `begin` and `end`.
- **Parameters:**
- `begin` (_[carla.Location](#carla.Location) – meters_) – Point in the coordinate system where the line starts.
- `end` (_[carla.Location](#carla.Location) – meters_) – Spot in the coordinate system where the line ends.
- `thickness` (_float – meters_) – Density of the line.
- `color` (_[carla.Color](#carla.Color)_) – RGB code to color the object. Red by default.
- `life_time` (_float – seconds_) – Shape's lifespan. By default it only lasts one frame. Set this to 0
for permanent shapes.
- **draw_point**(**self**, **location**, **size**=0.1, **color**=(255,0,0), **life_time**=-1.0)
Draws a point `location`.
- **Parameters:**
- `location` (_[carla.Location](#carla.Location) – meters_) – Spot in the coordinate system to center the object.
- `size` (_float – meters_) – Density of the point.
- `color` (_[carla.Color](#carla.Color)_) – RGB code to color the object. Red by default.
- `life_time` (_float – seconds_) – Shape's lifespan. By default it only lasts one frame. Set this to 0
for permanent shapes.
- **draw_string**(**self**, **location**, **text**, **draw_shadow**=False, **color**=(255,0,0), **life_time**=-1.0)
Draws a string in a given location of the simulation which can only be seen server-side.
- **Parameters:**
- `location` (_[carla.Location](#carla.Location) – meters_) – Spot in the simulation where the text will be centered.
- `text` (_str_) – Text intended to be shown in the world.
- `draw_shadow` (_bool_) – Casts a shadow for the string that could help in visualization. It is disabled by default.
- `color` (_[carla.Color](#carla.Color)_) – RGB code to color the string. Red by default.
- `life_time` (_float – seconds_) – Shape's lifespan. By default it only lasts one frame. Set this to 0
for permanent shapes.
---
## carla.GearPhysicsControl
Class that provides access to vehicle transmission details by defining a gear and when to run on it. This will be later used by [carla.VehiclePhysicsControl](#carla.VehiclePhysicsControl) to help simulate physics.
.osm
file (OpenStreetMap format) and returns the content of the .xodr
(OpenDRIVE format) describing said map. Some parameterization is passed to do the conversion.
- **Parameters:**
- `osm_file` (_str_) – The content of the input OpenStreetMap file parsed as string.
- `settings` (_[carla.OSM2ODRSettings](#carla.OSM2ODRSettings)_) – Parameterization for the conversion.
- **Return:** _str_
---
## carla.Osm2OdrSettings
Helper class that contains the parameterization that will be used by [carla.Osm2Odr](#carla.Osm2Odr) to convert an OpenStreetMap map to OpenDRIVE format. Find out more about this feature in the [docs](tuto_G_openstreetmap.md).
(pitch,yaw,roll)
, and in the Unreal Engine Editor (roll,pitch,yaw)
. When working in a build from source, don't mix up the axes' rotations._
10.0
by default.
- **Return:** _int_
- **Note:** _If no tick is received in synchronous mode, the simulation will freeze. Also, if many ticks are received from different clients, there may be synchronization issues. Please read the docs about [synchronous mode](https://[carla.readthedocs.io](#carla.readthedocs.io)/en/latest/adv_synchrony_timestep/) to learn more.
_
- **try_spawn_actor**(**self**, **blueprint**, **transform**, **attach_to**=None, **attachment**=Rigid)
Same as __spawn_actor()__ but returns None on failure instead of throwing an exception.
- **Parameters:**
- `blueprint` (_[carla.ActorBlueprint](#carla.ActorBlueprint)_) – The reference from which the actor will be created.
- `transform` (_[carla.Transform](#carla.Transform)_) – Contains the location and orientation the actor will be spawned with.
- `attach_to` (_[carla.Actor](#carla.Actor)_) – The parent object that the spawned actor will follow around.
- `attachment` (_[carla.AttachmentType](#carla.AttachmentType)_) – Determines how fixed and rigorous should be the changes in position according to its parent object.
- **Return:** _[carla.Actor](#carla.Actor)_
- **wait_for_tick**(**self**, **seconds**=10.0)
This method is used in [__asynchronous__ mode](https://[carla.readthedocs.io](#carla.readthedocs.io)/en/latest/adv_synchrony_timestep/). It makes the client wait for a server tick. When the next frame is computed, the server will tick and return a snapshot describing the new state of the world.
- **Parameters:**
- `seconds` (_float – seconds_) – Maximum time the server should wait for a tick. It is set to 10.0
by default.
- **Return:** _[carla.WorldSnapshot](#carla.WorldSnapshot)_
0.0
means variable time-step and it is the default mode.