multiwii API

class multiwii.MultiWii(serial_port: Serial)[source]

Bases: object

The main class for wiiproxy that handles communication with MultiWii flight controllers.

This class requires an open serial port with a baudrate of 115200 to be passed at instantiation.

Note

This class supports MSP v1 and does not support any newer versions.

Note

This class can be imported directly through the main module.

DEFAULT_MESSAGE_WRITE_READ_DELAY: Final[float] = 0.005

The default delay in seconds between writing and reading messages.

Type:

float

MSP_VERSION: Final[int] = 1

The supported MultiWii Serial Protocol version.

Type:

int

arm() NoReturn[source]

Arms the vehicle.

This method prepares the vehicle for operation by simulating the arming sequence performed by physical transmitters. It sets the throttle value to its minimum, and the yaw value to its maximum, for a few seconds simultaneously to initiate the arming process. This ensures that the vehicle is ready for further commands and a safe flight.

Note

Ensure that the vehicle is in a safe enviornment and that conditions are suitable for arming before invoking this method.

bind_transmitter_and_receiver() NoReturn[source]

Sends an MSP_BIND command to the FC using the provided data values.

This command initiates the binding process between the transmitter (radio controller) and the receiver connected to the FC. Binding establishes a secure communication link between the transmitter (TX) and the receiver (RX).

Note

Ensure that the FC is ready to receive the bind command and that the transmitter is in binding mode before calling this method.

calibrate_accelerometer() NoReturn[source]

Sends an MSP_ACC_CALIBRATION command to the FC using the provided data values.

This command initiates the accelerometer calibration process on the FC. Accelerometer calibration is essential for accurate attitude estimation and stabilization of the aircraft.

Note

The FC should be placed on a level surface during the calibration to ensure accurate results. Avoid moving or disturbing the FC during the process.

calibrate_magnetometer() NoReturn[source]

Sends an MSP_MAG_CALIBRATION command to the FC using the provided data values.

This command initiates the magnetometer (compass) calibration process on the FC. Magnetometer calibration is crucial for accurate heading estimation and navigation, especially in GPS-assisted flight modes.

Note

The FC should be rotated along all three axes (roll, pitch, yaw) in a smooth and consistent manner to ensure accurate results. Avoid any magnetic interference or disturbances during the process.

property command_to_data_structure_type_map: dict[_MspCommand, Type]

Gets the command to data structure type dictionary.

Returns:

A instance with a copy of the map.

Return type:

dict[_MspCommand, Type]

disarm() NoReturn[source]

Disarms the vehicle.

This method safely disarms the vehicle by resetting the yaw and throttle to their minimum values. This process simulates the disarming sequence used by physical transmitters, ensuring that the vehicle is no longer ready for flight, and that the vehicle is in a more safe state.

Note

Always ensure that the vehicle is on the ground and stationary before invoking this method to avoid accidental movement or damage.

get_data(command: _MspCommand) Any[source]

Sends a given command to the FC and parses the retrieved data values.

Parameters:

command (_MspCommand) – An instance of _MspCommand representing the MSP command to get corresponding data values for.

Returns:

An instance of a corresponding data structure type for the given command.

Return type:

Any

property message_write_read_delay: float

Gets the delay (in seconds) between each write and read message.

Returns:

The delay in seconds.

Return type:

float

reset_config() NoReturn[source]

Sends an MSP_RESET_CONF command to the FC using the provided data values.

This command resets the configuration settings on the FC to their default values. It effectively restores the FC to its initial configuration state, clearing any customized settings or adjustments made by the user.

Note

Resetting the config should be done with caution, as it will revert all settings to their defaults. Make sure to reconfigure the FC according to your requirements after executing this command to the FC using the provided data values.

save_config_to_eeprom() NoReturn[source]

Sends an MSP_EEPROM_WRITE command to the FC using the provided data values.

This command writes the current configuration settings to the EEPROM of the FC.

Note

Writing to EEPROM should be done with caution, as it modifies the stored config directly. Ensure that the values written are valid and intended, as incorrect values could lead to unexpected behavior or instability.

select_setting(value: int) NoReturn[source]

Sends an MSP_SELECT_SETTING command to the FC using the provided data values.

Selects the “setting configuration” with different PID and rate values using the given range value.

Parameters:

value (int) – A value of 0, 1 or 2.

Raises:

ValueError – If the provided value is not 0, 1 or 2.

property serial_port: Serial

Gets the serial port instance.

Returns:

The serial port instance.

Return type:

Serial

set_boxes(data: MspBox) NoReturn[source]

Sends an MSP_SET_BOX command to the FC using the provided data values.

Sets the flight modes (or “boxes”) config on the FC. Flight modes define the behavior of the aircraft based on various inputs from the transmitter or other sources.

Parameters:

data (tuple[MspBoxItem]) – A tuple of non-null MspBoxItem values.

set_head(value: int) NoReturn[source]

Sends an MSP_SET_HEAD command to the FC using the provided data values.

Sets the heading (yaw) direction reference on the FC with a value range of -180 to 180. It is used to define the forward direction of the aircraft relative to its orientation.

Parameters:

range (int) – The heading direction value within a range of -180 and 180.

Raises:

ValueError – If the provided range value is less than -180 or greater than 180.

set_misc_config(data: MspSetMisc) NoReturn[source]

Sends an MSP_SET_MISC command to the FC using the provided data values.

Sets miscellaneous config parameters on the FC—such as battery voltage scaling, failsafe behavior, or other settings not covered by specific MSP commands.

Parameters:

data (MspSetMisc) – An instance of the MspSetMisc class populated with values.

set_motors(data: MspMotor) NoReturn[source]

Sends an MSP_SET_MOTOR command to the FC using the provided data values.

Sets the motor output values on the FC. Motor output values determine the throttle level for each motor, controlling the rotation speed and thrust generated by the motors.

Parameters:

data (MspMotor) – An instance of the MspMotor class populated with values.

set_pid_values(data: MspPid) NoReturn[source]

Sends an MSP_SET_PID command to the FC using the provided data values.

Sets the PID values on the FC. PID values are used to adjust the stability and response characteristics of the aircraft.

Parameters:

data (MspPid) – An instance of the MspPid class populated with values.

set_raw_gps(data: MspRawGps) NoReturn[source]

Sends an MSP_SET_RAW_GPS command to the FC using the provided data values.

Sets the raw GPS data on the FC—such as the latitude, longitude, altitude, and other GPS-related information.

Parameters:

data (MspRawGps) – An instance of the MspRawGps class populated with values.

set_raw_rc(data: MspRc) NoReturn[source]

Sends an MSP_SET_RAW_RC command to the FC using the provided data values.

Sets the raw receiver (RC/RX) channel data on the FC. Raw FC data includes the pulse width values received from the transmitter for each channel, typically representing control inputs such as throttle, pitch, roll, and yaw.

Parameters:

data (MspRc) – An instance of the MspRc class populated with values.

set_rc_tuning(data: MspRcTuning) NoReturn[source]

Sends an MSP_SET_RC_TUNING command to the FC using the provided data values.

Sets RC tuning parameters on the FC—such as expo, rates, and other settings related to RC control response and behavior.

Parameters:

data (MspRcTuning) – An instance of the MspRcTuning class populated with values.

set_servo_config(data: MspServoConf) NoReturn[source]

Sends an MSP_SET_SERVO_CONF command to the FC using the provided data values.

Sets servo config parameters on the FC—such as servo mapping, direction, endpoints, and other settings related to servo control.

Parameters:

data (tuple[MspServoConfItem]) – A tuple with instances of the MspServoConfItem class populated with values.

set_waypoint(data: MspWaypoint) NoReturn[source]

Sends an MSP_SET_WP command to the FC using the provided data values.

Dispatches a command to set a waypoint on the FC, providing specific latitude, longitude, altitude, heading, duration and navigation flags for precise navigation and waypoint management.

Parameters:

data (MsWaypoint) – An instance of the MspWaypoint class populated with values.