MultirotorClient
- class airgen.client.MultirotorClient(ip='', port=41451, timeout_value=3600, geo=False)
Bases:
VehicleClient
,object
- cancelLastTask(vehicle_name='')
Cancel previous Async task
- Parameters:
vehicle_name (str, optional) -- Name of the vehicle
- getMultirotorState(vehicle_name='')
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='')
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='')
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='')
- landAsync(timeout_sec=60, vehicle_name='')
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='')
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
- moveByAngleThrottleAsync(pitch, roll, throttle, yaw_rate, duration, vehicle_name='')
- moveByAngleZAsync(pitch, roll, z, yaw, duration, vehicle_name='')
- moveByManualAsync(vx_max, vy_max, z_min, duration, drivetrain=0, yaw_mode=<YawMode> { 'is_rate': True, 'yaw_or_rate': 0.0}, vehicle_name='')
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='')
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='')
- 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 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='')
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='')
- moveByVelocityBodyFrameAsync(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 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='')
#todo: add description
- Parameters:
vx (_type_) -- _description_
vy (_type_) -- _description_
z (_type_) -- _description_
duration (_type_) -- _description_
drivetrain (_type_, optional) -- _description_. Defaults to DrivetrainType.MaxDegreeOfFreedom.
yaw_mode (_type_, optional) -- _description_. Defaults to YawMode().
vehicle_name (str, optional) -- _description_. Defaults to "".
- Returns:
_description_
- Return type:
_type_
- moveByVelocityZBodyFrameAsync(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 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
- moveOnGPSPathAsync(geopoints, orientations, 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='')
Give a list of LLA geopoints, and the drone will move along that path at the specified velocity
- Parameters:
path (_type_) -- _description_
velocity (_type_) -- _description_
timeout_sec (_type_, optional) -- _description_. Defaults to 3e38.
drivetrain (_type_, optional) -- _description_. Defaults to DrivetrainType.MaxDegreeOfFreedom.
yaw_mode (_type_, optional) -- _description_. Defaults to YawMode().
lookahead (int, optional) -- _description_. Defaults to -1.
adaptive_lookahead (int, optional) -- _description_. Defaults to 1.
vehicle_name (str, optional) -- _description_. Defaults to "".
- Returns:
_description_
- Return type:
_type_
- 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, orientations=[], vehicle_name='')
Give a list of 3D points, and the drone will move along that path at the specified velocity
- Parameters:
path (_type_) -- _description_
velocity (_type_) -- _description_
timeout_sec (_type_, optional) -- _description_. Defaults to 3e38.
drivetrain (_type_, optional) -- _description_. Defaults to DrivetrainType.MaxDegreeOfFreedom.
yaw_mode (_type_, optional) -- _description_. Defaults to YawMode().
lookahead (int, optional) -- _description_. Defaults to -1.
adaptive_lookahead (int, optional) -- _description_. Defaults to 1.
vehicle_name (str, optional) -- _description_. Defaults to "".
- Returns:
_description_
- Return type:
_type_
- moveToGPSAsync(lla, 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='')
- 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='')
move the drone directly towards to a desired position in the world if possible
- Parameters:
x (_type_) -- _description_
y (_type_) -- _description_
z (_type_) -- _description_
velocity (_type_) -- _description_
timeout_sec (_type_, optional) -- _description_. Defaults to 3e38.
drivetrain (_type_, optional) -- _description_. Defaults to DrivetrainType.MaxDegreeOfFreedom.
yaw_mode (_type_, optional) -- _description_. Defaults to YawMode().
lookahead (int, optional) -- _description_. Defaults to -1.
adaptive_lookahead (int, optional) -- _description_. Defaults to 1.
vehicle_name (str, optional) -- _description_. Defaults to "".
- Returns:
_description_
- Return type:
_type_
- 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='')
- rotateByYawRateAsync(yaw_rate, duration, vehicle_name='')
- rotateToYawAsync(yaw, timeout_sec=3e+38, margin=5, vehicle_name='')
- setAngleLevelControllerGains(angle_level_gains=<airgen.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() API.
This is because the airgen 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 airgen 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=<airgen.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
- setNacellesRotation(pitch, rate, sweep=False, vehicle_name='')
Set the rotation of all the Nacelles
- Parameters:
pitch (float) -- Pitch angle in degrees.
rate (float) -- Speed at which the angles update.
sweep (bool, optional) -- Whether we sweep to the target rotation, and stopping short of the target if blocked by something.
vehicle_name (str, optional) -- Vehicle to get the state of.
- setPositionControllerGains(position_gains=<airgen.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
- setVelocityControllerGains(velocity_gains=<airgen.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.
Passing VelocityControllerGains() sets gains to default airgen 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='')
Takeoff vehicle to 3m above ground. Vehicle should not be moving when this API is used. It also clears any prior collision information by calling simGetCollisionInfo()
- 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