Winch

class mavsdk.winch.Status(time_usec, line_length_m, speed_m_s, tension_kg, voltage_v, current_a, temperature_c, status_flags)

Bases: object

Status type.

Parameters:
  • time_usec (uint64_t) – Time in usec

  • line_length_m (float) – Length of the line in meters

  • speed_m_s (float) – Speed in meters per second

  • tension_kg (float) – Tension in kilograms

  • voltage_v (float) – Voltage in volts

  • current_a (float) – Current in amperes

  • temperature_c (int32_t) – Temperature in Celsius

  • status_flags (StatusFlags) – Status flags

class mavsdk.winch.StatusFlags(healthy, fully_retracted, moving, clutch_engaged, locked, dropping, arresting, ground_sense, retracting, redeliver, abandon_line, locking, load_line, load_payload)

Bases: object

Winch Status Flags.

The status flags are defined in mavlink https://mavlink.io/en/messages/common.html#MAV_WINCH_STATUS_FLAG.

Multiple status fields can be set simultaneously. Mavlink does not specify which states are mutually exclusive.

Parameters:
  • healthy (bool) – Winch is healthy

  • fully_retracted (bool) – Winch line is fully retracted

  • moving (bool) – Winch motor is moving

  • clutch_engaged (bool) – Winch clutch is engaged allowing motor to move freely

  • locked (bool) – Winch is locked by locking mechanism

  • dropping (bool) – Winch is gravity dropping payload

  • arresting (bool) – Winch is arresting payload descent

  • ground_sense (bool) – Winch is using torque measurements to sense the ground

  • retracting (bool) – Winch is returning to the fully retracted position

  • redeliver (bool) – Winch is redelivering the payload. This is a failover state if the line tension goes above a threshold during RETRACTING.

  • abandon_line (bool) – Winch is abandoning the line and possibly payload. Winch unspools the entire calculated line length. This is a failover state from REDELIVER if the number of attempts exceeds a threshold.

  • locking (bool) – Winch is engaging the locking mechanism

  • load_line (bool) – Winch is spooling on line

  • load_payload (bool) – Winch is loading a payload

class mavsdk.winch.Winch(async_plugin_manager)

Bases: AsyncBase

Allows users to send winch actions, as well as receive status information from winch systems.

Generated by dcsdkgen - MAVSDK Winch API

async abandon_line(instance)

Spool out the entire length of the line.

Parameters:

instance (uint32_t)

Raises:

WinchError – If the request fails. The error contains the reason for the failure.

async deliver(instance)

Sequence of drop, slow down, touch down, reel up, lock.

Parameters:

instance (uint32_t)

Raises:

WinchError – If the request fails. The error contains the reason for the failure.

async hold(instance)

Engage motor and hold current position.

Parameters:

instance (uint32_t)

Raises:

WinchError – If the request fails. The error contains the reason for the failure.

async load_line(instance)

Load the reel with line.

The winch will calculate the total loaded length and stop when the tension exceeds a threshold.

Parameters:

instance (uint32_t)

Raises:

WinchError – If the request fails. The error contains the reason for the failure.

async load_payload(instance)

Spools out just enough to present the hook to the user to load the payload.

Parameters:

instance (uint32_t)

Raises:

WinchError – If the request fails. The error contains the reason for the failure.

async lock(instance)

Perform the locking sequence to relieve motor while in the fully retracted position.

Parameters:

instance (uint32_t)

Raises:

WinchError – If the request fails. The error contains the reason for the failure.

name = 'Winch'
async rate_control(instance, rate_m_s)

Wind or unwind line at specified rate.

Parameters:
  • instance (uint32_t)

  • rate_m_s (float) – Rate at which to wind or unwind the line

Raises:

WinchError – If the request fails. The error contains the reason for the failure.

async relative_length_control(instance, length_m, rate_m_s)

Wind or unwind specified length of line, optionally using specified rate.

Parameters:
  • instance (uint32_t) – Instance ID of the winch addressed by this request

  • length_m (float) – Length of line to unwind or wind

  • rate_m_s (float) – Rate at which to wind or unwind the line

Raises:

WinchError – If the request fails. The error contains the reason for the failure.

async relax(instance)

Allow motor to freewheel.

Parameters:

instance (uint32_t)

Raises:

WinchError – If the request fails. The error contains the reason for the failure.

async retract(instance)

Return the reel to the fully retracted position.

Parameters:

instance (uint32_t)

Raises:

WinchError – If the request fails. The error contains the reason for the failure.

async status()

Subscribe to ‘winch status’ updates.

Yields:

status (Status) – The next ‘winch status’ state

class mavsdk.winch.WinchAction(value)

Bases: Enum

Winch Action type.

Values

RELAXED

Allow motor to freewheel

RELATIVE_LENGTH_CONTROL

Wind or unwind specified length of line, optionally using specified rate

RATE_CONTROL

Wind or unwind line at specified rate

LOCK

Perform the locking sequence to relieve motor while in the fully retracted position

DELIVER

Sequence of drop, slow down, touch down, reel up, lock

HOLD

Engage motor and hold current position

RETRACT

Return the reel to the fully retracted position

LOAD_LINE

Load the reel with line. The winch will calculate the total loaded length and stop when the tension exceeds a threshold

ABANDON_LINE

Spool out the entire length of the line

LOAD_PAYLOAD

Spools out just enough to present the hook to the user to load the payload

ABANDON_LINE = 8
DELIVER = 4
HOLD = 5
LOAD_LINE = 7
LOAD_PAYLOAD = 9
LOCK = 3
RATE_CONTROL = 2
RELATIVE_LENGTH_CONTROL = 1
RELAXED = 0
RETRACT = 6
exception mavsdk.winch.WinchError(result, origin, *params)

Bases: Exception

Raised when a WinchResult is a fail code

class mavsdk.winch.WinchResult(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 winch action requests.

Values

UNKNOWN

Unknown result

SUCCESS

Request was successful

NO_SYSTEM

No system is connected

BUSY

Temporarily rejected

TIMEOUT

Request timed out

UNSUPPORTED

Action not supported

FAILED

Action failed

BUSY = 3
FAILED = 6
NO_SYSTEM = 2
SUCCESS = 1
TIMEOUT = 4
UNKNOWN = 0
UNSUPPORTED = 5