Offboard¶
- class mavsdk.offboard.AccelerationNed(north_m_s2, east_m_s2, down_m_s2)¶
Bases:
object
Type for acceleration commands in NED (North East Down) coordinates.
- Parameters:
north_m_s2 (float) – Acceleration North (in metres/second^2)
east_m_s2 (float) – Acceleration East (in metres/second^2)
down_m_s2 (float) – Acceleration Down (in metres/second^2)
- class mavsdk.offboard.ActuatorControl(groups)¶
Bases:
object
Type for actuator control.
Control members should be normed to -1..+1 where 0 is neutral position. Throttle for single rotation direction motors is 0..1, negative range for reverse direction.
One group support eight controls.
Up to 16 actuator controls can be set. To ignore an output group, set all it controls to NaN. If one or more controls in group is not NaN, then all NaN controls will sent as zero. The first 8 actuator controls internally map to control group 0, the latter 8 actuator controls map to control group 1. Depending on what controls are set (instead of NaN) 1 or 2 MAVLink messages are actually sent.
In PX4 v1.9.0 Only first four Control Groups are supported (https://github.com/PX4/Firmware/blob/v1.9.0/src/modules/mavlink/mavlink_receiver.cpp#L980).
- Parameters:
groups ([ActuatorControlGroup]) – Control groups.
- class mavsdk.offboard.ActuatorControlGroup(controls)¶
Bases:
object
Eight controls that will be given to the group. Each control is a normalized (-1..+1) command value, which will be mapped and scaled through the mixer.
- Parameters:
controls ([float]) – Controls in the group
- class mavsdk.offboard.Attitude(roll_deg, pitch_deg, yaw_deg, thrust_value)¶
Bases:
object
Type for attitude body angles in NED reference frame (roll, pitch, yaw and thrust)
- Parameters:
roll_deg (float) – Roll angle (in degrees, positive is right side down)
pitch_deg (float) – Pitch angle (in degrees, positive is nose up)
yaw_deg (float) – Yaw angle (in degrees, positive is move nose to the right)
thrust_value (float) – Thrust (range: 0 to 1)
- class mavsdk.offboard.AttitudeRate(roll_deg_s, pitch_deg_s, yaw_deg_s, thrust_value)¶
Bases:
object
Type for attitude rate commands in body coordinates (roll, pitch, yaw angular rate and thrust)
- Parameters:
roll_deg_s (float) – Roll angular rate (in degrees/second, positive for clock-wise looking from front)
pitch_deg_s (float) – Pitch angular rate (in degrees/second, positive for head/front moving up)
yaw_deg_s (float) – Yaw angular rate (in degrees/second, positive for clock-wise looking from above)
thrust_value (float) – Thrust (range: 0 to 1)
- class mavsdk.offboard.Offboard(async_plugin_manager)¶
Bases:
AsyncBase
Control a drone with position, velocity, attitude or motor commands.
The module is called offboard because the commands can be sent from external sources as opposed to onboard control right inside the autopilot “board”.
Client code must specify a setpoint before starting offboard mode. Mavsdk automatically sends setpoints at 20Hz (PX4 Offboard mode requires that setpoints are minimally sent at 2Hz).
Generated by dcsdkgen - MAVSDK Offboard API
- async is_active()¶
Check if offboard control is active.
True means that the vehicle is in offboard mode and we are actively sending setpoints.
- Returns:
is_active – True if offboard is active
- Return type:
bool
- name = 'Offboard'¶
- async set_acceleration_ned(acceleration_ned)¶
Set the acceleration in NED coordinates.
- Parameters:
acceleration_ned (AccelerationNed) – Acceleration
- Raises:
OffboardError – If the request fails. The error contains the reason for the failure.
- async set_actuator_control(actuator_control)¶
Set direct actuator control values to groups #0 and #1.
First 8 controls will go to control group 0, the following 8 controls to control group 1 (if actuator_control.num_controls more than 8).
- Parameters:
actuator_control (ActuatorControl) – Actuator control values
- Raises:
OffboardError – If the request fails. The error contains the reason for the failure.
- async set_attitude(attitude)¶
Set the attitude in terms of roll, pitch and yaw in degrees with thrust.
- Parameters:
attitude (Attitude) – Attitude roll, pitch and yaw along with thrust
- Raises:
OffboardError – If the request fails. The error contains the reason for the failure.
- async set_attitude_rate(attitude_rate)¶
Set the attitude rate in terms of pitch, roll and yaw angular rate along with thrust.
- Parameters:
attitude_rate (AttitudeRate) – Attitude rate roll, pitch and yaw angular rate along with thrust
- Raises:
OffboardError – If the request fails. The error contains the reason for the failure.
- async set_position_global(position_global_yaw)¶
Set the position in Global coordinates (latitude, longitude, altitude) and yaw
- Parameters:
position_global_yaw (PositionGlobalYaw) – Position and yaw
- Raises:
OffboardError – If the request fails. The error contains the reason for the failure.
- async set_position_ned(position_ned_yaw)¶
Set the position in NED coordinates and yaw.
- Parameters:
position_ned_yaw (PositionNedYaw) – Position and yaw
- Raises:
OffboardError – If the request fails. The error contains the reason for the failure.
- async set_position_velocity_acceleration_ned(position_ned_yaw, velocity_ned_yaw, acceleration_ned)¶
Set the position, velocity and acceleration in NED coordinates, with velocity and acceleration used as feed-forward.
- Parameters:
position_ned_yaw (PositionNedYaw) – Position and yaw
velocity_ned_yaw (VelocityNedYaw) – Velocity and yaw
acceleration_ned (AccelerationNed) – Acceleration
- Raises:
OffboardError – If the request fails. The error contains the reason for the failure.
- async set_position_velocity_ned(position_ned_yaw, velocity_ned_yaw)¶
Set the position in NED coordinates, with the velocity to be used as feed-forward.
- Parameters:
position_ned_yaw (PositionNedYaw) – Position and yaw
velocity_ned_yaw (VelocityNedYaw) – Velocity and yaw
- Raises:
OffboardError – If the request fails. The error contains the reason for the failure.
- async set_velocity_body(velocity_body_yawspeed)¶
Set the velocity in body coordinates and yaw angular rate. Not available for fixed-wing aircraft.
- Parameters:
velocity_body_yawspeed (VelocityBodyYawspeed) – Velocity and yaw angular rate
- Raises:
OffboardError – If the request fails. The error contains the reason for the failure.
- async set_velocity_ned(velocity_ned_yaw)¶
Set the velocity in NED coordinates and yaw. Not available for fixed-wing aircraft.
- Parameters:
velocity_ned_yaw (VelocityNedYaw) – Velocity and yaw
- Raises:
OffboardError – If the request fails. The error contains the reason for the failure.
- async start()¶
Start offboard control.
- Raises:
OffboardError – If the request fails. The error contains the reason for the failure.
- async stop()¶
Stop offboard control.
The vehicle will be put into Hold mode: https://docs.px4.io/en/flight_modes/hold.html
- Raises:
OffboardError – If the request fails. The error contains the reason for the failure.
- exception mavsdk.offboard.OffboardError(result, origin, *params)¶
Bases:
Exception
Raised when a OffboardResult is a fail code
- class mavsdk.offboard.OffboardResult(result, result_str)¶
Bases:
object
Result type.
- Parameters:
result (Result) – Result enum value
result_str (std::string) – Human-readable English string describing the result
- class Result(value)¶
Bases:
Enum
Possible results returned for offboard requests
Values¶
- UNKNOWN
Unknown result
- SUCCESS
Request succeeded
- NO_SYSTEM
No system is connected
- CONNECTION_ERROR
Connection error
- BUSY
Vehicle is busy
- COMMAND_DENIED
Command denied
- TIMEOUT
Request timed out
- NO_SETPOINT_SET
Cannot start without setpoint set
- FAILED
Request failed
- BUSY = 4¶
- COMMAND_DENIED = 5¶
- CONNECTION_ERROR = 3¶
- FAILED = 8¶
- NO_SETPOINT_SET = 7¶
- NO_SYSTEM = 2¶
- SUCCESS = 1¶
- TIMEOUT = 6¶
- UNKNOWN = 0¶
- class mavsdk.offboard.PositionGlobalYaw(lat_deg, lon_deg, alt_m, yaw_deg, altitude_type)¶
Bases:
object
Type for position commands in Global (Latitude, Longitude, Altitude) coordinates and yaw.
- Parameters:
lat_deg (double) – Latitude (in degrees)
lon_deg (double) – Longitude (in degrees)
alt_m (float) – altitude (in metres)
yaw_deg (float) – Yaw in degrees (0 North, positive is clock-wise looking from above)
altitude_type (AltitudeType) – altitude type for this position
- class mavsdk.offboard.PositionNedYaw(north_m, east_m, down_m, yaw_deg)¶
Bases:
object
Type for position commands in NED (North East Down) coordinates and yaw.
- Parameters:
north_m (float) – Position North (in metres)
east_m (float) – Position East (in metres)
down_m (float) – Position Down (in metres)
yaw_deg (float) – Yaw in degrees (0 North, positive is clock-wise looking from above)
- class mavsdk.offboard.VelocityBodyYawspeed(forward_m_s, right_m_s, down_m_s, yawspeed_deg_s)¶
Bases:
object
Type for velocity commands in body coordinates.
- Parameters:
forward_m_s (float) – Velocity forward (in metres/second)
right_m_s (float) – Velocity right (in metres/second)
down_m_s (float) – Velocity down (in metres/second)
yawspeed_deg_s (float) – Yaw angular rate (in degrees/second, positive for clock-wise looking from above)
- class mavsdk.offboard.VelocityNedYaw(north_m_s, east_m_s, down_m_s, yaw_deg)¶
Bases:
object
Type for velocity commands in NED (North East Down) coordinates and yaw.
- Parameters:
north_m_s (float) – Velocity North (in metres/second)
east_m_s (float) – Velocity East (in metres/second)
down_m_s (float) – Velocity Down (in metres/second)
yaw_deg (float) – Yaw in degrees (0 North, positive is clock-wise looking from above)