airsim

This page documents airsim, the python package to be used for Microsoft Colosseum.

class airsim.client.VehicleClient(ip='', port=41451, timeout_value=3600)[source]

Bases: object

armDisarm(arm, vehicle_name='')[source]

Arms or disarms vehicle

Parameters:
  • arm (bool) – True to arm, False to disarm the vehicle

  • vehicle_name (str, optional) – Name of the vehicle to send this command to

Returns:

Success

Return type:

bool

cancelLastTask(vehicle_name='')[source]

Cancel previous Async task

Parameters:

vehicle_name (str, optional) – Name of the vehicle

confirmConnection()[source]

Checks state of connection every 1 sec and reports it in Console so user can see the progress for connection.

enableApiControl(is_enabled, vehicle_name='')[source]

Enables or disables API control for vehicle corresponding to vehicle_name

Parameters:
  • is_enabled (bool) – True to enable, False to disable API control

  • vehicle_name (str, optional) – Name of the vehicle to send this command to

getBarometerData(barometer_name='', vehicle_name='')[source]
Parameters:
  • barometer_name (str, optional) – Name of Barometer to get data from, specified in settings.json

  • vehicle_name (str, optional) – Name of vehicle to which the sensor corresponds to

Return type:

BarometerData

getClientVersion()[source]
getDistanceSensorData(distance_sensor_name='', vehicle_name='')[source]
Parameters:
  • distance_sensor_name (str, optional) – Name of Distance Sensor to get data from, specified in settings.json

  • vehicle_name (str, optional) – Name of vehicle to which the sensor corresponds to

Return type:

DistanceSensorData

getGpsData(gps_name='', vehicle_name='')[source]
Parameters:
  • gps_name (str, optional) – Name of GPS to get data from, specified in settings.json

  • vehicle_name (str, optional) – Name of vehicle to which the sensor corresponds to

Return type:

GpsData

getHomeGeoPoint(vehicle_name='')[source]

Get the Home location of the vehicle

Parameters:

vehicle_name (str, optional) – Name of vehicle to get home location of

Returns:

Home location of the vehicle

Return type:

GeoPoint

getImuData(imu_name='', vehicle_name='')[source]
Parameters:
  • imu_name (str, optional) – Name of IMU to get data from, specified in settings.json

  • vehicle_name (str, optional) – Name of vehicle to which the sensor corresponds to

Return type:

ImuData

getLidarData(lidar_name='', vehicle_name='')[source]
Parameters:
  • lidar_name (str, optional) – Name of Lidar to get data from, specified in settings.json

  • vehicle_name (str, optional) – Name of vehicle to which the sensor corresponds to

Return type:

LidarData

getMagnetometerData(magnetometer_name='', vehicle_name='')[source]
Parameters:
  • magnetometer_name (str, optional) – Name of Magnetometer to get data from, specified in settings.json

  • vehicle_name (str, optional) – Name of vehicle to which the sensor corresponds to

Return type:

MagnetometerData

getMinRequiredClientVersion()[source]
getMinRequiredServerVersion()[source]
getServerVersion()[source]
getSettingsString()[source]

Fetch the settings text being used by AirSim

Returns:

Settings text in JSON format

Return type:

str

isApiControlEnabled(vehicle_name='')[source]

Returns true if API control is established.

If false (which is default) then API calls would be ignored. After a successful call to enableApiControl, isApiControlEnabled should return true.

Parameters:

vehicle_name (str, optional) – Name of the vehicle

Returns:

If API control is enabled

Return type:

bool

isRecording()[source]

Whether Recording is running or not

Returns:

True if Recording, else False

Return type:

bool

listVehicles()[source]

Lists the names of current vehicles

Returns:

List containing names of all vehicles

Return type:

list[str]

ping()[source]

If connection is established then this call will return true otherwise it will be blocked until timeout

Return type:

bool

reset()[source]

Reset the vehicle to its original starting state

Note that you must call enableApiControl and armDisarm again after the call to reset

simAddDetectionFilterMeshName(camera_name, image_type, mesh_name, vehicle_name='', external=False)[source]

Add mesh name to detect in wild card format

For example: simAddDetectionFilterMeshName(“Car_*”) will detect all instance named “Car_*”

Parameters:
  • camera_name (str) – Name of the camera, for backwards compatibility, ID numbers such as 0,1,etc. can also be used

  • image_type (ImageType) – Type of image required

  • mesh_name (str) – mesh name in wild card format

  • vehicle_name (str, optional) – Vehicle which the camera is associated with

  • external (bool, optional) – Whether the camera is an External Camera

simAddVehicle(vehicle_name, vehicle_type, pose, pawn_path='')[source]

Create vehicle at runtime

Parameters:
  • vehicle_name (str) – Name of the vehicle being created

  • vehicle_type (str) – Type of vehicle, e.g. “simpleflight”

  • pose (Pose) – Initial pose of the vehicle

  • pawn_path (str, optional) – Vehicle blueprint path, default empty wbich uses the default blueprint for the vehicle type

Returns:

Whether vehicle was created

Return type:

bool

simClearDetectionMeshNames(camera_name, image_type, vehicle_name='', external=False)[source]

Clear all mesh names from detection filter

Parameters:
  • camera_name (str) – Name of the camera, for backwards compatibility, ID numbers such as 0,1,etc. can also be used

  • image_type (ImageType) – Type of image required

  • vehicle_name (str, optional) – Vehicle which the camera is associated with

  • external (bool, optional) – Whether the camera is an External Camera

simContinueForFrames(frames)[source]

Continue (or resume if paused) the simulation for the specified number of frames, after which the simulation will be paused.

Parameters:

frames (int) – Frames to run the simulation for

simContinueForTime(seconds)[source]

Continue the simulation for the specified number of seconds

Parameters:

seconds (float) – Time to run the simulation for

simCreateVoxelGrid(position, x, y, z, res, of)[source]

Construct and save a binvox-formatted voxel grid of environment

Parameters:
  • position (Vector3r) – Position around which voxel grid is centered in m

  • x (int) – Size of each voxel grid dimension in m

  • y (int) – Size of each voxel grid dimension in m

  • z (int) – Size of each voxel grid dimension in m

  • res (float) – Resolution of voxel grid in m

  • of (str) – Name of output file to save voxel grid as

Returns:

True if output written to file successfully, else False

Return type:

bool

simDestroyObject(object_name)[source]

Removes selected object from the world

Parameters:

object_name (str) – Name of object to be removed

Returns:

True if object is queued up for removal

Return type:

bool

simEnableFocusPlane(enable, camera_name, vehicle_name='', external=False)[source]
simEnableManualFocus(enable, camera_name, vehicle_name='', external=False)[source]
simEnableWeather(enable)[source]

Enable Weather effects. Needs to be called before using simSetWeatherParameter API

Parameters:

enable (bool) – True to enable, False to disable

simFindLookAtRotation(object_name, vehicle_name='')[source]
simFlushPersistentMarkers()[source]

Clear any persistent markers - those plotted with setting is_persistent=True in the APIs below

simGetCameraInfo(camera_name, vehicle_name='', external=False)[source]

Get details about the camera

Parameters:
  • camera_name (str) – Name of the camera, for backwards compatibility, ID numbers such as 0,1,etc. can also be used

  • vehicle_name (str, optional) – Vehicle which the camera is associated with

  • external (bool, optional) – Whether the camera is an External Camera

Return type:

CameraInfo

simGetCollisionInfo(vehicle_name='')[source]
Parameters:

vehicle_name (str, optional) – Name of the Vehicle to get the info of

Return type:

CollisionInfo

simGetCurrentFieldOfView(camera_name, vehicle_name='', external=False)[source]
simGetDetections(camera_name, image_type, vehicle_name='', external=False)[source]

Get current detections

Parameters:
  • camera_name (str) – Name of the camera, for backwards compatibility, ID numbers such as 0,1,etc. can also be used

  • image_type (ImageType) – Type of image required

  • vehicle_name (str, optional) – Vehicle which the camera is associated with

  • external (bool, optional) – Whether the camera is an External Camera

Returns:

DetectionInfo array

simGetDistortionParams(camera_name, vehicle_name='', external=False)[source]

Get camera distortion parameters

Parameters:
  • camera_name (str) – Name of the camera, for backwards compatibility, ID numbers such as 0,1,etc. can also be used

  • vehicle_name (str, optional) – Vehicle which the camera is associated with

  • external (bool, optional) – Whether the camera is an External Camera

Returns:

List of distortion parameter values corresponding to K1, K2, K3, P1, P2 respectively.

Return type:

List (float)

simGetFilmbackSettings(camera_name, vehicle_name='', external=False)[source]
simGetFocalLength(camera_name, vehicle_name='', external=False)[source]
simGetFocusAperture(camera_name, vehicle_name='', external=False)[source]
simGetFocusDistance(camera_name, vehicle_name='', external=False)[source]
simGetGroundTruthEnvironment(vehicle_name='') EnvironmentState[source]

Get ground truth environment state

The position inside the returned EnvironmentState is in the frame of the vehicle’s starting point

Parameters:

vehicle_name (str, optional) – Name of the vehicle

Returns:

Ground truth environment state

Return type:

EnvironmentState

simGetGroundTruthKinematics(vehicle_name='') KinematicsState[source]

Get Ground truth kinematics of the vehicle

The position inside the returned KinematicsState is in the frame of the vehicle’s starting point

Parameters:

vehicle_name (str, optional) – Name of the vehicle

Returns:

Ground truth of the vehicle

Return type:

KinematicsState

simGetImage(camera_name, image_type, vehicle_name='', external=False)[source]

Get a single image

Returns bytes of png format image which can be dumped into abinary file to create .png image string_to_uint8_array() can be used to convert into Numpy unit8 array See https://microsoft.github.io/AirSim/image_apis/ for details

Parameters:
  • camera_name (str) – Name of the camera, for backwards compatibility, ID numbers such as 0,1,etc. can also be used

  • image_type (ImageType) – Type of image required

  • vehicle_name (str, optional) – Name of the vehicle with the camera

  • external (bool, optional) – Whether the camera is an External Camera

Returns:

Binary string literal of compressed png image

simGetImages(requests, vehicle_name='', external=False)[source]

Get multiple images

See https://microsoft.github.io/AirSim/image_apis/ for details and examples

Parameters:
  • requests (list[ImageRequest]) – Images required

  • vehicle_name (str, optional) – Name of vehicle associated with the camera

  • external (bool, optional) – Whether the camera is an External Camera

Return type:

list[ImageResponse]

simGetLensSettings(camera_name, vehicle_name='', external=False)[source]
simGetLidarSegmentation(lidar_name='', vehicle_name='')[source]

NOTE: Deprecated API, use getLidarData() API instead Returns Segmentation ID of each point’s collided object in the last Lidar update

Parameters:
  • lidar_name (str, optional) – Name of Lidar sensor

  • vehicle_name (str, optional) – Name of the vehicle wth the sensor

Returns:

Segmentation IDs of the objects

Return type:

list[int]

simGetMeshPositionVertexBuffers()[source]

Returns the static meshes that make up the scene

See https://microsoft.github.io/AirSim/meshes/ for details and how to use this

Return type:

list[MeshPositionVertexBuffersResponse]

simGetObjectPose(object_name)[source]

The position inside the returned Pose is in the world frame

Parameters:

object_name (str) – Object to get the Pose of

Return type:

Pose

simGetObjectScale(object_name)[source]

Gets scale of an object in the world

Parameters:

object_name (str) – Object to get the scale of

Returns:

Scale

Return type:

airsim.Vector3r

simGetPresetFilmbackSettings(camera_name, vehicle_name='', external=False)[source]
simGetPresetLensSettings(camera_name, vehicle_name='', external=False)[source]
simGetSegmentationObjectID(mesh_name)[source]

Returns Object ID for the given mesh name

Mapping of Object IDs to RGB values can be seen at https://microsoft.github.io/AirSim/seg_rgbs.txt

Parameters:

mesh_name (str) – Name of the mesh to get the ID of

simGetVehiclePose(vehicle_name='')[source]

The position inside the returned Pose is in the frame of the vehicle’s starting point

Parameters:

vehicle_name (str, optional) – Name of the vehicle to get the Pose of

Return type:

Pose

simGetWorldExtents()[source]

Returns a list of GeoPoints representing the minimum and maximum extents of the world

Returns:

list[GeoPoint]

simIsPause()[source]

Returns true if the simulation is paused

Returns:

If the simulation is paused

Return type:

bool

simListAssets()[source]

Lists all the assets present in the Asset Registry

Returns:

Names of all the assets

Return type:

list[str]

simListSceneObjects(name_regex='.*')[source]

Lists the objects present in the environment

Default behaviour is to list all objects, regex can be used to return smaller list of matching objects or actors

Parameters:

name_regex (str, optional) – String to match actor names against, e.g. “Cylinder.*”

Returns:

List containing all the names

Return type:

list[str]

simListSceneObjectsByTag(tag_regex='.*')[source]

Lists the objects present in the environment by searching their tags

Default behaviour is to list all objects, regex can be used to return smaller list of matching objects or actors

Parameters:

tag_regex (str, optional) – String to match actor tags against, e.g. “Tag.*”

Returns:

List containing all the names

Return type:

list[str]

simLoadLevel(level_name)[source]

Loads a level specified by its name

Parameters:

level_name (str) – Name of the level to load

Returns:

True if the level was successfully loaded

Return type:

bool

simPause(is_paused)[source]

Pauses simulation

Parameters:

is_paused (bool) – True to pause the simulation, False to release

simPlotArrows(points_start, points_end, color_rgba=[1.0, 0.0, 0.0, 1.0], thickness=5.0, arrow_size=2.0, duration=-1.0, is_persistent=False)[source]

Plots a list of arrows in World NED frame, defined from points_start[0] to points_end[0], points_start[1] to points_end[1], … , points_start[n-1] to points_end[n-1]

Parameters:
  • points_start (list[Vector3r]) – List of 3D start positions of arrow start positions, specified as Vector3r objects

  • points_end (list[Vector3r]) – List of 3D end positions of arrow start positions, specified as Vector3r objects

  • color_rgba (list, optional) – desired RGBA values from 0.0 to 1.0

  • thickness (float, optional) – Thickness of line

  • arrow_size (float, optional) – Size of arrow head

  • duration (float, optional) – Duration (seconds) to plot for

  • is_persistent (bool, optional) – If set to True, the desired object will be plotted for infinite time.

simPlotLineList(points, color_rgba=[1.0, 0.0, 0.0, 1.0], thickness=5.0, duration=-1.0, is_persistent=False)[source]

Plots a line strip in World NED frame, defined from points[0] to points[1], points[2] to points[3], … , points[n-2] to points[n-1]

Parameters:
  • points (list[Vector3r]) – List of 3D locations of line start and end points, specified as Vector3r objects. Must be even

  • color_rgba (list, optional) – desired RGBA values from 0.0 to 1.0

  • thickness (float, optional) – Thickness of line

  • duration (float, optional) – Duration (seconds) to plot for

  • is_persistent (bool, optional) – If set to True, the desired object will be plotted for infinite time.

simPlotLineStrip(points, color_rgba=[1.0, 0.0, 0.0, 1.0], thickness=5.0, duration=-1.0, is_persistent=False)[source]

Plots a line strip in World NED frame, defined from points[0] to points[1], points[1] to points[2], … , points[n-2] to points[n-1]

Parameters:
  • points (list[Vector3r]) – List of 3D locations of line start and end points, specified as Vector3r objects

  • color_rgba (list, optional) – desired RGBA values from 0.0 to 1.0

  • thickness (float, optional) – Thickness of line

  • duration (float, optional) – Duration (seconds) to plot for

  • is_persistent (bool, optional) – If set to True, the desired object will be plotted for infinite time.

simPlotPoints(points, color_rgba=[1.0, 0.0, 0.0, 1.0], size=10.0, duration=-1.0, is_persistent=False)[source]

Plot a list of 3D points in World NED frame

Parameters:
  • points (list[Vector3r]) – List of Vector3r objects

  • color_rgba (list, optional) – desired RGBA values from 0.0 to 1.0

  • size (float, optional) – Size of plotted point

  • duration (float, optional) – Duration (seconds) to plot for

  • is_persistent (bool, optional) – If set to True, the desired object will be plotted for infinite time.

simPlotStrings(strings, positions, scale=5, color_rgba=[1.0, 0.0, 0.0, 1.0], duration=-1.0)[source]

Plots a list of strings at desired positions in World NED frame.

Parameters:
  • strings (list[String], optional) – List of strings to plot

  • positions (list[Vector3r]) – List of positions where the strings should be plotted. Should be in one-to-one correspondence with the strings’ list

  • scale (float, optional) – Font scale of transform name

  • color_rgba (list, optional) – desired RGBA values from 0.0 to 1.0

  • duration (float, optional) – Duration (seconds) to plot for

simPlotTransforms(poses, scale=5.0, thickness=5.0, duration=-1.0, is_persistent=False)[source]

Plots a list of transforms in World NED frame.

Parameters:
  • poses (list[Pose]) – List of Pose objects representing the transforms to plot

  • scale (float, optional) – Length of transforms’ axes

  • thickness (float, optional) – Thickness of transforms’ axes

  • duration (float, optional) – Duration (seconds) to plot for

  • is_persistent (bool, optional) – If set to True, the desired object will be plotted for infinite time.

simPlotTransformsWithNames(poses, names, tf_scale=5.0, tf_thickness=5.0, text_scale=10.0, text_color_rgba=[1.0, 0.0, 0.0, 1.0], duration=-1.0)[source]

Plots a list of transforms with their names in World NED frame.

Parameters:
  • poses (list[Pose]) – List of Pose objects representing the transforms to plot

  • names (list[string]) – List of strings with one-to-one correspondence to list of poses

  • tf_scale (float, optional) – Length of transforms’ axes

  • tf_thickness (float, optional) – Thickness of transforms’ axes

  • text_scale (float, optional) – Font scale of transform name

  • text_color_rgba (list, optional) – desired RGBA values from 0.0 to 1.0 for the transform name

  • duration (float, optional) – Duration (seconds) to plot for

simPrintLogMessage(message, message_param='', severity=0)[source]

Prints the specified message in the simulator’s window.

If message_param is supplied, then it’s printed next to the message and in that case if this API is called with same message value but different message_param again then previous line is overwritten with new line (instead of API creating new line on display).

For example, simPrintLogMessage(“Iteration: “, to_string(i)) keeps updating same line on display when API is called with different values of i. The valid values of severity parameter is 0 to 3 inclusive that corresponds to different colors.

Parameters:
  • message (str) – Message to be printed

  • message_param (str, optional) – Parameter to be printed next to the message

  • severity (int, optional) – Range 0-3, inclusive, corresponding to the severity of the message

simRunConsoleCommand(command)[source]

Allows the client to execute a command in Unreal’s native console, via an API. Affords access to the countless built-in commands such as “stat unit”, “stat fps”, “open [map]”, adjust any config settings, etc. etc. Allows the user to create bespoke APIs very easily, by adding a custom event to the level blueprint, and then calling the console command “ce MyEventName [args]”. No recompilation of AirSim needed!

Parameters:

command ([string]) – Desired Unreal Engine Console command to run

Returns:

Success

Return type:

[bool]

simSetCameraFov(camera_name, fov_degrees, vehicle_name='', external=False)[source]
  • Control the field of view of a selected camera

Parameters:
  • camera_name (str) – Name of the camera to be controlled

  • fov_degrees (float) – Value of field of view in degrees

  • vehicle_name (str, optional) – Name of vehicle which the camera corresponds to

  • external (bool, optional) – Whether the camera is an External Camera

simSetCameraPose(camera_name, pose, vehicle_name='', external=False)[source]
  • Control the pose of a selected camera

Parameters:
  • camera_name (str) – Name of the camera to be controlled

  • pose (Pose) – Pose representing the desired position and orientation of the camera

  • vehicle_name (str, optional) – Name of vehicle which the camera corresponds to

  • external (bool, optional) – Whether the camera is an External Camera

simSetDetectionFilterRadius(camera_name, image_type, radius_cm, vehicle_name='', external=False)[source]

Set detection radius for all cameras

Parameters:
  • camera_name (str) – Name of the camera, for backwards compatibility, ID numbers such as 0,1,etc. can also be used

  • image_type (ImageType) – Type of image required

  • radius_cm (int) – Radius in [cm]

  • vehicle_name (str, optional) – Vehicle which the camera is associated with

  • external (bool, optional) – Whether the camera is an External Camera

simSetDistortionParam(camera_name, param_name, value, vehicle_name='', external=False)[source]

Set single camera distortion parameter

Parameters:
  • camera_name (str) – Name of the camera, for backwards compatibility, ID numbers such as 0,1,etc. can also be used

  • param_name (str) – Name of distortion parameter

  • value (float) – Value of distortion parameter

  • vehicle_name (str, optional) – Vehicle which the camera is associated with

  • external (bool, optional) – Whether the camera is an External Camera

simSetDistortionParams(camera_name, distortion_params, vehicle_name='', external=False)[source]

Set camera distortion parameters

Parameters:
  • camera_name (str) – Name of the camera, for backwards compatibility, ID numbers such as 0,1,etc. can also be used

  • distortion_params (dict) – Dictionary of distortion param names and corresponding values {“K1”: 0.0, “K2”: 0.0, “K3”: 0.0, “P1”: 0.0, “P2”: 0.0}

  • vehicle_name (str, optional) – Vehicle which the camera is associated with

  • external (bool, optional) – Whether the camera is an External Camera

simSetExtForce(ext_force)[source]

Set arbitrary external forces, in World frame, NED direction. Can be used for implementing simple payloads.

Parameters:

ext_force (Vector3r) – Force, in World frame, NED direction, in N

simSetFilmbackSettings(sensor_width, sensor_height, camera_name, vehicle_name='', external=False)[source]
simSetFocalLength(focal_length, camera_name, vehicle_name='', external=False)[source]
simSetFocusAperture(focus_aperture, camera_name, vehicle_name='', external=False)[source]
simSetFocusDistance(focus_distance, camera_name, vehicle_name='', external=False)[source]
simSetKinematics(state, ignore_collision, vehicle_name='')[source]

Set the kinematics state of the vehicle

If you don’t want to change position (or orientation) then just set components of position (or orientation) to floating point nan values

Parameters:
  • state (KinematicsState) – Desired Pose pf the vehicle

  • ignore_collision (bool) – Whether to ignore any collision or not

  • vehicle_name (str, optional) – Name of the vehicle to move

simSetLightIntensity(light_name, intensity)[source]

Change intensity of named light

Parameters:
  • light_name (str) – Name of light to change

  • intensity (float) – New intensity value

Returns:

True if successful, otherwise False

Return type:

bool

simSetObjectMaterial(object_name, material_name, component_id=0)[source]

Runtime Swap Texture API See https://microsoft.github.io/AirSim/retexturing/ for details :param object_name: name of object to set material for :type object_name: str :param material_name: name of material to set for object :type material_name: str :param component_id: index of material elements :type component_id: int, optional

Returns:

True if material was set

Return type:

bool

simSetObjectMaterialFromTexture(object_name, texture_path, component_id=0)[source]

Runtime Swap Texture API See https://microsoft.github.io/AirSim/retexturing/ for details :param object_name: name of object to set material for :type object_name: str :param texture_path: path to texture to set for object :type texture_path: str :param component_id: index of material elements :type component_id: int, optional

Returns:

True if material was set

Return type:

bool

simSetObjectPose(object_name, pose, teleport=True)[source]

Set the pose of the object(actor) in the environment

The specified actor must have Mobility set to movable, otherwise there will be undefined behaviour. See https://www.unrealengine.com/en-US/blog/moving-physical-objects for details on how to set Mobility and the effect of Teleport parameter

Parameters:
  • object_name (str) – Name of the object(actor) to move

  • pose (Pose) – Desired Pose of the object

  • teleport (bool, optional) – Whether to move the object immediately without affecting their velocity

Returns:

If the move was successful

Return type:

bool

simSetObjectScale(object_name, scale_vector)[source]

Sets scale of an object in the world

Parameters:
  • object_name (str) – Object to set the scale of

  • scale_vector (airsim.Vector3r) – Desired scale of object

Returns:

True if scale change was successful

Return type:

bool

simSetPresetFilmbackSettings(preset_filmback_settings, camera_name, vehicle_name='', external=False)[source]
simSetPresetLensSettings(preset_lens_settings, camera_name, vehicle_name='', external=False)[source]
simSetSegmentationObjectID(mesh_name, object_id, is_name_regex=False)[source]

Set segmentation ID for specific objects

See https://microsoft.github.io/AirSim/image_apis/#segmentation for details

Parameters:
Returns:

If the mesh was found

Return type:

bool

simSetTimeOfDay(is_enabled, start_datetime='', is_start_datetime_dst=False, celestial_clock_speed=1, update_interval_secs=60, move_sun=True)[source]

Control the position of Sun in the environment

Sun’s position is computed using the coordinates specified in OriginGeopoint in settings for the date-time specified in the argument, else if the string is empty, current date & time is used

Parameters:
  • is_enabled (bool) – True to enable time-of-day effect, False to reset the position to original

  • start_datetime (str, optional) – Date & Time in %Y-%m-%d %H:%M:%S format, e.g. 2018-02-12 15:20:00

  • is_start_datetime_dst (bool, optional) – True to adjust for Daylight Savings Time

  • celestial_clock_speed (float, optional) – Run celestial clock faster or slower than simulation clock E.g. Value 100 means for every 1 second of simulation clock, Sun’s position is advanced by 100 seconds so Sun will move in sky much faster

  • update_interval_secs (float, optional) – Interval to update the Sun’s position

  • move_sun (bool, optional) – Whether or not to move the Sun

simSetTraceLine(color_rgba, thickness=1.0, vehicle_name='')[source]

Modify the color and thickness of the line when Tracing is enabled

Tracing can be enabled by pressing T in the Editor or setting EnableTrace to True in the Vehicle Settings

Parameters:
  • color_rgba (list) – desired RGBA values from 0.0 to 1.0

  • thickness (float, optional) – Thickness of the line

  • vehicle_name (string, optional) – Name of the vehicle to set Trace line values for

simSetVehiclePose(pose, ignore_collision, vehicle_name='')[source]

Set the pose of the vehicle

If you don’t want to change position (or orientation) then just set components of position (or orientation) to floating point nan values

Parameters:
  • pose (Pose) – Desired Pose pf the vehicle

  • ignore_collision (bool) – Whether to ignore any collision or not

  • vehicle_name (str, optional) – Name of the vehicle to move

simSetWeatherParameter(param, val)[source]

Enable various weather effects

Parameters:
  • param (WeatherParameter) – Weather effect to be enabled

  • val (float) – Intensity of the effect, Range 0-1

simSetWind(wind)[source]

Set simulated wind, in World frame, NED direction, m/s

Parameters:

wind (Vector3r) – Wind, in World frame, NED direction, in m/s

simSpawnObject(object_name, asset_name, pose, scale, physics_enabled=False, is_blueprint=False)[source]

Spawned selected object in the world

Parameters:
  • object_name (str) – Desired name of new object

  • asset_name (str) – Name of asset(mesh) in the project database

  • pose (airsim.Pose) – Desired pose of object

  • scale (airsim.Vector3r) – Desired scale of object

  • physics_enabled (bool, optional) – Whether to enable physics for the object

  • is_blueprint (bool, optional) – Whether to spawn a blueprint or an actor

Returns:

Name of spawned object, in case it had to be modified

Return type:

str

simSwapTextures(tags, tex_id=0, component_id=0, material_id=0)[source]

Runtime Swap Texture API

See https://microsoft.github.io/AirSim/retexturing/ for details

Parameters:
  • tags (str) – string of “,” or “, “ delimited tags to identify on which actors to perform the swap

  • tex_id (int, optional) –

    indexes the array of textures assigned to each actor undergoing a swap

    If out-of-bounds for some object’s texture set, it will be taken modulo the number of textures that were available

  • component_id (int, optional) –

  • material_id (int, optional) –

Returns:

List of objects which matched the provided tags and had the texture swap perfomed

Return type:

list[str]

simTestLineOfSightBetweenPoints(point1, point2)[source]

Returns whether the target point is visible from the perspective of the source point

Parameters:
Returns:

Success

Return type:

[bool]

simTestLineOfSightToPoint(point, vehicle_name='')[source]

Returns whether the target point is visible from the perspective of the inputted vehicle

Parameters:
  • point (GeoPoint) – target point

  • vehicle_name (str, optional) – Name of vehicle

Returns:

Success

Return type:

[bool]

startRecording()[source]

Start Recording

Recording will be done according to the settings

stopRecording()[source]

Stop Recording

class airsim.client.MultirotorClient(ip='', port=41451, timeout_value=3600)[source]

Bases: VehicleClient, object

getMultirotorState(vehicle_name='') MultirotorState[source]

The position inside the returned MultirotorState is in the frame of the vehicle’s starting point

Parameters:

vehicle_name (str, optional) – Vehicle to get the state of

Return type:

MultirotorState

getRotorStates(vehicle_name='') RotorStates[source]

Used to obtain the current state of all a multirotor’s rotors. The state includes the speeds, thrusts and torques for all rotors.

Parameters:

vehicle_name (str, optional) – Vehicle to get the rotor state of

Returns:

Containing a timestamp and the speed, thrust and torque of all rotors.

Return type:

RotorStates

goHomeAsync(timeout_sec=3e+38, vehicle_name='')[source]

Return vehicle to Home i.e. Launch location

Parameters:
  • timeout_sec (int, optional) – Timeout for the vehicle to reach desired altitude

  • vehicle_name (str, optional) – Name of the vehicle to send this command to

Returns:

future. call .join() to wait for method to finish. Example: client.METHOD().join()

Return type:

msgpackrpc.future.Future

hoverAsync(vehicle_name='')[source]
landAsync(timeout_sec=60, vehicle_name='')[source]

Land the vehicle

Parameters:
  • timeout_sec (int, optional) – Timeout for the vehicle to land

  • vehicle_name (str, optional) – Name of the vehicle to send this command to

Returns:

future. call .join() to wait for method to finish. Example: client.METHOD().join()

Return type:

msgpackrpc.future.Future

moveByAngleRatesThrottleAsync(roll_rate, pitch_rate, yaw_rate, throttle, duration, vehicle_name='')[source]
  • Desired throttle is between 0.0 to 1.0

  • Roll rate, pitch rate, and yaw rate set points are given in radians, in the body frame.

  • The body frame follows the Front Left Up (FLU) convention, and right-handedness.

  • Frame Convention:
    • X axis is along the Front direction of the quadrotor.

    Clockwise rotation about this axis defines a positive roll angle.
    Hence, rolling with a positive angle is equivalent to translating in the right direction, w.r.t. our FLU body frame.
    • Y axis is along the Left direction of the quadrotor.

    Clockwise rotation about this axis defines a positive pitch angle.
    Hence, pitching with a positive angle is equivalent to translating in the front direction, w.r.t. our FLU body frame.
    • Z axis is along the Up direction.

    Clockwise rotation about this axis defines a positive yaw angle.
    Hence, yawing with a positive angle is equivalent to rotated towards the left direction wrt our FLU body frame. Or in an anticlockwise fashion in the body XY / FL plane.
Parameters:
  • roll_rate (float) – Desired roll rate, in radians / second

  • pitch_rate (float) – Desired pitch rate, in radians / second

  • yaw_rate (float) – Desired yaw rate, in radians / second

  • throttle (float) – Desired throttle (between 0.0 to 1.0)

  • duration (float) – Desired amount of time (seconds), to send this command for

  • vehicle_name (str, optional) – Name of the multirotor to send this command to

Returns:

future. call .join() to wait for method to finish. Example: client.METHOD().join()

Return type:

msgpackrpc.future.Future

moveByAngleRatesZAsync(roll_rate, pitch_rate, yaw_rate, z, duration, vehicle_name='')[source]
  • z is given in local NED frame of the vehicle.

  • Roll rate, pitch rate, and yaw rate set points are given in radians, in the body frame.

  • The body frame follows the Front Left Up (FLU) convention, and right-handedness.

  • Frame Convention:
    • X axis is along the Front direction of the quadrotor.

    Clockwise rotation about this axis defines a positive roll angle.
    Hence, rolling with a positive angle is equivalent to translating in the right direction, w.r.t. our FLU body frame.
    • Y axis is along the Left direction of the quadrotor.

    Clockwise rotation about this axis defines a positive pitch angle.
    Hence, pitching with a positive angle is equivalent to translating in the front direction, w.r.t. our FLU body frame.
    • Z axis is along the Up direction.

    Clockwise rotation about this axis defines a positive yaw angle.
    Hence, yawing with a positive angle is equivalent to rotated towards the left direction wrt our FLU body frame. Or in an anticlockwise fashion in the body XY / FL plane.
Parameters:
  • roll_rate (float) – Desired roll rate, in radians / second

  • pitch_rate (float) – Desired pitch rate, in radians / second

  • yaw_rate (float) – Desired yaw rate, in radians / second

  • z (float) – Desired Z value (in local NED frame of the vehicle)

  • duration (float) – Desired amount of time (seconds), to send this command for

  • vehicle_name (str, optional) – Name of the multirotor to send this command to

Returns:

future. call .join() to wait for method to finish. Example: client.METHOD().join()

Return type:

msgpackrpc.future.Future

moveByAngleThrottleAsync(pitch, roll, throttle, yaw_rate, duration, vehicle_name='')[source]
moveByAngleZAsync(pitch, roll, z, yaw, duration, vehicle_name='')[source]
moveByManualAsync(vx_max, vy_max, z_min, duration, drivetrain=0, yaw_mode=<YawMode> {   'is_rate': True, 'yaw_or_rate': 0.0}, vehicle_name='')[source]
  • Read current RC state and use it to control the vehicles.

Parameters sets up the constraints on velocity and minimum altitude while flying. If RC state is detected to violate these constraints then that RC state would be ignored.

Parameters:
  • vx_max (float) – max velocity allowed in x direction

  • vy_max (float) – max velocity allowed in y direction

  • vz_max (float) – max velocity allowed in z direction

  • z_min (float) – min z allowed for vehicle position

  • duration (float) – after this duration vehicle would switch back to non-manual mode

  • drivetrain (DrivetrainType) – when ForwardOnly, vehicle rotates itself so that its front is always facing the direction of travel. If MaxDegreeOfFreedom then it doesn’t do that (crab-like movement)

  • yaw_mode (YawMode) – Specifies if vehicle should face at given angle (is_rate=False) or should be rotating around its axis at given rate (is_rate=True)

  • vehicle_name (str, optional) – Name of the multirotor to send this command to

Returns:

future. call .join() to wait for method to finish. Example: client.METHOD().join()

Return type:

msgpackrpc.future.Future

moveByMotorPWMsAsync(front_right_pwm, rear_left_pwm, front_left_pwm, rear_right_pwm, duration, vehicle_name='')[source]
  • Directly control the motors using PWM values

Parameters:
  • front_right_pwm (float) – PWM value for the front right motor (between 0.0 to 1.0)

  • rear_left_pwm (float) – PWM value for the rear left motor (between 0.0 to 1.0)

  • front_left_pwm (float) – PWM value for the front left motor (between 0.0 to 1.0)

  • rear_right_pwm (float) – PWM value for the rear right motor (between 0.0 to 1.0)

  • duration (float) – Desired amount of time (seconds), to send this command for

  • vehicle_name (str, optional) – Name of the multirotor to send this command to

Returns:

future. call .join() to wait for method to finish. Example: client.METHOD().join()

Return type:

msgpackrpc.future.Future

moveByRC(rcdata=<RCData> {   'is_initialized': False, 'is_valid': False, 'pitch': 0.0, 'roll': 0.0, 'switch1': 0, 'switch2': 0, 'switch3': 0, 'switch4': 0, 'switch5': 0, 'switch6': 0, 'switch7': 0, 'switch8': 0, 'throttle': 0.0, 'timestamp': 0, 'yaw': 0.0}, vehicle_name='')[source]
moveByRollPitchYawThrottleAsync(roll, pitch, yaw, throttle, duration, vehicle_name='')[source]
  • Desired throttle is between 0.0 to 1.0

  • Roll angle, pitch angle, and yaw angle are given in degrees when using PX4 and in radians when using SimpleFlight, in the body frame.

  • The body frame follows the Front Left Up (FLU) convention, and right-handedness.

  • Frame Convention:
    • X axis is along the Front direction of the quadrotor.

    Clockwise rotation about this axis defines a positive roll angle.
    Hence, rolling with a positive angle is equivalent to translating in the right direction, w.r.t. our FLU body frame.
    • Y axis is along the Left direction of the quadrotor.

    Clockwise rotation about this axis defines a positive pitch angle.
    Hence, pitching with a positive angle is equivalent to translating in the front direction, w.r.t. our FLU body frame.
    • Z axis is along the Up direction.

    Clockwise rotation about this axis defines a positive yaw angle.
    Hence, yawing with a positive angle is equivalent to rotated towards the left direction wrt our FLU body frame. Or in an anticlockwise fashion in the body XY / FL plane.
Parameters:
  • roll (float) – Desired roll angle.

  • pitch (float) – Desired pitch angle.

  • yaw (float) – Desired yaw angle.

  • throttle (float) – Desired throttle (between 0.0 to 1.0)

  • duration (float) – Desired amount of time (seconds), to send this command for

  • vehicle_name (str, optional) – Name of the multirotor to send this command to

Returns:

future. call .join() to wait for method to finish. Example: client.METHOD().join()

Return type:

msgpackrpc.future.Future

moveByRollPitchYawZAsync(roll, pitch, yaw, z, duration, vehicle_name='')[source]
  • z is given in local NED frame of the vehicle.

  • Roll angle, pitch angle, and yaw angle set points are given in radians, in the body frame.

  • The body frame follows the Front Left Up (FLU) convention, and right-handedness.

  • Frame Convention:
    • X axis is along the Front direction of the quadrotor.

    Clockwise rotation about this axis defines a positive roll angle.
    Hence, rolling with a positive angle is equivalent to translating in the right direction, w.r.t. our FLU body frame.
    • Y axis is along the Left direction of the quadrotor.

    Clockwise rotation about this axis defines a positive pitch angle.
    Hence, pitching with a positive angle is equivalent to translating in the front direction, w.r.t. our FLU body frame.
    • Z axis is along the Up direction.

    Clockwise rotation about this axis defines a positive yaw angle.
    Hence, yawing with a positive angle is equivalent to rotated towards the left direction wrt our FLU body frame. Or in an anticlockwise fashion in the body XY / FL plane.
Parameters:
  • roll (float) – Desired roll angle, in radians.

  • pitch (float) – Desired pitch angle, in radians.

  • yaw (float) – Desired yaw angle, in radians.

  • z (float) – Desired Z value (in local NED frame of the vehicle)

  • duration (float) – Desired amount of time (seconds), to send this command for

  • vehicle_name (str, optional) – Name of the multirotor to send this command to

Returns:

future. call .join() to wait for method to finish. Example: client.METHOD().join()

Return type:

msgpackrpc.future.Future

moveByRollPitchYawrateThrottleAsync(roll, pitch, yaw_rate, throttle, duration, vehicle_name='')[source]
  • Desired throttle is between 0.0 to 1.0

  • Roll angle, pitch angle, and yaw rate set points are given in radians, in the body frame.

  • The body frame follows the Front Left Up (FLU) convention, and right-handedness.

  • Frame Convention:
    • X axis is along the Front direction of the quadrotor.

    Clockwise rotation about this axis defines a positive roll angle.
    Hence, rolling with a positive angle is equivalent to translating in the right direction, w.r.t. our FLU body frame.
    • Y axis is along the Left direction of the quadrotor.

    Clockwise rotation about this axis defines a positive pitch angle.
    Hence, pitching with a positive angle is equivalent to translating in the front direction, w.r.t. our FLU body frame.
    • Z axis is along the Up direction.

    Clockwise rotation about this axis defines a positive yaw angle.
    Hence, yawing with a positive angle is equivalent to rotated towards the left direction wrt our FLU body frame. Or in an anticlockwise fashion in the body XY / FL plane.
Parameters:
  • roll (float) – Desired roll angle, in radians.

  • pitch (float) – Desired pitch angle, in radians.

  • yaw_rate (float) – Desired yaw rate, in radian per second.

  • throttle (float) – Desired throttle (between 0.0 to 1.0)

  • duration (float) – Desired amount of time (seconds), to send this command for

  • vehicle_name (str, optional) – Name of the multirotor to send this command to

Returns:

future. call .join() to wait for method to finish. Example: client.METHOD().join()

Return type:

msgpackrpc.future.Future

moveByRollPitchYawrateZAsync(roll, pitch, yaw_rate, z, duration, vehicle_name='')[source]
  • z is given in local NED frame of the vehicle.

  • Roll angle, pitch angle, and yaw rate set points are given in radians, in the body frame.

  • The body frame follows the Front Left Up (FLU) convention, and right-handedness.

  • Frame Convention:
    • X axis is along the Front direction of the quadrotor.

    Clockwise rotation about this axis defines a positive roll angle.
    Hence, rolling with a positive angle is equivalent to translating in the right direction, w.r.t. our FLU body frame.
    • Y axis is along the Left direction of the quadrotor.

    Clockwise rotation about this axis defines a positive pitch angle.
    Hence, pitching with a positive angle is equivalent to translating in the front direction, w.r.t. our FLU body frame.
    • Z axis is along the Up direction.

    Clockwise rotation about this axis defines a positive yaw angle.
    Hence, yawing with a positive angle is equivalent to rotated towards the left direction wrt our FLU body frame. Or in an anticlockwise fashion in the body XY / FL plane.
Parameters:
  • roll (float) – Desired roll angle, in radians.

  • pitch (float) – Desired pitch angle, in radians.

  • yaw_rate (float) – Desired yaw rate, in radian per second.

  • z (float) – Desired Z value (in local NED frame of the vehicle)

  • duration (float) – Desired amount of time (seconds), to send this command for

  • vehicle_name (str, optional) – Name of the multirotor to send this command to

Returns:

future. call .join() to wait for method to finish. Example: client.METHOD().join()

Return type:

msgpackrpc.future.Future

moveByVelocityAsync(vx, vy, vz, duration, drivetrain=0, yaw_mode=<YawMode> {   'is_rate': True, 'yaw_or_rate': 0.0}, vehicle_name='')[source]
Parameters:
  • vx (float) – desired velocity in world (NED) X axis

  • vy (float) – desired velocity in world (NED) Y axis

  • vz (float) – desired velocity in world (NED) Z axis

  • duration (float) – Desired amount of time (seconds), to send this command for

  • drivetrain (DrivetrainType, optional) –

  • yaw_mode (YawMode, optional) –

  • vehicle_name (str, optional) – Name of the multirotor to send this command to

Returns:

future. call .join() to wait for method to finish. Example: client.METHOD().join()

Return type:

msgpackrpc.future.Future

moveByVelocityBodyFrameAsync(vx, vy, vz, duration, drivetrain=0, yaw_mode=<YawMode> {   'is_rate': True, 'yaw_or_rate': 0.0}, vehicle_name='')[source]
Parameters:
  • vx (float) – desired velocity in the X axis of the vehicle’s local NED frame.

  • vy (float) – desired velocity in the Y axis of the vehicle’s local NED frame.

  • vz (float) – desired velocity in the Z axis of the vehicle’s local NED frame.

  • duration (float) – Desired amount of time (seconds), to send this command for

  • drivetrain (DrivetrainType, optional) –

  • yaw_mode (YawMode, optional) –

  • vehicle_name (str, optional) – Name of the multirotor to send this command to

Returns:

future. call .join() to wait for method to finish. Example: client.METHOD().join()

Return type:

msgpackrpc.future.Future

moveByVelocityZAsync(vx, vy, z, duration, drivetrain=0, yaw_mode=<YawMode> {   'is_rate': True, 'yaw_or_rate': 0.0}, vehicle_name='')[source]
moveByVelocityZBodyFrameAsync(vx, vy, z, duration, drivetrain=0, yaw_mode=<YawMode> {   'is_rate': True, 'yaw_or_rate': 0.0}, vehicle_name='')[source]
Parameters:
  • vx (float) – desired velocity in the X axis of the vehicle’s local NED frame

  • vy (float) – desired velocity in the Y axis of the vehicle’s local NED frame

  • z (float) – desired Z value (in local NED frame of the vehicle)

  • duration (float) – Desired amount of time (seconds), to send this command for

  • drivetrain (DrivetrainType, optional) –

  • yaw_mode (YawMode, optional) –

  • vehicle_name (str, optional) – Name of the multirotor to send this command to

Returns:

future. call .join() to wait for method to finish. Example: client.METHOD().join()

Return type:

msgpackrpc.future.Future

moveOnPathAsync(path, velocity, timeout_sec=3e+38, drivetrain=0, yaw_mode=<YawMode> {   'is_rate': True, 'yaw_or_rate': 0.0}, lookahead=-1, adaptive_lookahead=1, vehicle_name='')[source]
moveToGPSAsync(latitude, longitude, altitude, velocity, timeout_sec=3e+38, drivetrain=0, yaw_mode=<YawMode> {   'is_rate': True, 'yaw_or_rate': 0.0}, lookahead=-1, adaptive_lookahead=1, vehicle_name='')[source]
moveToPositionAsync(x, y, z, velocity, timeout_sec=3e+38, drivetrain=0, yaw_mode=<YawMode> {   'is_rate': True, 'yaw_or_rate': 0.0}, lookahead=-1, adaptive_lookahead=1, vehicle_name='')[source]
moveToZAsync(z, velocity, timeout_sec=3e+38, yaw_mode=<YawMode> {   'is_rate': True, 'yaw_or_rate': 0.0}, lookahead=-1, adaptive_lookahead=1, vehicle_name='')[source]
rotateByYawRateAsync(yaw_rate, duration, vehicle_name='')[source]
rotateToYawAsync(yaw, timeout_sec=3e+38, margin=5, vehicle_name='')[source]
setAngleLevelControllerGains(angle_level_gains=<airsim.types.AngleLevelControllerGains object>, vehicle_name='')[source]
  • Sets angle level controller gains (used by any API setting angle references - for ex: moveByRollPitchYawZAsync(), moveByRollPitchYawThrottleAsync(), etc)

  • Modifying these gains will also affect the behaviour of moveByVelocityAsync() API.

    This is because the AirSim flight controller will track velocity setpoints by converting them to angle set points.

  • This function should only be called if the default angle level control PID gains need to be modified.

  • Passing AngleLevelControllerGains() sets gains to default airsim values.

Parameters:
  • angle_level_gains (AngleLevelControllerGains) –

    • Correspond to the roll, pitch, yaw axes, defined in the body frame.

    • Pass AngleLevelControllerGains() to reset gains to default recommended values.

  • vehicle_name (str, optional) – Name of the multirotor to send this command to

setAngleRateControllerGains(angle_rate_gains=<airsim.types.AngleRateControllerGains object>, vehicle_name='')[source]
  • Modifying these gains will have an affect on ALL move*() APIs.

    This is because any velocity setpoint is converted to an angle level setpoint which is tracked with an angle level controllers. That angle level setpoint is itself tracked with and angle rate controller.

  • This function should only be called if the default angle rate control PID gains need to be modified.

Parameters:
  • angle_rate_gains (AngleRateControllerGains) –

    • Correspond to the roll, pitch, yaw axes, defined in the body frame.

    • Pass AngleRateControllerGains() to reset gains to default recommended values.

  • vehicle_name (str, optional) – Name of the multirotor to send this command to

setPositionControllerGains(position_gains=<airsim.types.PositionControllerGains object>, vehicle_name='')[source]

Sets position controller gains for moveByPositionAsync. This function should only be called if the default position control PID gains need to be modified.

Parameters:
  • position_gains (PositionControllerGains) –

    • Correspond to the X, Y, Z axes.

    • Pass PositionControllerGains() to reset gains to default recommended values.

  • vehicle_name (str, optional) – Name of the multirotor to send this command to

setVelocityControllerGains(velocity_gains=<airsim.types.VelocityControllerGains object>, vehicle_name='')[source]
  • Sets velocity controller gains for moveByVelocityAsync().

  • This function should only be called if the default velocity control PID gains need to be modified.

  • Passing VelocityControllerGains() sets gains to default airsim values.

Parameters:
  • velocity_gains (VelocityControllerGains) –

    • Correspond to the world X, Y, Z axes.

    • Pass VelocityControllerGains() to reset gains to default recommended values.

    • Modifying velocity controller gains will have an affect on the behaviour of moveOnSplineAsync() and moveOnSplineVelConstraintsAsync(), as they both use velocity control to track the trajectory.

  • vehicle_name (str, optional) – Name of the multirotor to send this command to

takeoffAsync(timeout_sec=20, vehicle_name='')[source]

Takeoff vehicle to 3m above ground. Vehicle should not be moving when this API is used

Parameters:
  • timeout_sec (int, optional) – Timeout for the vehicle to reach desired altitude

  • vehicle_name (str, optional) – Name of the vehicle to send this command to

Returns:

future. call .join() to wait for method to finish. Example: client.METHOD().join()

Return type:

msgpackrpc.future.Future

class airsim.client.CarClient(ip='', port=41451, timeout_value=3600)[source]

Bases: VehicleClient, object

getCarControls(vehicle_name='')[source]
Parameters:

vehicle_name (str, optional) – Name of vehicle

Return type:

CarControls

getCarState(vehicle_name='')[source]

The position inside the returned CarState is in the frame of the vehicle’s starting point

Parameters:

vehicle_name (str, optional) – Name of vehicle

Return type:

CarState

setCarControls(controls, vehicle_name='')[source]

Control the car using throttle, steering, brake, etc.

Parameters:
  • controls (CarControls) – Struct containing control values

  • vehicle_name (str, optional) – Name of vehicle to be controlled

class airsim.types.AngleLevelControllerGains(roll_gains=<airsim.types.PIDGains object>, pitch_gains=<airsim.types.PIDGains object>, yaw_gains=<airsim.types.PIDGains object>)[source]

Struct to contain controller gains used by angle rate PID controller

roll_gains

kP, kI, kD for roll axis

Type:

PIDGains

pitch_gains

kP, kI, kD for pitch axis

Type:

PIDGains

yaw_gains

kP, kI, kD for yaw axis

Type:

PIDGains

to_lists()[source]
class airsim.types.AngleRateControllerGains(roll_gains=<airsim.types.PIDGains object>, pitch_gains=<airsim.types.PIDGains object>, yaw_gains=<airsim.types.PIDGains object>)[source]

Struct to contain controller gains used by angle level PID controller

roll_gains

kP, kI, kD for roll axis

Type:

PIDGains

pitch_gains

kP, kI, kD for pitch axis

Type:

PIDGains

yaw_gains

kP, kI, kD for yaw axis

Type:

PIDGains

to_lists()[source]
class airsim.types.BarometerData[source]
altitude = <Quaternionr> {   'w_val': 1.0,     'x_val': 0.0,     'y_val': 0.0,     'z_val': 0.0}
attribute_order = [('time_stamp', <class 'numpy.uint64'>), ('altitude', <class 'float'>), ('pressure', <class 'float'>), ('qnh', <class 'float'>)]
pressure = <Vector3r> {   'x_val': 0.0,     'y_val': 0.0,     'z_val': 0.0}
qnh = <Vector3r> {   'x_val': 0.0,     'y_val': 0.0,     'z_val': 0.0}
time_stamp = 0
class airsim.types.Box2D[source]
attribute_order = [('min', <class 'airsim.types.Vector2r'>), ('max', <class 'airsim.types.Vector2r'>)]
max = <Vector2r> {   'x_val': 0.0,     'y_val': 0.0}
min = <Vector2r> {   'x_val': 0.0,     'y_val': 0.0}
class airsim.types.Box3D[source]
attribute_order = [('min', <class 'airsim.types.Vector3r'>), ('max', <class 'airsim.types.Vector3r'>)]
max = <Vector3r> {   'x_val': 0.0,     'y_val': 0.0,     'z_val': 0.0}
min = <Vector3r> {   'x_val': 0.0,     'y_val': 0.0,     'z_val': 0.0}
class airsim.types.CameraInfo[source]
attribute_order = [('pose', <class 'airsim.types.Pose'>), ('fov', <class 'float'>), ('proj_mat', <class 'airsim.types.ProjectionMatrix'>)]
fov = -1
pose = <Pose> {   'orientation': <Quaternionr> {   'w_val': 1.0,     'x_val': 0.0,     'y_val': 0.0,     'z_val': 0.0},     'position': <Vector3r> {   'x_val': 0.0,     'y_val': 0.0,     'z_val': 0.0}}
proj_mat = <ProjectionMatrix> {   }
class airsim.types.CarControls(throttle=0, steering=0, brake=0, handbrake=False, is_manual_gear=False, manual_gear=0, gear_immediate=True)[source]
attribute_order = [('throttle', <class 'float'>), ('steering', <class 'float'>), ('brake', <class 'float'>), ('handbrake', <class 'bool'>), ('is_manual_gear', <class 'bool'>), ('manual_gear', <class 'int'>), ('gear_immediate', <class 'bool'>)]
brake = 0.0
gear_immediate = True
handbrake = False
is_manual_gear = False
manual_gear = 0
set_throttle(throttle_val, forward)[source]
steering = 0.0
throttle = 0.0
class airsim.types.CarState[source]
attribute_order = [('speed', <class 'float'>), ('gear', <class 'int'>), ('rpm', <class 'float'>), ('maxrpm', <class 'float'>), ('handbrake', <class 'bool'>), ('collision', <class 'airsim.types.CollisionInfo'>), ('kinematics_estimated', <class 'airsim.types.KinematicsState'>), ('timestamp', <class 'numpy.uint64'>)]
collision = <CollisionInfo> {   }
gear = 0
handbrake = False
kinematics_estimated = <KinematicsState> {   }
maxrpm = 0.0
rpm = 0.0
speed = 0.0
timestamp = 0
class airsim.types.CollisionInfo[source]
attribute_order = [('has_collided', <class 'bool'>), ('normal', <class 'airsim.types.Vector3r'>), ('impact_point', <class 'airsim.types.Vector3r'>), ('position', <class 'airsim.types.Vector3r'>), ('penetration_depth', <class 'float'>), ('time_stamp', <class 'numpy.uint64'>), ('object_name', <class 'str'>), ('object_id', <class 'int'>)]
has_collided = False
impact_point = <Vector3r> {   'x_val': 0.0,     'y_val': 0.0,     'z_val': 0.0}
normal = <Vector3r> {   'x_val': 0.0,     'y_val': 0.0,     'z_val': 0.0}
object_id = -1
object_name = ''
penetration_depth = 0.0
position = <Vector3r> {   'x_val': 0.0,     'y_val': 0.0,     'z_val': 0.0}
time_stamp = 0.0
class airsim.types.DetectionInfo[source]
attribute_order = [('name', <class 'str'>), ('geo_point', <class 'airsim.types.GeoPoint'>), ('box2D', <class 'airsim.types.Box2D'>), ('box3D', <class 'airsim.types.Box3D'>), ('relative_pose', <class 'airsim.types.Pose'>)]
box2D = <Box2D> {   }
box3D = <Box3D> {   }
geo_point = <GeoPoint> {   }
name = ''
relative_pose = <Pose> {   'orientation': <Quaternionr> {   'w_val': 1.0,     'x_val': 0.0,     'y_val': 0.0,     'z_val': 0.0},     'position': <Vector3r> {   'x_val': 0.0,     'y_val': 0.0,     'z_val': 0.0}}
class airsim.types.DistanceSensorData[source]
attribute_order = [('time_stamp', <class 'numpy.uint64'>), ('distance', <class 'float'>), ('min_distance', <class 'float'>), ('max_distance', <class 'float'>), ('relative_pose', <class 'airsim.types.Pose'>)]
distance = 0.0
max_distance = 0.0
min_distance = 0.0
relative_pose = <Pose> {   'orientation': <Quaternionr> {   'w_val': 1.0,     'x_val': 0.0,     'y_val': 0.0,     'z_val': 0.0},     'position': <Vector3r> {   'x_val': 0.0,     'y_val': 0.0,     'z_val': 0.0}}
time_stamp = 0
class airsim.types.DrivetrainType[source]
ForwardOnly = 1
MaxDegreeOfFreedom = 0
class airsim.types.EnvironmentState[source]
air_density = 0.0
air_pressure = 0.0
attribute_order = [('position', <class 'airsim.types.Vector3r'>), ('geo_point', <class 'airsim.types.GeoPoint'>), ('gravity', <class 'airsim.types.Vector3r'>), ('air_pressure', <class 'float'>), ('temperature', <class 'float'>), ('air_density', <class 'float'>)]
geo_point = <GeoPoint> {   }
gravity = <Vector3r> {   'x_val': 0.0,     'y_val': 0.0,     'z_val': 0.0}
position = <Vector3r> {   'x_val': 0.0,     'y_val': 0.0,     'z_val': 0.0}
temperature = 0.0
class airsim.types.GeoPoint[source]
altitude = 0.0
attribute_order = [('latitude', <class 'float'>), ('longitude', <class 'float'>), ('altitude', <class 'float'>)]
latitude = 0.0
longitude = 0.0
class airsim.types.GnssFixType[source]
GNSS_FIX_2D_FIX = 2
GNSS_FIX_3D_FIX = 3
GNSS_FIX_NO_FIX = 0
GNSS_FIX_TIME_ONLY = 1
class airsim.types.GnssReport[source]
attribute_order = [('geo_point', <class 'airsim.types.GeoPoint'>), ('eph', <class 'float'>), ('epv', <class 'float'>), ('velocity', <class 'airsim.types.Vector3r'>), ('fix_type', <class 'int'>), ('time_utc', <class 'numpy.uint64'>)]
eph = 0.0
epv = 0.0
fix_type = <GnssFixType> {   }
geo_point = <GeoPoint> {   }
time_utc = 0
velocity = <Vector3r> {   'x_val': 0.0,     'y_val': 0.0,     'z_val': 0.0}
class airsim.types.GpsData[source]
attribute_order = [('time_stamp', <class 'numpy.uint64'>), ('gnss', <class 'airsim.types.GnssReport'>), ('is_valid', <class 'bool'>)]
gnss = <GnssReport> {   }
is_valid = False
time_stamp = 0
class airsim.types.ImageRequest(camera_name, image_type, pixels_as_float=False, compress=True)[source]
attribute_order = [('camera_name', <class 'str'>), ('image_type', <class 'int'>), ('pixels_as_float', <class 'bool'>), ('compress', <class 'bool'>)]
camera_name = '0'
compress = False
image_type = 0
pixels_as_float = False
class airsim.types.ImageResponse[source]
attribute_order = [('image_data_uint8', <class 'numpy.ndarray'>), ('image_data_float', <class 'numpy.ndarray'>), ('camera_position', <class 'airsim.types.Vector3r'>), ('camera_name', <class 'str'>), ('camera_orientation', <class 'airsim.types.Quaternionr'>), ('time_stamp', <class 'numpy.uint64'>), ('message', <class 'str'>), ('pixels_as_float', <class 'bool'>), ('compress', <class 'bool'>), ('width', <class 'int'>), ('height', <class 'int'>), ('image_type', <class 'int'>)]
camera_name = ''
camera_orientation = <Quaternionr> {   'w_val': 1.0,     'x_val': 0.0,     'y_val': 0.0,     'z_val': 0.0}
camera_position = <Vector3r> {   'x_val': 0.0,     'y_val': 0.0,     'z_val': 0.0}
compress = True
height = 0
image_data_float = array([], dtype=float64)
image_data_uint8 = array([], dtype=uint8)
image_type = 0
message = ''
pixels_as_float = 0.0
time_stamp = 0
width = 0
class airsim.types.ImageType[source]
DepthPerspective = 2
DepthPlanar = 1
DepthVis = 3
DisparityNormalized = 4
Infrared = 7
OpticalFlow = 8
OpticalFlowVis = 9
Scene = 0
Segmentation = 5
SurfaceNormals = 6
class airsim.types.ImuData[source]
angular_velocity = <Vector3r> {   'x_val': 0.0,     'y_val': 0.0,     'z_val': 0.0}
attribute_order = [('time_stamp', <class 'numpy.uint64'>), ('orientation', <class 'airsim.types.Quaternionr'>), ('angular_velocity', <class 'airsim.types.Vector3r'>), ('linear_acceleration', <class 'airsim.types.Vector3r'>)]
linear_acceleration = <Vector3r> {   'x_val': 0.0,     'y_val': 0.0,     'z_val': 0.0}
orientation = <Quaternionr> {   'w_val': 1.0,     'x_val': 0.0,     'y_val': 0.0,     'z_val': 0.0}
time_stamp = 0
class airsim.types.KinematicsState[source]
angular_acceleration = <Vector3r> {   'x_val': 0.0,     'y_val': 0.0,     'z_val': 0.0}
angular_velocity = <Vector3r> {   'x_val': 0.0,     'y_val': 0.0,     'z_val': 0.0}
attribute_order = [('position', <class 'airsim.types.Vector3r'>), ('orientation', <class 'airsim.types.Quaternionr'>), ('linear_velocity', <class 'airsim.types.Vector3r'>), ('angular_velocity', <class 'airsim.types.Vector3r'>), ('linear_acceleration', <class 'airsim.types.Vector3r'>), ('angular_acceleration', <class 'airsim.types.Vector3r'>)]
linear_acceleration = <Vector3r> {   'x_val': 0.0,     'y_val': 0.0,     'z_val': 0.0}
linear_velocity = <Vector3r> {   'x_val': 0.0,     'y_val': 0.0,     'z_val': 0.0}
orientation = <Quaternionr> {   'w_val': 1.0,     'x_val': 0.0,     'y_val': 0.0,     'z_val': 0.0}
position = <Vector3r> {   'x_val': 0.0,     'y_val': 0.0,     'z_val': 0.0}
class airsim.types.LandedState[source]
Flying = 1
Landed = 0
class airsim.types.LidarData[source]
attribute_order = [('time_stamp', <class 'numpy.uint64'>), ('point_cloud', <class 'float'>), ('pose', <class 'airsim.types.Pose'>), ('segmentation', <class 'int'>)]
point_cloud = 0.0
pose = <Pose> {   'orientation': <Quaternionr> {   'w_val': 1.0,     'x_val': 0.0,     'y_val': 0.0,     'z_val': 0.0},     'position': <Vector3r> {   'x_val': 0.0,     'y_val': 0.0,     'z_val': 0.0}}
segmentation = 0
time_stamp = 0
class airsim.types.MagnetometerData[source]
attribute_order = [('time_stamp', <class 'numpy.uint64'>), ('magnetic_field_body', <class 'airsim.types.Vector3r'>), ('magnetic_field_covariance', <class 'float'>)]
magnetic_field_body = <Vector3r> {   'x_val': 0.0,     'y_val': 0.0,     'z_val': 0.0}
magnetic_field_covariance = 0.0
time_stamp = 0
class airsim.types.MeshPositionVertexBuffersResponse[source]
attribute_order = [('position', <class 'airsim.types.Vector3r'>), ('orientation', <class 'airsim.types.Quaternionr'>), ('vertices', <class 'float'>), ('indices', <class 'float'>), ('name', <class 'str'>)]
indices = 0.0
name = ''
orientation = <Quaternionr> {   'w_val': 1.0,     'x_val': 0.0,     'y_val': 0.0,     'z_val': 0.0}
position = <Vector3r> {   'x_val': 0.0,     'y_val': 0.0,     'z_val': 0.0}
vertices = 0.0
class airsim.types.MsgpackMixin[source]
attribute_order = []
classmethod from_msgpack(encoded)[source]
to_msgpack(*args, **kwargs)[source]
class airsim.types.MultirotorState[source]
attribute_order = [('collision', <class 'airsim.types.CollisionInfo'>), ('kinematics_estimated', <class 'airsim.types.KinematicsState'>), ('gps_location', <class 'airsim.types.GeoPoint'>), ('timestamp', <class 'numpy.uint64'>), ('landed_state', <class 'int'>), ('rc_data', <class 'airsim.types.RCData'>), ('ready', <class 'bool'>), ('ready_message', <class 'str'>), ('can_arm', <class 'bool'>)]
can_arm = False
collision = <CollisionInfo> {   }
gps_location = <GeoPoint> {   }
kinematics_estimated = <KinematicsState> {   }
landed_state = 0
rc_data = <RCData> {   'is_initialized': False,     'is_valid': False,     'pitch': 0.0,     'roll': 0.0,     'switch1': 0,     'switch2': 0,     'switch3': 0,     'switch4': 0,     'switch5': 0,     'switch6': 0,     'switch7': 0,     'switch8': 0,     'throttle': 0.0,     'timestamp': 0,     'yaw': 0.0}
ready = False
ready_message = ''
timestamp = 0
class airsim.types.PIDGains(kp, ki, kd)[source]

Struct to store values of PID gains. Used to transmit controller gain values while instantiating AngleLevel/AngleRate/Velocity/PositionControllerGains objects.

kP

Proportional gain

Type:

float

kI

Integrator gain

Type:

float

kD

Derivative gain

Type:

float

to_list()[source]
class airsim.types.Pose(position_val=None, orientation_val=None)[source]
attribute_order = [('position', <class 'airsim.types.Vector3r'>), ('orientation', <class 'airsim.types.Quaternionr'>)]
containsNan()[source]
static nanPose()[source]
orientation = <Quaternionr> {   'w_val': 1.0,     'x_val': 0.0,     'y_val': 0.0,     'z_val': 0.0}
position = <Vector3r> {   'x_val': 0.0,     'y_val': 0.0,     'z_val': 0.0}
class airsim.types.PositionControllerGains(x_gains=<airsim.types.PIDGains object>, y_gains=<airsim.types.PIDGains object>, z_gains=<airsim.types.PIDGains object>)[source]

Struct to contain controller gains used by position PID controller

x_gains

kP, kI, kD for X axis

Type:

PIDGains

y_gains

kP, kI, kD for Y axis

Type:

PIDGains

z_gains

kP, kI, kD for Z axis

Type:

PIDGains

to_lists()[source]
class airsim.types.ProjectionMatrix[source]
attribute_order = [('matrix', <class 'list'>)]
matrix = []
class airsim.types.Quaternionr(x_val=0.0, y_val=0.0, z_val=0.0, w_val=1.0)[source]
attribute_order = [('w_val', <class 'float'>), ('x_val', <class 'float'>), ('y_val', <class 'float'>), ('z_val', <class 'float'>)]
conjugate()[source]
containsNan()[source]
cross(other)[source]
dot(other)[source]
get_length()[source]
inverse()[source]
static nanQuaternionr()[source]
outer_product(other)[source]
rotate(other)[source]
sgn()[source]
star()[source]
to_numpy_array()[source]
w_val = 0.0
x_val = 0.0
y_val = 0.0
z_val = 0.0
class airsim.types.RCData(timestamp=0, pitch=0.0, roll=0.0, throttle=0.0, yaw=0.0, switch1=0, switch2=0, switch3=0, switch4=0, switch5=0, switch6=0, switch7=0, switch8=0, is_initialized=False, is_valid=False)[source]
attribute_order = [('timestamp', <class 'numpy.uint64'>), ('pitch', <class 'float'>), ('roll', <class 'float'>), ('throttle', <class 'float'>), ('yaw', <class 'float'>), ('switch1', <class 'int'>), ('switch2', <class 'int'>), ('switch3', <class 'int'>), ('switch4', <class 'int'>), ('switch5', <class 'int'>), ('switch6', <class 'int'>), ('switch7', <class 'int'>), ('switch8', <class 'int'>), ('is_initialized', <class 'bool'>), ('is_valid', <class 'bool'>)]
is_initialized = False
is_valid = False
pitch = 0.0
roll = 0.0
switch1 = 0
switch2 = 0
switch3 = 0
switch4 = 0
switch5 = 0
switch6 = 0
switch7 = 0
switch8 = 0
throttle = 0.0
timestamp = 0
yaw = 0.0
class airsim.types.RotorStates[source]
attribute_order = [('timestamp', <class 'numpy.uint64'>), ('rotors', <class 'list'>)]
rotors = []
timestamp = 0
class airsim.types.Vector2r(x_val=0.0, y_val=0.0)[source]
attribute_order = [('x_val', <class 'float'>), ('y_val', <class 'float'>)]
x_val = 0.0
y_val = 0.0
class airsim.types.Vector3r(x_val=0.0, y_val=0.0, z_val=0.0)[source]
attribute_order = [('x_val', <class 'float'>), ('y_val', <class 'float'>), ('z_val', <class 'float'>)]
containsNan()[source]
cross(other)[source]
distance_to(other)[source]
dot(other)[source]
get_length()[source]
static nanVector3r()[source]
to_Quaternionr()[source]
to_numpy_array()[source]
x_val = 0.0
y_val = 0.0
z_val = 0.0
class airsim.types.VelocityControllerGains(x_gains=<airsim.types.PIDGains object>, y_gains=<airsim.types.PIDGains object>, z_gains=<airsim.types.PIDGains object>)[source]

Struct to contain controller gains used by velocity PID controller

x_gains

kP, kI, kD for X axis

Type:

PIDGains

y_gains

kP, kI, kD for Y axis

Type:

PIDGains

z_gains

kP, kI, kD for Z axis

Type:

PIDGains

to_lists()[source]
class airsim.types.WeatherParameter[source]
Dust = 6
Enabled = 8
Fog = 7
MapleLeaf = 4
Rain = 0
RoadLeaf = 5
RoadSnow = 3
Roadwetness = 1
Snow = 2
class airsim.types.YawMode(is_rate=True, yaw_or_rate=0.0)[source]
attribute_order = [('is_rate', <class 'bool'>), ('yaw_or_rate', <class 'float'>)]
is_rate = True
yaw_or_rate = 0.0
airsim.utils.get_pfm_array(response)[source]
airsim.utils.get_public_fields(obj)[source]
airsim.utils.list_to_2d_float_array(flst, width, height)[source]
airsim.utils.read_pfm(file)[source]

Read a pfm file

airsim.utils.string_to_float_array(bstr)[source]
airsim.utils.string_to_uint8_array(bstr)[source]
airsim.utils.to_dict(obj)[source]
airsim.utils.to_eularian_angles(q)[source]
airsim.utils.to_quaternion(pitch, roll, yaw)[source]
airsim.utils.to_str(obj)[source]
airsim.utils.wait_key(message='')[source]

Wait for a key press on the console and return it.

airsim.utils.write_file(filename, bstr)[source]

Write binary data to file. Used for writing compressed PNG images

airsim.utils.write_pfm(file, image, scale=1)[source]

Write a pfm file

airsim.utils.write_png(filename, image)[source]

image must be numpy array H X W X channels