Colosseum API Reference
Colosseum.armDisarm
— FunctionArms || disarms vehicle
Args: arm (bool) True to arm, false to disarm the vehicle vehicle_name (str, optional) Name of the vehicle to send this command to
Returns: bool: Success
Colosseum.cancelLastTask
— FunctionCancel previous Async task
Args: vehicle_name (str, optional): Name of the vehicle
Colosseum.confirmConnection
— MethodChecks state of connection every 1 sec and reports it in Console so user can see the progress for connection.
Colosseum.getBarometerData
— FunctionArgs: barometername (str, optional): Name of Barometer to get data from, specified in settings.json vehiclename (str, optional): Name of vehicle to which the sensor corresponds to
Returns: BarometerData:
Colosseum.getCarControls
— FunctionArgs: vehicle_name (str, optional): Name of vehicle
Returns: CarControls:
Colosseum.getCarState
— FunctionThe position inside the returned CarState is in the frame of the vehicle's starting point
Args: vehicle_name (str, optional): Name of vehicle
Returns: CarState:
Colosseum.getDistanceSensorData
— FunctionArgs: distancesensorname (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
Returns: DistanceSensorData:
Colosseum.getGpsData
— FunctionArgs: gpsname (str, optional): Name of GPS to get data from, specified in settings.json vehiclename (str, optional): Name of vehicle to which the sensor corresponds to
Returns: GpsData:
Colosseum.getHomeGeoPoint
— FunctionGet the Home location of the vehicle
Args: vehicle_name (str, optional) Name of vehicle to get home location of
Returns: GeoPoint: Home location of the vehicle
Colosseum.getImuData
— FunctionArgs: imuname (str, optional): Name of IMU to get data from, specified in settings.json vehiclename (str, optional): Name of vehicle to which the sensor corresponds to
Returns: ImuData:
Colosseum.getLidarData
— FunctionArgs: lidarname (str, optional): Name of Lidar to get data from, specified in settings.json vehiclename (str, optional): Name of vehicle to which the sensor corresponds to
Returns: LidarData:
Colosseum.getMagnetometerData
— FunctionArgs: magnetometername (str, optional): Name of Magnetometer to get data from, specified in settings.json vehiclename (str, optional): Name of vehicle to which the sensor corresponds to
Returns: MagnetometerData:
Colosseum.getMinRequiredClientVersion
— MethodEnables || disables API control for vehicle corresponding to vehicle_name
Args: isenabled (bool) True to enable, false to disable API control vehiclename (str, optional) Name of the vehicle to send this command to
Colosseum.getMultirotorState
— FunctionThe position inside the returned MultirotorState is in the frame of the vehicle's starting point
Args: vehicle_name (str, optional): Vehicle to get the state of
Returns: MultirotorState:
Colosseum.getRotorStates
— FunctionUsed to obtain the current state of all a multirotor's rotors. The state includes the speeds, thrusts and torques for all rotors.
Args: vehicle_name (str, optional): Vehicle to get the rotor state of
Returns: RotorStates: Containing a timestamp and the speed, thrust and torque of all rotors.
Colosseum.getSettingsString
— MethodFetch the settings text being used by AirSim
Returns: str: Settings text in JSON format
Colosseum.goHomeAsync
— FunctionReturn vehicle to Home i.e. Launch location
Args: timeoutsec (int, optional): Timeout for the vehicle to reach desired altitude vehiclename (str, optional): Name of the vehicle to send this command to
Returns: msgpackrpc.future.Future: future. call .join() to wait for method to finish. Example: client.METHOD().join()
Colosseum.isApiControlEnabled
— FunctionReturns true if API control is established.
If false (which is functionault) then API calls would be ignored. After a successful call to enableApiControl
, isApiControlEnabled
should return true.
Args: vehicle_name (str, optional) Name of the vehicle
Returns: bool: If API control is enabled
Colosseum.isRecording
— MethodWhether Recording is running or not
Returns: bool: True if Recording, else false
Colosseum.landAsync
— FunctionLand the vehicle
Args: timeoutsec (int, optional): Timeout for the vehicle to land vehiclename (str, optional): Name of the vehicle to send this command to
Returns: msgpackrpc.future.Future: future. call .join() to wait for method to finish. Example: client.METHOD().join()
Colosseum.listVehicles
— MethodLists the names of current vehicles
Returns: list[str]: List containing names of all vehicles
Colosseum.moveByAngleRatesThrottleAsync
— FunctionDesired 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.
Args: rollrate (float): Desired roll rate, in radians / second pitchrate (float): Desired pitch rate, in radians / second yawrate (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 vehiclename (str, optional): Name of the multirotor to send this command to
Returns: msgpackrpc.future.Future: future. call .join() to wait for method to finish. Example: client.METHOD().join()
Colosseum.moveByAngleRatesZAsync
— Functionz 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.
Args: rollrate (float): Desired roll rate, in radians / second pitchrate (float): Desired pitch rate, in radians / second yawrate (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 vehiclename (str, optional): Name of the multirotor to send this command to
Returns: msgpackrpc.future.Future: future. call .join() to wait for method to finish. Example: client.METHOD().join()
Colosseum.moveByManualAsync
— Function- 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.
Args: vxmax (float): max velocity allowed in x direction vymax (float): max velocity allowed in y direction vzmax (float): max velocity allowed in z direction zmin (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) yawmode (YawMode): Specifies if vehicle should face at given angle (israte=false) or should be rotating around its axis at given rate (israte=True) vehiclename (str, optional): Name of the multirotor to send this command to Returns: msgpackrpc.future.Future: future. call .join() to wait for method to finish. Example: client.METHOD().join()
Colosseum.moveByMotorPWMsAsync
— Function- Directly control the motors using PWM values
Args: frontrightpwm (float): PWM value for the front right motor (between 0.0 to 1.0) rearleftpwm (float): PWM value for the rear left motor (between 0.0 to 1.0) frontleftpwm (float): PWM value for the front left motor (between 0.0 to 1.0) rearrightpwm (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: msgpackrpc.future.Future: future. call .join() to wait for method to finish. Example: client.METHOD().join()
Colosseum.moveByRollPitchYawThrottleAsync
— FunctionDesired 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.
Args: 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: msgpackrpc.future.Future: future. call .join() to wait for method to finish. Example: client.METHOD().join()
Colosseum.moveByRollPitchYawZAsync
— Functionz 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.
Args: 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: msgpackrpc.future.Future: future. call .join() to wait for method to finish. Example: client.METHOD().join()
Colosseum.moveByRollPitchYawrateThrottleAsync
— FunctionDesired 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.
Args: roll (float): Desired roll angle, in radians. pitch (float): Desired pitch angle, in radians. yawrate (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 vehiclename (str, optional): Name of the multirotor to send this command to
Returns: msgpackrpc.future.Future: future. call .join() to wait for method to finish. Example: client.METHOD().join()
Colosseum.moveByRollPitchYawrateZAsync
— Functionz 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.
Args: roll (float): Desired roll angle, in radians. pitch (float): Desired pitch angle, in radians. yawrate (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 vehiclename (str, optional): Name of the multirotor to send this command to
Returns: msgpackrpc.future.Future: future. call .join() to wait for method to finish. Example: client.METHOD().join()
Colosseum.moveByVelocityAsync
— FunctionArgs: 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): yawmode (YawMode, optional): vehiclename (str, optional): Name of the multirotor to send this command to
Returns: msgpackrpc.future.Future: future. call .join() to wait for method to finish. Example: client.METHOD().join()
Colosseum.moveByVelocityBodyFrameAsync
— FunctionArgs: 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): yawmode (YawMode, optional): vehiclename (str, optional): Name of the multirotor to send this command to
Returns: msgpackrpc.future.Future: future. call .join() to wait for method to finish. Example: client.METHOD().join()
Colosseum.moveByVelocityZBodyFrameAsync
— FunctionArgs: 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): yawmode (YawMode, optional): vehiclename (str, optional): Name of the multirotor to send this command to
Returns: msgpackrpc.future.Future: future. call .join() to wait for method to finish. Example: client.METHOD().join()
Colosseum.ping
— Methodping(c::AbstractVehicleClient)
If connection is established then this call will return true otherwise it will be blocked until timeout
Colosseum.reset
— Methodreset(c::AbstractVehicleClient)
Reset the vehicle to its original starting state
Note that you must call enableApiControl
and armDisarm
again after the call to reset
Colosseum.setAngleLevelControllerGains
— Function- 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.
Args: anglelevelgains (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
Colosseum.setAngleRateControllerGains
— Function- 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.
Args: anglerategains (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
Colosseum.setCarControls
— FunctionControl the car using throttle, steering, brake, etc.
Args: controls (CarControls): Struct containing control values vehicle_name (str, optional): Name of vehicle to be controlled
Colosseum.setPositionControllerGains
— FunctionSets position controller gains for moveByPositionAsync. This function should only be called if the default position control PID gains need to be modified.
Args: positiongains (PositionControllerGains): - Correspond to the X, Y, Z axes. - Pass PositionControllerGains() to reset gains to default recommended values. vehiclename (str, optional): Name of the multirotor to send this command to
Colosseum.setVelocityControllerGains
— Function- 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.
Args: velocitygains (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. vehiclename (str, optional): Name of the multirotor to send this command to
Colosseum.simAddDetectionFilterMeshName
— FunctionAdd mesh name to detect in wild card format
For example: simAddDetectionFilterMeshName("Car*") will detect all instance named "Car*"
Args: cameraname (str) Name of the camera, for backwards compatibility, ID numbers such as 0,1,etc. can also be used imagetype (ImageType) Type of image required meshname (str) mesh name in wild card format vehiclename (str, optional) Vehicle which the camera is associated with external (bool, optional) Whether the camera is an External Camera
Colosseum.simAddVehicle
— FunctionCreate vehicle at runtime
Args: vehiclename (str): Name of the vehicle being created vehicletype (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: bool: Whether vehicle was created
Colosseum.simClearDetectionMeshNames
— FunctionClear all mesh names from detection filter
Args: cameraname (str) Name of the camera, for backwards compatibility, ID numbers such as 0,1,etc. can also be used imagetype (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
Colosseum.simContinueForFrames
— MethodContinue (or resume if paused) the simulation for the specified number of frames, after which the simulation will be paused.
Args: frames (int) Frames to run the simulation for
Colosseum.simContinueForTime
— MethodContinue the simulation for the specified number of seconds
Args: seconds (float) Time to run the simulation for
Colosseum.simCreateVoxelGrid
— MethodConstruct and save a binvox-formatted voxel grid of environment
Args: position (Vector3r): Position around which voxel grid is centered in m x, y, 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: bool: True if output written to file successfully, else false
Colosseum.simDestroyObject
— MethodRemoves selected object from the world
Args: object_name (str) Name of object to be removed
Returns: bool: True if object is queued up for removal
Colosseum.simEnableWeather
— MethodEnable Weather effects. Needs to be called before using simSetWeatherParameter
API
Args: enable (bool) True to enable, false to disable
Colosseum.simFlushPersistentMarkers
— MethodClear any persistent markers - those plotted with setting is_persistent=True
in the APIs below
Colosseum.simGetCameraInfo
— FunctionGet details about the camera
Args: cameraname (str) Name of the camera, for backwards compatibility, ID numbers such as 0,1,etc. can also be used vehiclename (str, optional) Vehicle which the camera is associated with external (bool, optional) Whether the camera is an External Camera
Returns: CameraInfo:
Colosseum.simGetCollisionInfo
— FunctionArgs: vehicle_name (str, optional) Name of the Vehicle to get the info of
Returns: CollisionInfo:
Colosseum.simGetDetections
— FunctionGet current detections
Args: cameraname (str) Name of the camera, for backwards compatibility, ID numbers such as 0,1,etc. can also be used imagetype (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
Colosseum.simGetDistortionParams
— FunctionGet camera distortion parameters
Args: cameraname (str) Name of the camera, for backwards compatibility, ID numbers such as 0,1,etc. can also be used vehiclename (str, optional) Vehicle which the camera is associated with external (bool, optional) Whether the camera is an External Camera
Returns: List (float) List of distortion parameter values corresponding to K1, K2, K3, P1, P2 respectively.
Colosseum.simGetGroundTruthEnvironment
— FunctionGet ground truth environment state
The position inside the returned EnvironmentState is in the frame of the vehicle's starting point
Args: vehicle_name (str, optional): Name of the vehicle
Returns: EnvironmentState: Ground truth environment state
Colosseum.simGetGroundTruthKinematics
— FunctionGet Ground truth kinematics of the vehiclevehicle_name=""
The position inside the returned KinematicsState is in the frame of the vehicle's starting point
Args: vehicle_name (str, optional): Name of the vehicle
Returns: KinematicsState: Ground truth of the vehicle
Colosseum.simGetImage
— FunctionGet 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/imageapis/ for details Args: cameraname (str) Name of the camera, for backwards compatibility, ID numbers such as 0,1,etc. can also be used imagetype (ImageType) Type of image required vehiclename (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
Colosseum.simGetImages
— FunctionGet multiple images
See https://microsoft.github.io/AirSim/image_apis/ for details and examples
Args: 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
Returns: list[ImageResponse]:
Colosseum.simGetLidarSegmentation
— FunctionNOTE: Deprecated API, use getLidarData()
API instead Returns Segmentation ID of each point's collided object in the last Lidar update
Args: lidarname (str, optional): Name of Lidar sensor vehiclename (str, optional): Name of the vehicle wth the sensor
Returns: list[int]: Segmentation IDs of the objects
Colosseum.simGetMeshPositionVertexBuffers
— MethodReturns the static meshes that make up the scene
See https://microsoft.github.io/AirSim/meshes/ for details and how to use this
Returns: list[MeshPositionVertexBuffersResponse]:
Colosseum.simGetObjectPose
— MethodThe position inside the returned Pose is in the world frame
Args: object_name (str) Object to get the Pose of
Returns: Pose:
Colosseum.simGetObjectScale
— MethodGets scale of an object in the world
Args: object_name (str) Object to get the scale of
Returns: airsim.Vector3r: Scale
Colosseum.simGetSegmentationObjectID
— MethodReturns 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
Args: mesh_name (str) Name of the mesh to get the ID of
Colosseum.simGetVehiclePose
— FunctionThe position inside the returned Pose is in the frame of the vehicle's starting point
Args: vehicle_name (str, optional) Name of the vehicle to get the Pose of
Returns: Pose:
Colosseum.simGetWorldExtents
— MethodReturns a list of GeoPoints representing the minimum and maximum extents of the world
Returns: list[GeoPoint]
Colosseum.simIsPause
— MethodReturns true if the simulation is paused
Returns: bool: If the simulation is paused
Colosseum.simListAssets
— MethodLists all the assets present in the Asset Registry
Returns: list[str]: Names of all the assets
Colosseum.simListSceneObjects
— FunctionLists the objects present in the environment
end
functionault behaviour is to list all objects, regex can be used to return smaller list of matching objects || actors
Args:
name_regex (str, optional) String to match actor names against, e.g. "Cylinder.*"
Returns:
list[str]: List containing all the names
Colosseum.simLoadLevel
— MethodLoads a level specified by its name
Args: level_name (str) Name of the level to load
Returns: bool: True if the level was successfully loaded
Colosseum.simPause
— MethodPauses simulation
Args: is_paused (bool) True to pause the simulation, false to release
Colosseum.simPlotArrows
— FunctionPlots a list of arrows in World NED frame, defined from pointsstart[0] to pointsend[0], pointsstart[1] to pointsend[1], ... , pointsstart[n-1] to pointsend[n-1]
Args: pointsstart (list[Vector3r]): List of 3D start positions of arrow start positions, specified as Vector3r objects pointsend (list[Vector3r]): List of 3D end positions of arrow start positions, specified as Vector3r objects colorrgba (list, optional): desired RGBA values from 0.0 to 1.0 thickness (float, optional): Thickness of line arrowsize (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.
Colosseum.simPlotLineList
— FunctionPlots 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]
Args: points (list[Vector3r]): List of 3D locations of line start and end points, specified as Vector3r objects. Must be even colorrgba (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 ispersistent (bool, optional): If set to True, the desired object will be plotted for infinite time.
Colosseum.simPlotLineStrip
— FunctionPlots 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]
Args: points (list[Vector3r]): List of 3D locations of line start and end points, specified as Vector3r objects colorrgba (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 ispersistent (bool, optional): If set to True, the desired object will be plotted for infinite time.
Colosseum.simPlotPoints
— FunctionPlot a list of 3D points in World NED frame
Args: points (list[Vector3r]): List of Vector3r objects colorrgba (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 ispersistent (bool, optional): If set to True, the desired object will be plotted for infinite time.
Colosseum.simPlotStrings
— FunctionPlots a list of strings at desired positions in World NED frame.
Args: 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
Colosseum.simPlotTransforms
— FunctionPlots a list of transforms in World NED frame.
Args: 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.
Colosseum.simPlotTransformsWithNames
— FunctionPlots a list of transforms with their names in World NED frame.
Args: 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 tfscale (float, optional): Length of transforms' axes tfthickness (float, optional): Thickness of transforms' axes textscale (float, optional): Font scale of transform name textcolor_rgba (list, optional): desired RGBA values from 0.0 to 1.0 for the transform name duration (float, optional): Duration (seconds) to plot for
Colosseum.simPrintLogMessage
— FunctionPrints the specified message in the simulator's window.
If messageparam 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 messageparam 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.
Args: 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
Colosseum.simRunConsoleCommand
— MethodAllows 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!
Args: command ([string]) Desired Unreal Engine Console command to run
Returns: [bool]: Success
Colosseum.simSetCameraFov
— Function- Control the field of view of a selected camera
Args: cameraname (str) Name of the camera to be controlled fovdegrees (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
Colosseum.simSetCameraPose
— Function- Control the pose of a selected camera
Args: cameraname (str) Name of the camera to be controlled pose (Pose) Pose representing the desired position and orientation of the camera vehiclename (str, optional) Name of vehicle which the camera corresponds to external (bool, optional) Whether the camera is an External Camera
Colosseum.simSetDetectionFilterRadius
— FunctionSet detection radius for all cameras
Args: cameraname (str) Name of the camera, for backwards compatibility, ID numbers such as 0,1,etc. can also be used imagetype (ImageType) Type of image required radiuscm (int) Radius in [cm] vehiclename (str, optional) Vehicle which the camera is associated with external (bool, optional) Whether the camera is an External Camera
Colosseum.simSetDistortionParam
— FunctionSet single camera distortion parameter
Args: cameraname (str) Name of the camera, for backwards compatibility, ID numbers such as 0,1,etc. can also be used paramname (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
Colosseum.simSetDistortionParams
— FunctionSet camera distortion parameters
Args: cameraname (str) Name of the camera, for backwards compatibility, ID numbers such as 0,1,etc. can also be used distortionparams (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
Colosseum.simSetExtForce
— MethodSet arbitrary external forces, in World frame, NED direction. Can be used for implementing simple payloads.
Args: ext_force (Vector3r): Force, in World frame, NED direction, in N
Colosseum.simSetKinematics
— FunctionSet 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
Args: state (KinematicsState): Desired Pose pf the vehicle ignorecollision (bool): Whether to ignore any collision or not vehiclename (str, optional): Name of the vehicle to move
Colosseum.simSetLightIntensity
— MethodChange intensity of named light
Args: light_name (String) Name of light to change intensity (Real) New intensity value
Returns: bool: True if successful, otherwise false
Colosseum.simSetObjectMaterial
— FunctionRuntime Swap Texture API See https://microsoft.github.io/AirSim/retexturing/ for details Args: objectname (str) name of object to set material for materialname (str) name of material to set for object component_id (int, optional) : index of material elements
Returns: bool: True if material was set
Colosseum.simSetObjectMaterialFromTexture
— FunctionRuntime Swap Texture API See https://microsoft.github.io/AirSim/retexturing/ for details Args: objectname (str) name of object to set material for texturepath (str) path to texture to set for object component_id (int, optional) : index of material elements
Returns: bool: True if material was set
Colosseum.simSetObjectPose
— FunctionSet the pose of the object(actor) in the environment
The specified actor must have Mobility set to movable, otherwise there will be unend
functionined 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
Args:
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:
bool: If the move was successful
Colosseum.simSetObjectScale
— MethodSets scale of an object in the world
Args: objectname (str) Object to set the scale of scalevector (airsim.Vector3r) Desired scale of object
Returns: bool: True if scale change was successful
Colosseum.simSetSegmentationObjectID
— FunctionSet segmentation ID for specific objects
See https://microsoft.github.io/AirSim/image_apis/#segmentation for details
Args: meshname (str) Name of the mesh to set the ID of (supports regex) objectid (int) Object ID to be set, range 0-255
RBG values for IDs can be seen at https://microsoft.github.io/AirSim/seg_rgbs.txt
is_name_regex (bool, optional) Whether the mesh name is a regex
Returns: bool: If the mesh was found
Colosseum.simSetTimeOfDay
— FunctionControl 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
Args: isenabled (bool) True to enable time-of-day effect, false to reset the position to original startdatetime (str, optional) Date & Time in %Y-%m-%d %H:%M:%S format, e.g. 2018-02-12 15:20:00
isstartdatetimedst (bool, optional) True to adjust for Daylight Savings Time celestialclockspeed (float, optional) Run celestial clock faster || 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 updateintervalsecs (float, optional) Interval to update the Sun's position movesun (bool, optional) Whether || not to move the Sun
Colosseum.simSetTraceLine
— FunctionModify the color and thickness of the line when Tracing is enabled
Tracing can be enabled by pressing T in the Editor || setting EnableTrace
to True
in the Vehicle Settings
Args: colorrgba (list) desired RGBA values from 0.0 to 1.0 thickness (float, optional) Thickness of the line vehiclename (string, optional) Name of the vehicle to set Trace line values for
Colosseum.simSetVehiclePose
— FunctionSet 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
Args: pose (Pose) Desired Pose pf the vehicle ignorecollision (bool) Whether to ignore any collision || not vehiclename (str, optional) Name of the vehicle to move
Colosseum.simSetWeatherParameter
— MethodEnable various weather effects
Args: param (WeatherParameter) Weather effect to be enabled val (float) Intensity of the effect, Range 0-1
Colosseum.simSetWind
— MethodSet simulated wind, in World frame, NED direction, m/s
Args: wind (Vector3r): Wind, in World frame, NED direction, in m/s
Colosseum.simSpawnObject
— FunctionSpawned selected object in the world
Args: objectname (str) Desired name of new object assetname (str) Name of asset(mesh) in the project database pose (airsim.Pose) Desired pose of object scale (airsim.Vector3r) Desired scale of object physicsenabled (bool, optional) Whether to enable physics for the object isblueprint (bool, optional) Whether to spawn a blueprint || an actor
Returns: str: Name of spawned object, in case it had to be modified
Colosseum.simSwapTextures
— FunctionRuntime Swap Texture API
See https://microsoft.github.io/AirSim/retexturing/ for details
Args: tags (str) string of "," || ", " 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[str]: List of objects which matched the provided tags and had the texture swap perfomed
Colosseum.simTestLineOfSightBetweenPoints
— MethodReturns whether the target point is visible from the perspective of the source point
Args: point1 (GeoPoint) source point point2 (GeoPoint) target point
Returns: [bool]: Success
Colosseum.simTestLineOfSightToPoint
— FunctionReturns whether the target point is visible from the perspective of the inputted vehicle
Args: point (GeoPoint) target point vehicle_name (str, optional) Name of vehicle
Returns: [bool]: Success
Colosseum.startRecording
— MethodStart Recording
Recording will be done according to the settings
Colosseum.stopRecording
— MethodStop Recording
Colosseum.takeoffAsync
— FunctionTakeoff vehicle to 3m above ground. Vehicle should not be moving when this API is used
Args: timeoutsec (int, optional): Timeout for the vehicle to reach desired altitude vehiclename (str, optional): Name of the vehicle to send this command to
Returns: msgpackrpc.future.Future: future. call .join() to wait for method to finish. Example: client.METHOD().join()