airsimneurips¶
This page documents airsimneurips, the python package to be used for
Game
of Drones: A NeurIPS 2019 Competition.
Please see the quick API overview in the github
readme
-
class
airsimneurips.client.
MultirotorClient
(ip='127.0.0.1', port=41451, timeout_value=3600)¶ -
-
arm
(vehicle_name='')¶ -
Arms vehicle corresponding to vehicle_name
-
cancelLastTask
(vehicle_name='')¶
-
clearTrajectory
(vehicle_name='')¶ -
Clears, and stops following the current trajectory (see moveOnSpline() or moveOnSplineVelConstraintsAsyn,c if any.
- Parameters
-
vehicle_name (str, optional) – Name of the multirotor to send this command to
- Returns
-
Description
- Return type
-
TYPE
-
confirmConnection
()¶ -
Checks state of connection every 1 sec and reports it in Console so user can see the progress for connection.
-
disableApiControl
(vehicle_name='')¶ -
Disables API control for vehicle with name vehicle_name
-
disarm
(vehicle_name='')¶ -
Disarms vehicle corresponding to vehicle_name.
-
enableApiControl
(vehicle_name='')¶ -
Enables API control for vehicle with name vehicle_name
-
getMultirotorState
(vehicle_name='') → airsimneurips.types.MultirotorState¶ -
- Parameters
-
vehicle_name (str, optional) – Name of the multirotor to send this command to
- Returns
-
Description
- Return type
-
goHomeAsync
(timeout_sec=3e+38, vehicle_name='')¶
-
hoverAsync
(vehicle_name='')¶
-
isApiControlEnabled
(vehicle_name='')¶ -
Returns true if API control is established. If false (which is default) then API calls would be ignored. After a successful call to enableApiControl, the isApiControlEnabled should return true.
-
landAsync
(timeout_sec=60, vehicle_name='')¶
-
moveByAngleRatesThrottleAsync
(roll_rate, pitch_rate, yaw_rate, throttle, duration, vehicle_name='')¶ -
-
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='')¶ -
-
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
-
-
moveByRollPitchYawThrottleAsync
(roll, pitch, yaw, throttle, duration, vehicle_name='')¶ -
-
Desired throttle is between 0.0 to 1.0
-
Roll angle, pitch angle, and yaw angle 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.
-
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='')¶ -
-
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='')¶ -
-
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='')¶ -
-
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='')¶ -
- 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) – Description
-
yaw_mode (YawMode, optional) – Description
-
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='')¶ -
- Parameters
-
-
vx (float) – desired velocity in world (NED) X axis
-
vy (float) – desired velocity in world (NED) Y axis
-
z (float) – desired altitude in world (NED) Z axis
-
duration (float) – Desired amount of time (seconds), to send this command for
-
drivetrain (DrivetrainType, optional) – Description
-
yaw_mode (YawMode, optional) – Description
-
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
-
moveByYawRateAsync
(yaw_rate, duration, vehicle_name='')¶
-
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='')¶ -
- Parameters
-
-
path (TYPE) – Description
-
velocity (TYPE) – Description
-
timeout_sec (float, optional) – Description
-
drivetrain (TYPE, optional) – Description
-
yaw_mode (TYPE, optional) – Description
-
lookahead (TYPE, optional) – Description
-
adaptive_lookahead (int, optional) – Description
-
vehicle_name (str, optional) – Name of the multirotor to send this command to
-
- Returns
-
Description
- Return type
-
TYPE
-
moveOnSplineAsync
(waypoints, vel_max=15.0, acc_max=7.5, add_position_constraint=True, add_velocity_constraint=True, add_acceleration_constraint=False, viz_traj=True, viz_traj_color_rgba=[1.0, 0.0, 0.0, 1.0], replan_from_lookahead=True, replan_lookahead_sec=1.0, vehicle_name='')¶ -
-
Fits a minimum jerk trajectory to the list of given 3D waypoints (specified by the waypoints parameter).
-
Uses ETHZ-ASL’s mav_trajectory_generation as the trajectory planning backend.
-
Tracks the references positions and velocities using a pure pursuit tracking controller.
-
The gains of the pure pursuit tracking controller are set by setTrajectoryTrackerGains.
-
Reference yaws are allocated along the tangent of the trajectory. Hence the drone will always look at the direction along which it is flying, behaving like a 3D car.
-
Note: setTrajectoryTrackerGains() must be called once before calling moveOnSpline()
- Parameters
-
-
-
List of 3D waypoints, defined in local NED frame of the vehicle to track.
-
-
vel_max (float, optional) –
-
Maximum magnitude of velocity along trajectory
-
-
acc_max (float, optional) –
-
Maximum magnitude of acceleration along trajectory
-
-
add_position_constraint (bool, optional) –
-
Add a start constraint at current position, so that the planned trajectory is smooth if the drone is already moving.
-
If replan_from_lookahead is False, and add_position_constraint is False, trajectory starts from the first element of the “waypoints” list param.
-
If replan_from_lookahead is False, and add_position_constraint is True, a position constraint is added at current odometry, and so the trajectory starts from current position.
-
If replan_from_lookahead is True, a position constraint trajectory is always added at look-ahead point regardless of the value of “add_position_constraint”, and so the trajectory starts from the lookahead point.
-
See below for the definition of “look-ahead point”.
-
-
add_velocity_constraint (bool, optional) –
-
Should only be set to True if add_position_constraint is True.
-
If replan_from_lookahead is True, a velocity constraint is added at current odometry.
-
If replan_from_lookahead is True, a velocity constraint is added at lookahead point.
-
-
add_acceleration_constraint (bool, optional) –
-
Should only be set to True if add_velocity_constraint (and therefore, add_position_constraint) is True.
-
If replan_from_lookahead is True, an acceleration constraint is added at current odometry.
-
If replan_from_lookahead is True, an acceleration constraint is added at lookahead point.
-
-
viz_traj (bool, optional) –
-
set this to True to visualize trajectory in unreal window.
-
Note that visualization would appear in the FPV image, so this should only be used for debugging.
-
-
viz_traj_color_rgba (list, optional) –
-
list of 4 floats from 0.0 to 1.0 that determines RGBA value of trajectory visualization.
-
Example: viz_traj_color_rgba=[1.0, 0.0, 0.0, 1.0] corresponds to Red
-
-
replan_from_lookahead (bool, optional) –
-
If this is set to true, the trajectory will start from the “look-ahead point” associated with the trajectory the drone is currently following.
-
The lookahead point is defined by the value of the replan_lookahead_sec paramater sent in the previous call to moveOnSpline.
-
-
replan_lookahead_sec (float, optional) –
-
Defines the lookahead point by sampling the current trajectory replan_lookahead_sec number of seconds ahead.
-
If replan_from_lookahead is passed as True in the next call to moveOnSpline, the next call’s trajectory will start from the lookahead point defined by the current call’s replan_lookahead_sec
-
-
vehicle_name (str, optional) –
-
Name of the multirotor to send this command to
-
-
- Returns
-
Success
- Return type
-
-
moveOnSplineVelConstraintsAsync
(waypoints, velocity_constraints, vel_max=15.0, acc_max=7.5, add_position_constraint=True, add_velocity_constraint=True, add_acceleration_constraint=False, viz_traj=True, viz_traj_color_rgba=[1.0, 0.0, 0.0, 0.4], replan_from_lookahead=True, replan_lookahead_sec=1.0, vehicle_name='')¶ -
-
Fits a minimum jerk trajectory to the list of given 3D waypoints (specified by the waypoints parameter).
-
Also adds corresponding 3D velocity vector constraints (specified by the velocity_constraints parameter).
-
Uses ETHZ-ASL’s mav_trajectory_generation as the trajectory planning backend.
-
Tracks the references positions and velocities using a pure pursuit tracking controller.
-
The gains of the pure pursuit tracking controller are set by setTrajectoryTrackerGains.
-
Reference yaws are allocated along the tangent of the trajectory. Hence the drone will always look at the direction along which it is flying, behaving like a 3D car.
-
Reference yaws are allocated along the tangent of the trajectory.
-
Note: setTrajectoryTrackerGains() must be called once before calling moveOnSpline()
- Parameters
-
-
-
List of 3D waypoints, defined in local NED frame of the vehicle to track.
-
-
velocity_constraints (list[Vector3r]) –
-
List of 3D velocity vector constraints, defined in local NED frame of the vehicle to track.
-
-
vel_max (float, optional) –
-
Maximum magnitude of velocity along trajectory
-
-
acc_max (float, optional) –
-
Maximum magnitude of acceleration along trajectory (-) –
-
add_position_constraint (bool, optional) –
-
Add a start constraint at current position, so that the planned trajectory is smooth if the drone is already moving.
-
If replan_from_lookahead is False, and add_position_constraint is False, trajectory starts from the first element of the “waypoints” list param.
-
If replan_from_lookahead is False, and add_position_constraint is True, a position constraint is added at current odometry, and so the trajectory starts from current position.
-
If replan_from_lookahead is True, a position constraint trajectory is always added at look-ahead point regardless of the value of “add_position_constraint”, and so the trajectory starts from the lookahead point.
-
See below for the definition of “look-ahead point”.
-
-
add_velocity_constraint (bool, optional) –
-
Should only be set to True if add_position_constraint is True.
-
If replan_from_lookahead is True, a velocity constraint is added at current odometry.
-
If replan_from_lookahead is True, a velocity constraint is added at lookahead point.
-
-
add_acceleration_constraint (bool, optional) –
-
Should only be set to True if add_velocity_constraint (and therefore, add_position_constraint) is True.
-
If replan_from_lookahead is True, an acceleration constraint is added at current odometry.
-
If replan_from_lookahead is True, an acceleration constraint is added at lookahead point.
-
-
viz_traj (bool, optional) –
-
set this to True to visualize trajectory in unreal window.
-
Note that visualization would appear in the FPV image, so this should only be used for debugging.
-
-
viz_traj_color_rgba (list, optional) –
-
list of 4 floats from 0.0 to 1.0 that determines RGBA value of trajectory visualization.
-
Example: viz_traj_color_rgba=[1.0, 0.0, 0.0, 1.0] corresponds to Red
-
-
replan_from_lookahead (bool, optional) –
-
If this is set to true, the trajectory will start from the “look-ahead point” associated with the trajectory the drone is currently following.
-
The lookahead point is defined by the value of the replan_lookahead_sec paramater sent in the previous call to moveOnSpline.
-
-
replan_lookahead_sec (float, optional) –
-
Defines the lookahead point by sampling the current trajectory replan_lookahead_sec number of seconds ahead.
-
If replan_from_lookahead is passed as True in the next call to moveOnSpline, the next call’s trajectory will start from the lookahead point defined by the current call’s replan_lookahead_sec
-
-
vehicle_name (str, optional) –
-
Name of the multirotor to send this command to
-
-
- Returns
-
Success
- Return type
-
-
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='')¶ -
- Parameters
-
-
x (float) – Description
-
y (float) – Description
-
z (float) – Description
-
velocity (float) – Description
-
timeout_sec (float, optional) – Description
-
drivetrain (DrivetrainType, optional) – Description
-
yaw_mode (YawMode, optional) – Description
-
lookahead (float, optional) – Description
-
adaptive_lookahead (int, optional) – Description
-
vehicle_name (str, optional) – Name of the multirotor to send this command to
-
- Returns
-
Success
- Return type
-
moveToYawAsync
(yaw, timeout_sec=3e+38, margin=5, vehicle_name='')¶
-
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='')¶ -
- Parameters
-
-
z (float) – Description
-
velocity (float) – Description
-
timeout_sec (float, optional) – Description
-
yaw_mode (YawMode, optional) – Description
-
lookahead (float, optional) – Description
-
adaptive_lookahead (int, optional) – Description
-
vehicle_name (str, optional) – Name of the multirotor to send this command to
-
- Returns
-
Success
- Return type
-
ping
()¶ -
If connection is established then this call will return true otherwise it will be blocked until timeout. :returns: True if ping was succesfull :rtype: bool
-
plot_transform
(pose_list, vehicle_name='')¶ -
Plots a transform for a requested list of poses
-
reset
()¶ -
This resets the vehicle to its original starting state. Note that you must call enableApiControl() and arm() again after calling reset.
-
setAngleLevelControllerGains
(angle_level_gains=<airsimneurips.types.AngleLevelControllerGains object>, vehicle_name='')¶ -
-
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() and moveOnSpline*() APIs.
-
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=<airsimneurips.types.AngleRateControllerGains object>, vehicle_name='')¶ -
-
- 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=<airsimneurips.types.PositionControllerGains object>, vehicle_name='')¶ -
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
-
-
setTrajectoryTrackerGains
(gains=<airsimneurips.types.TrajectoryTrackerGains object>, vehicle_name='')¶ -
-
Sets trajectory tracker gains for moveOnSplineAsync, moveOnSplineVelConstraintsAsync.
-
Must be called once before either of the moveOnSpline*() APIs is called
- Parameters
-
-
gains (TrajectoryTrackerGains) – Pass TrajectoryTrackerGains() to set default values. Look at TrajectoryTrackerGains to set custom gains
-
vehicle_name (str, optional) – Name of the multirotor to send this command to
-
-
-
setVelocityControllerGains
(velocity_gains=<airsimneurips.types.VelocityControllerGains object>, vehicle_name='')¶ -
-
Sets velocity controller gains for moveByVelocityAsync().
-
This function should only be called if the default velocity control PID gains need to be modified.
-
- Modifying the velocity controller gains will have an effect on the trajectory tracking behavior of moveOnSpline*() APIs,
-
as moveOnSpline*() APIs use a controller on the lines of the pure-pursuit approach, which is tracking the reference position and velocities of the reference trajectories, while minimizing cross-track errors in both position and velocity state, by sending velocity commands (via moveByVelocityAsync()) in the backend. If you change this, it might be worth playing with the gains of moveOnSpline() by using setTrajectoryTrackerGains()
-
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
-
-
-
simContinueForTime
(duration)¶ -
- Parameters
-
duration (float) – Unpauses simulator if paused, runs it for desired duration (seconds), then pauses it.
-
simDisableRaceLog
()¶ -
Disables race log
-
simGetCameraInfo
(camera_name, vehicle_name='')¶ -
- Parameters
-
-
camera_name (TYPE) – Description
-
vehicle_name (str, optional) – Name of the multirotor to send this command to
-
- Returns
-
Description
- Return type
-
simGetCollisionInfo
(vehicle_name='')¶ -
- Parameters
-
vehicle_name (str, optional) – Name of the multirotor to send this command to
- Returns
-
Description
- Return type
-
simGetGroundTruthKinematics
(vehicle_name='') → airsimneurips.types.KinematicsState¶ -
- Parameters
-
vehicle_name (str, optional) – Name of the multirotor to send this command to
- Returns
-
Description
- Return type
-
TYPE
-
simGetImage
(camera_name, image_type, vehicle_name='')¶
-
simGetImages
(requests, vehicle_name='')¶ -
- Parameters
-
-
requests (ImageRequest) – Description
-
vehicle_name (str) – Name of the multirotor to send this command to
-
- Returns
-
Description
- Return type
-
TYPE
-
simGetLastGatePassed
(vehicle_name)¶
-
simGetNominalGateInnerDimensions
()¶ -
-
Return the dimensions of the drone racing gate cavity, with scale (width=1.0, thickness=1.0, height=1.0)
-
Use this API in conjunction with simGetObjectScale(), simSetObjectScale(), simSetObjectPose() to generate arbitrary sized checkered gates with arbitrary poses.
- Returns
-
width, thickness, height of the gate inner cavity in meters. See https://github.com/microsoft/AirSim-NeurIPS2019-Drone-Racing/issues/28 for gate coordinate system
- Return type
-
-
simGetNominalGateOuterDimensions
()¶ -
-
Return the outer dimensions of the drone racing gate, with scale (width=1.0, thickness=1.0, height=1.0)
-
Use this API in conjunction with simGetObjectScale(), simSetObjectScale(), simSetObjectPose() to generate arbitrary sized checkered gates with arbitrary poses.
- Returns
-
width, thickness, height of the gate inner cavity in meters. See https://github.com/microsoft/AirSim-NeurIPS2019-Drone-Racing/issues/28 for gate coordinate system
- Return type
-
-
simGetObjectPose
(object_name)¶ -
Returns true pose for tier 1 races Returns noisy pose for tier 2 and 3 races
-
simGetObjectScale
(object_name)¶
-
simGetSegmentationObjectID
(mesh_name)¶
-
simGetVehiclePose
(vehicle_name='')¶
-
simIsRacerDisqualified
(vehicle_name)¶
-
simListSceneObjects
(name_regex='.*')¶ -
Returns list of all objects in the scene
- Parameters
-
name_regex (str, optional) – Description
- Returns
-
List of all objects in the scene
- Return type
-
List[strings]
-
simLoadLevel
(level_name)¶ -
Loads desired level
- Parameters
-
level_name (str) – Description
- Returns
-
Description
- Return type
-
TYPE
-
simPause
()¶ -
Pauses sim
-
simPrintLogMessage
(message, message_param='', severity=0)¶ -
Prints the specified message in the simulator’s window. | If message_param is also supplied then its 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.
-
simResetRace
()¶ -
Resets a current race: moves players to start positions, timer and penalties reset.
-
simSetCameraOrientation
(camera_name, orientation, vehicle_name='')¶ -
Sets camera’s orientation to desired quaternion
- Parameters
-
-
camera_name (str) – Description
-
orientation (Quaternionr) – Desired orientation quaternion
-
vehicle_name (str, optional) – Name of the multirotor to send this command to
-
-
simSetObjectPose
(object_name, pose, teleport=True)¶
-
simSetObjectScale
(object_name, scale_vector)¶
-
simSetSegmentationObjectID
(mesh_name, object_id, is_name_regex=False)¶
-
simSetVehiclePose
(pose, ignore_collison, vehicle_name='')¶ -
- Parameters
-
-
pose (TYPE) – Description
-
ignore_collison (TYPE) – Description
-
vehicle_name (str, optional) – Name of the multirotor to send this command to
-
-
simStartRace
(tier=1)¶ -
Starts an instance of a race in your given level, if valid.
-
simUnPause
()¶ -
Resumes / unpauses sim
-
takeoffAsync
(timeout_sec=20, vehicle_name='')¶
-
waitOnLastTask
(timeout_sec=nan)¶ -
- Parameters
-
timeout_sec (TYPE, optional) – Description
- Returns
-
Description
- Return type
-
TYPE
-
-
class
airsimneurips.types.
AngleLevelControllerGains
(rollGains=<airsimneurips.types.PIDGains object>, pitchGains=<airsimneurips.types.PIDGains object>, yawGains=<airsimneurips.types.PIDGains object>)¶ -
Struct to contain controller gains used by angle rate PID controller
-
class
airsimneurips.types.
AngleRateControllerGains
(rollGains=<airsimneurips.types.PIDGains object>, pitchGains=<airsimneurips.types.PIDGains object>, yawGains=<airsimneurips.types.PIDGains object>)¶ -
Struct to contain controller gains used by angle level PID controller
-
class
airsimneurips.types.
CollisionInfo
¶ -
-
impact_point
¶ -
Description
- Type
-
TYPE
-
normal
¶ -
Description
- Type
-
TYPE
-
position
¶ -
Description
- Type
-
TYPE
-
-
class
airsimneurips.types.
DrivetrainType
¶ -
Type of DrivetrainType
-
class
airsimneurips.types.
GeoPoint
¶
-
class
airsimneurips.types.
ImageRequest
(camera_name, image_type, pixels_as_float=False, compress=True)¶ -
-
image_type
¶ -
Description
- Type
-
TYPE
-
-
class
airsimneurips.types.
ImageResponse
¶ -
-
camera_orientation
¶ -
Description
- Type
-
TYPE
-
camera_position
¶ -
Description
- Type
-
TYPE
-
image_data_uint8
¶ -
Description
- Type
-
TYPE
-
image_type
¶ -
Description
- Type
-
TYPE
-
time_stamp
¶ -
Description
- Type
-
TYPE
-
-
class
airsimneurips.types.
ImageType
¶
-
class
airsimneurips.types.
MsgpackMixin
¶ -
-
classmethod
from_msgpack
(encoded)¶ -
- Parameters
-
encoded (TYPE) – Description
- Returns
-
Description
- Return type
-
TYPE
-
to_msgpack
(*args, **kwargs)¶ -
- Parameters
-
-
*args – Description
-
**kwargs – Description
-
- Returns
-
Description
- Return type
-
TYPE
-
classmethod
-
class
airsimneurips.types.
MultirotorState
¶ -
-
collision
¶ -
Description
- Type
-
kinematics_estimated
¶ -
Description
- Type
-
landed_state
¶ -
Description
- Type
-
LandedState.Landed
-
timestamp
¶ -
Description
- Type
-
np.uint64
-
-
class
airsimneurips.types.
PIDGains
(kp, ki, kd)¶ -
Struct to store values of PID gains. Used to transmit controller gain values while instantiating AngleLevel/AngleRate/Velocity/PositionControllerGains objects.
-
class
airsimneurips.types.
Pose
(position_val=<Vector3r> { 'x_val': 0.0, 'y_val': 0.0, 'z_val': 0.0}, orientation_val=<Quaternionr> { 'w_val': 1.0, 'x_val': 0.0, 'y_val': 0.0, 'z_val': 0.0})¶ -
-
orientation
¶ -
Description
- Type
-
static
nanPose
()¶ -
- Returns
-
Description
- Return type
-
TYPE
-
-
class
airsimneurips.types.
PositionControllerGains
(xGains=<airsimneurips.types.PIDGains object>, yGains=<airsimneurips.types.PIDGains object>, zGains=<airsimneurips.types.PIDGains object>)¶ -
Struct to contain controller gains used by position PID controller
-
class
airsimneurips.types.
Quaternionr
(x_val=0.0, y_val=0.0, z_val=0.0, w_val=1.0)¶ -
-
conjugate
()¶ -
- Returns
-
Description
- Return type
-
TYPE
-
cross
(other)¶ -
- Parameters
-
other (TYPE) – Description
- Returns
-
Description
- Return type
-
TYPE
- Raises
-
TypeError – Description
-
dot
(other)¶ -
- Parameters
-
other (TYPE) – Description
- Returns
-
Description
- Return type
-
TYPE
- Raises
-
TypeError – Description
-
inverse
()¶ -
- Returns
-
Description
- Return type
-
TYPE
-
static
nanQuaternionr
()¶ -
- Returns
-
Description
- Return type
-
TYPE
-
outer_product
(other)¶ -
- Parameters
-
other (TYPE) – Description
- Returns
-
Description
- Return type
-
TYPE
- Raises
-
TypeError – Description
-
rotate
(other)¶ -
- Parameters
-
other (TYPE) – Description
- Returns
-
Description
- Return type
-
TYPE
- Raises
-
-
TypeError – Description
-
ValueError – Description
-
-
sgn
()¶ -
- Returns
-
Description
- Return type
-
TYPE
-
star
()¶ -
- Returns
-
Description
- Return type
-
TYPE
-
to_numpy_array
()¶ -
- Returns
-
Description
- Return type
-
np.array
-
-
class
airsimneurips.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)¶ -
-
pitch
¶ -
Description
- Type
-
TYPE
-
roll
¶ -
Description
- Type
-
TYPE
-
switch1
¶ -
Description
- Type
-
TYPE
-
switch2
¶ -
Description
- Type
-
TYPE
-
switch3
¶ -
Description
- Type
-
TYPE
-
switch4
¶ -
Description
- Type
-
TYPE
-
switch5
¶ -
Description
- Type
-
TYPE
-
switch6
¶ -
Description
- Type
-
TYPE
-
switch7
¶ -
Description
- Type
-
TYPE
-
switch8
¶ -
Description
- Type
-
TYPE
-
throttle
¶ -
Description
- Type
-
TYPE
-
yaw
¶ -
Description
- Type
-
TYPE
-
-
class
airsimneurips.types.
TrajectoryTrackerGains
(kp_cross_track=7.5, kd_cross_track=0.0, kp_vel_cross_track=5.0, kd_vel_cross_track=0.0, kp_along_track=0.4, kd_along_track=0.0, kp_vel_along_track=0.04, kd_vel_along_track=0.0, kp_z_track=2.0, kd_z_track=0.0, kp_vel_z=0.4, kd_vel_z=0.0, kp_yaw=3.0, kd_yaw=0.1)¶ -
Struct to contain trajectory tracker gains used by the pure pursuit controller for moveBySpline and moveBySplineVelConstraints
-
kp_cross_track
¶ -
P gain for position error measured perpendicular to path tangent, or in the “cross track” direction
- Type
-
kd_cross_track
¶ -
D gain for position error measured perpendicular to path tangent, or in the “cross track” direction
- Type
-
kp_vel_cross_track
¶ -
P gain for velocity error measured perpendicular to path tangent, or in the “cross track” direction
- Type
-
kd_vel_cross_track
¶ -
D gain for velocity error measured perpendicular to path tangent, or in the “cross track” direction
- Type
-
-
class
airsimneurips.types.
Vector3r
(x_val=0.0, y_val=0.0, z_val=0.0)¶ -
-
cross
(other)¶ -
- Parameters
-
other (TYPE) – Description
- Returns
-
Description
- Return type
-
TYPE
- Raises
-
TypeError – Description
-
distance_to
(other)¶ -
- Parameters
-
other (TYPE) – Description
- Returns
-
Description
- Return type
-
TYPE
-
dot
(other)¶ -
- Parameters
-
other (TYPE) – Description
- Returns
-
Description
- Return type
-
TYPE
- Raises
-
TypeError – Description
-
get_length
()¶ -
- Returns
-
Description
- Return type
-
TYPE
-
static
nanVector3r
()¶ -
- Returns
-
Description
- Return type
-
TYPE
-
to_Quaternionr
()¶ -
- Returns
-
Description
- Return type
-
TYPE
-
to_numpy_array
()¶ -
- Returns
-
Description
- Return type
-
TYPE
-
-
class
airsimneurips.types.
VelocityControllerGains
(xGains=<airsimneurips.types.PIDGains object>, yGains=<airsimneurips.types.PIDGains object>, zGains=<airsimneurips.types.PIDGains object>)¶ -
Struct to contain controller gains used by velocity PID controller
-
class
airsimneurips.types.
YawMode
(is_rate=True, yaw_or_rate=0.0)¶ -
Struct YawMode with two fields, yaw_or_rate and is_rate. If is_rate field is True then yaw_or_rate field is interpreted as angular velocity in degrees/sec, which means you want vehicle to rotate continuously around its axis at that angular velocity while moving.
If is_rate is False then yaw_or_rate is interpreted as angle in degrees, which means you want vehicle to rotate to specific angle (i.e. yaw) and keep that angle while moving.
When yaw_mode.is_rate == true, the drivetrain parameter shouldn’t be set to ForwardOnly because there’s a contradiction as we’re asking for the drone to keep front pointing ahead, but also rotate continuously. However if you have yaw_mode.is_rate = false in ForwardOnly mode then you can do some funky stuff. For example, you can have drone do circles and have yaw_or_rate set to 90 so camera is always pointed to center. In MaxDegreeofFreedom also you can get some funky stuff by setting yaw_mode.is_rate = true and say yaw_mode.yaw_or_rate = 20. This will cause drone to go in its path while rotating which may allow to do 360 scanning.
In most cases, you just don’t want yaw to change which you can do by setting yaw rate of 0. The shorthand for this is airsim.YawMode()
-
is_rate
¶ -
if True, yaw_or_rate is interpreted as angular velocity in degrees/sec, if False, yaw_or_rate is interpreted as angles in degrees,
- Type
-
-
airsimneurips.utils.
get_pfm_array
(response)¶ -
- Parameters
-
response (TYPE) – Description
- Returns
-
Description
- Return type
-
TYPE
-
airsimneurips.utils.
get_public_fields
(obj)¶ -
- Parameters
-
obj (TYPE) – Description
- Returns
-
Description
- Return type
-
TYPE
-
airsimneurips.utils.
list_to_2d_float_array
(flst, width, height)¶ -
- Parameters
-
-
flst (TYPE) – Description
-
width (TYPE) – Description
-
height (TYPE) – Description
-
- Returns
-
Description
- Return type
-
TYPE
-
airsimneurips.utils.
read_pfm
(file)¶ -
Read a pfm file
- Parameters
-
file (TYPE) – Description
- Returns
-
Description
- Return type
-
TYPE
- Raises
-
Exception – Description
-
airsimneurips.utils.
string_to_float_array
(bstr)¶ -
- Parameters
-
bstr (TYPE) – Description
- Returns
-
Description
- Return type
-
TYPE
-
airsimneurips.utils.
string_to_uint8_array
(bstr)¶ -
- Parameters
-
bstr (TYPE) – Description
- Returns
-
Description
- Return type
-
TYPE
-
airsimneurips.utils.
to_dict
(obj)¶ -
- Parameters
-
obj (TYPE) – Description
- Returns
-
Description
- Return type
-
TYPE
-
airsimneurips.utils.
to_eularian_angles
(q)¶ -
- Parameters
-
q (TYPE) – Description
- Returns
-
Description
- Return type
-
TYPE
-
airsimneurips.utils.
to_quaternion
(pitch, roll, yaw)¶ -
- Parameters
-
-
pitch (TYPE) – Description
-
roll (TYPE) – Description
-
yaw (TYPE) – Description
-
- Returns
-
Description
- Return type
-
TYPE
-
airsimneurips.utils.
to_str
(obj)¶ -
- Parameters
-
obj (TYPE) – Description
- Returns
-
Description
- Return type
-
TYPE
-
airsimneurips.utils.
wait_key
(message='')¶ -
Wait for a key press on the console and return it.
- Parameters
-
message (str, optional) – Description
- Returns
-
Description
- Return type
-
TYPE
-
airsimneurips.utils.
write_file
(filename, bstr)¶ -
- Parameters
-
-
filename (TYPE) – Description
-
bstr (TYPE) – Description
-
-
airsimneurips.utils.
write_pfm
(file, image, scale=1)¶ -
Write a pfm file
-
airsimneurips.utils.
write_png
(filename, image)¶ -
image must be numpy array H X W X channels
- Parameters
-
-
filename (TYPE) – Description
-
image (TYPE) – Description
-