Documentation¶
Controller¶
This module is responsible for controlling ardupilot.
- class MAVez.controller.Controller(connection_string='tcp:127.0.0.1:5762', baud=57600, logger=None)¶
Bases:
object
Controller class for atomic MAVLink communication with ardupilot.
- Parameters:
connection_string (str) – The connection string for ardupilot. Default is “tcp:127.0.0.1:5762” used for SITL.
baud (int) – The baud rate for the connection. Default is 57600.
logger – Logger instance for logging messages (optional).
- Raises:
ConnectionError – If the connection to ardupilot fails.
- Returns:
A Controller instance that can be used to communicate with ardupilot.
- TIMEOUT_DURATION = 5¶
- TIMEOUT_ERROR = 101¶
- arm(force=False)¶
Arm ardupilot
- Parameters:
force (bool) – If True, ardupilot will be armed regardless of its state.
- Returns:
0 if ardupilot was armed successfully, error code if there was an error, 101 if the response timed out.
- Return type:
int
- await_current_mission_index()¶
Get the current mission index.
- Returns:
The current mission index if received, TIMEOUT_ERROR (101) if the response timed out.
- Return type:
int
- await_mission_ack()¶
Wait for a mission ack from ardupilot.
- Returns:
0 if the mission ack was received, error code if there was an error, 101 if the response timed out.
- Return type:
int
- await_mission_item_reached(timeout=5)¶
Wait for a mission item reached message from ardupilot.
- Parameters:
timeout (int) – The timeout duration in seconds. Default is 5 seconds.
- Returns:
The sequence number of the reached mission item if received, TIMEOUT_ERROR (101) if the response timed out.
- Return type:
int
- await_mission_request()¶
Wait for a mission request from ardupilot.
- Returns:
Mission index if a mission request was received, 101 if the response timed out.
- Return type:
int
- decode_error(error_code)¶
Decode the error code into a human-readable string.
- Parameters:
error_code (int) – The error code to decode.
- Returns:
A human-readable error message.
- Return type:
str
- disable_geofence(floor_only=False)¶
Disable the geofence.
- Parameters:
floor_only (bool) – If True, only the floor of the geofence will be disabled.
- Returns:
0 if the geofence was disabled successfully, 101 if the response timed out.
- Return type:
int
- disable_message_interval(message_type, timeout=5)¶
Disable the message interval for the specified message type.
- Parameters:
message_type (str) – The type of message to disable the interval for.
timeout (int) – The timeout duration in seconds. Default is 5 seconds.
- Returns:
0 if the message interval was disabled successfully, error code if there was an error, 101 if the response timed out.
- Return type:
int
- disarm(force=False)¶
Disarm ardupilot.
- Parameters:
force (bool) – If True, ardupilot will be disarmed regardless of its state.
- Returns:
0 if ardupilot was disarmed successfully, error code if there was an error, 101 if the response timed out.
- Return type:
int
- enable_geofence()¶
Enable the geofence.
- Returns:
0 if the geofence was enabled successfully, 101 if the response timed out.
- Return type:
int
- receive_attitude(timeout=5)¶
Wait for an attitude message from ardupilot.
- Parameters:
timeout (int) – The timeout duration in seconds. Default is 5 seconds.
- Returns:
response if an attitude message was received, TIMEOUT_ERROR (101) if the response timed out.
- receive_channel_input(timeout=5)¶
Wait for an RC_CHANNELS message from ardupilot.
- Parameters:
timeout (int) – The timeout duration in seconds. Default is 5 seconds.
- Returns:
response if an RC_CHANNELS message was received, 101 if the response timed out
- receive_gps(timeout=5)¶
Wait for a gps_raw_int message from ardupilot.
- Parameters:
timeout (int) – The timeout duration in seconds. Default is 5 seconds.
- Returns:
A Coordinate object containing the GPS data if received, TIMEOUT_ERROR (101) if the response timed out.
- Return type:
- receive_landing_status(timeout=5)¶
Wait for a landed_state message from ardupilot.
- Parameters:
timeout (int) – The timeout duration in seconds. Default is 5 seconds.
- Returns:
The landing state if received, TIMEOUT_ERROR (101) if the response timed out, 0 if the state is undefined, 1 if on ground, 2 if in air, 3 if taking off, 4 if landing.
- Return type:
int
- receive_wind(timeout=5)¶
Wait for a wind_cov message from ardupilot.
- Parameters:
timeout (int) – The timeout duration in seconds. Default is 5 seconds.
- Returns:
response if a wind_cov message was received, 101 if the response timed out
- send_clear_mission()¶
Clear the mission on ardupilot.
- Returns:
0 if the mission was cleared successfully
- Return type:
int
- send_message(message)¶
Send a MAVLink message to ardupilot.
- Parameters:
message – The MAVLink message to send.
- Returns:
None
- send_mission_count(count, mission_type=0)¶
Send the mission count to ardupilot.
- Parameters:
count (int) – The number of mission items.
mission_type (int) – The type of mission (default is 0 for MISSION_TYPE 0).
- Returns:
0 if the mission count was sent successfully, 101 if the response timed out.
- Return type:
int
- set_current_mission_index(index)¶
sets the target mission index to the specified index
- Parameters:
index (int) – The index to set as the current mission index.
- Returns:
0 if the current mission index was set successfully, error code if there was an error, 101 if the response timed out.
- Return type:
int
- set_home(home_coordinate=0, 0, 0)¶
Set the home location.
- Parameters:
home_coordinate (Coordinate) – The home coordinate to set. If the coordinate is (0, 0, 0), the current GPS location will be used.
- Returns:
0 if the home location was set successfully, error code if there was an error, 101 if the response timed out.
- Return type:
int
- set_logger(logger)¶
Set the logger for the controller.
- Parameters:
logger – Logger instance for logging messages.
- Returns:
None
- set_message_interval(message_type, interval, timeout=5)¶
Set the message interval for the specified message type.
- Parameters:
message_type (str) – The type of message to set the interval for.
interval (int) – The interval in milliseconds to set for the message type.
timeout (int) – The timeout duration in seconds. Default is 5 seconds.
- Returns:
0 if the message interval was set successfully, error code if there was an error, 101 if the response timed out.
- Return type:
int
- set_mode(mode)¶
Set the ardupilot mode.
- Parameters:
mode (str) – The mode to set ardupilot to. Options include: “AUTO”, “GUIDED”, “FBWA”, etc…
- Returns:
0 if the mode was set successfully, 111 if the mode is unknown, 101 if the response timed out.
- Return type:
int
- set_servo(servo_number, pwm)¶
Set the a servo to a specified PWM value.
- Parameters:
servo_number (int) – The servo number to set.
pwm (int) – The PWM value to set the servo to.
- Returns:
0 if the servo was set successfully, error code if there was an error, 101 if the response timed out.
- Return type:
int
- start_mission(start_index, end_index)¶
Start the mission at the specified index.
- Parameters:
start_index (int) – The index to start the mission from.
end_index (int) – The index to end the mission at.
- Returns:
0 if the mission was started successfully, error code if there was an error, 101 if the response timed out.
- Return type:
int
Coordinate¶
Represents a geographic coordinate with latitude, longitude, and altitude.
- class MAVez.coordinate.Coordinate(lat, lon, alt, dms=False, use_int=True, heading=None)¶
Bases:
object
This class represents a coordinate in latitude, longitude, and altitude. It provides methods to initialize the coordinate, convert between degrees and decimal degrees, and offset the coordinate by a given distance and heading.
- Parameters:
lat (float | str) – Latitude in decimal degrees or DMS format if dms is True.
lon (float | str) – Longitude in decimal degrees or DMS format if dms is True.
alt (float) – Altitude in meters.
dms (bool) – If True, the coordinates are in degrees, minutes, seconds format. Defaults to False.
use_int (bool) – If True, the coordinates are stored as integers. Defaults to True.
heading (float | None) – Heading in degrees. Defaults to None.
- Returns:
An instance of the Coordinate class.
- Return type:
- bearing_to(other)¶
Calculate the bearing between two coordinates in degrees.
- Parameters:
other (Coordinate) – The other coordinate to calculate the bearing to.
- Returns:
The bearing in degrees from self to other.
- Return type:
float
- distance_to(other)¶
Calculate the distance between two coordinates in meters using the haversine formula.
- Parameters:
other (Coordinate) – The other coordinate to calculate the distance to.
- Returns:
The distance in meters between the two coordinates.
- Return type:
float
- dms_to_dd(dms)¶
Convert degrees, minutes, seconds to decimal degrees.
- Parameters:
dms (tuple) – A tuple of (degrees, minutes, seconds).
- Returns:
The decimal degrees equivalent of the DMS input.
- Return type:
float
- normalize()¶
Normalize the coordinates to decimal degrees.
- Returns:
A tuple containing the latitude and longitude in decimal degrees.
- Return type:
tuple
- offset_coordinate(offset, heading)¶
Offset the coordinate by a given distance and heading.
- Parameters:
offset (float) – The distance to offset in meters.
heading (float) – The heading in degrees.
- Returns:
A new Coordinate object with the offset applied.
- Return type:
Flight Controller¶
This module is responsible for managing the flight of ardupilot.
- class MAVez.flight_controller.Flight_Controller(connection_string='tcp:127.0.0.1:5762', logger=None)¶
Bases:
Controller
Manages the flight plan for ardupilot. Extends the Controller class to provide complex flight functionalities.
- Parameters:
connection_string (str) – The connection string to ardupilot.
logger (Logger | None) – Optional logger for logging flight events.
- Raises:
ConnectionError – If the connection to ardupilot fails.
- Returns:
An instance of the Flight_Controller class.
- Return type:
- AIRDROP_NOT_BUILT_ERROR = 303¶
- DETECT_LOAD_ERROR = 302¶
- PREFLIGHT_CHECK_ERROR = 301¶
- append_mission(filename)¶
Append a mission to the mission list.
- Parameters:
filename (str) – The file containing the mission to append.
- Returns:
0 if the mission was appended successfully, otherwise an error code.
- Return type:
int
- decode_error(error_code)¶
Decode an error code.
- Parameters:
error_code (int) – The error code to decode.
- Returns:
A string describing the error.
- Return type:
str
- get_altitude()¶
Get the altitude from ardupilot.
- Returns:
The altitude in meters if successful, otherwise an error code.
- Return type:
float
- jump_to_next_mission_item()¶
Jump to the next mission item.
- Returns:
0 if the jump was successful, otherwise an error code.
- Return type:
int
- preflight_check(land_mission_file, geofence_file, home_coordinate=0, 0, 0)¶
Perform a preflight check. On success, set preflight_check_done to True. Loads the land mission and geofence mission, sets home location, and enables geofence.
- Parameters:
land_mission_file (str) – Path to the file containing the land mission.
geofence_file (str) – Path to the file containing the geofence mission.
home_coordinate (Coordinate) – The home coordinate to set (optional).
- Returns:
0 if the preflight check passed, otherwise an error code.
- Return type:
int
- takeoff(takeoff_mission_file)¶
Takeoff ardupilot. Preflight check must be done first.
- Parameters:
takeoff_mission_file (str) – The file containing the takeoff mission.
- Returns:
0 if the takeoff was successful, otherwise an error code.
- Return type:
int
- wait_and_send_next_mission()¶
Waits for the last waypoint to be reached, clears the mission, sends the next mission, sets mode to auto.
- Returns:
0 if the next mission was sent successfully, otherwise an error code.
- Return type:
int
- wait_for_channel_input(channel, value, timeout=10, wait_time=120, value_tolerance=100)¶
Wait for a specified rc channel to reach a given value
- Parameters:
channel (int) – The channel number to wait for.
value (int) – The value to wait for.
timeout (int) – The maximum time to wait for an update on the channel in seconds.
wait_time (int) – The maximum time to wait for the channel to be set in seconds.
value_tolerance (int) – The tolerance range for the set value.
- Returns:
0 if the channel was set to the desired value, otherwise an error code
- Return type:
int
- wait_for_landed(timeout=60)¶
Wait for ardupilot to signal landed.
- Parameters:
timeout (int) – The maximum time to wait for the landing status in seconds.
- Returns:
0 if the landing was successful, otherwise an error code.
- Return type:
int
- wait_for_waypoint_reached(target, timeout=30)¶
Wait for ardupilot to reach the current waypoint.
- Parameters:
target (int) – The target waypoint index to wait for.
timeout (int) – The maximum time to wait for the waypoint to be reached in seconds.
- Returns:
0 if the waypoint was reached successfully, otherwise an error code.
- Return type:
int
Mission¶
An ardupilot mission.
- class MAVez.mission.Mission(controller, type=0)¶
Bases:
object
Represents a mission for ardupilot.
- Parameters:
controller (Controller) – The controller instance to send the mission through.
type (int) – The type of the mission, default is 0 (waypoint mission).
- Returns:
An instance of the Mission class.
- Return type:
- MISSION_SEND_TIMEOUT = 20¶
- TIMEOUT_ERROR = 101¶
- add_mission_item(mission_item)¶
Add a mission item to the mission.
- Parameters:
mission_item (Mission_Item) – The mission item to add.
- Returns:
0 if the mission item was added successfully.
- Return type:
int
- clear_mission()¶
Clear the mission from the drone.
- Returns:
0 if the mission was cleared successfully, or an error code if there was an error.
- Return type:
int
- decode_error(error_code)¶
Decode an error code into a human-readable string.
- Parameters:
error_code (int) – The error code to decode.
- Returns:
A human-readable string describing the error.
- Return type:
str
- load_mission_from_file(filename, start=0, end=-1, first_seq=-1, overwrite=True)¶
Load a QGC WPL 110 mission from a file. For details on the file format, see: https://mavlink.io/en/file_formats/
- Parameters:
filename (str) – The path to the file containing the mission.
start (int) – The line number to start loading from, default is 0.
end (int) – The line number to stop loading at, default is -1 (load to the end).
first_seq (int) – The sequence number to start from, default is -1 (use the sequence number from the file).
overwrite (bool) – Whether to overwrite the existing mission items, default is True.
- Returns:
0 if the mission was loaded successfully, or an error code if there was an error.
- Return type:
int
- save_mission_to_file(filename)¶
Save the mission to a file in QGC WPL 110 format. For details on the file format, see: https://mavlink.io/en/file_formats/
- Parameters:
filename (str) – The path to the file to save the mission to.
- Returns:
0 if the mission was saved successfully.
- Return type:
int
- send_mission()¶
Send the mission to ardupilot.
- Returns:
0 if the mission was sent successfully, or an error code if there was an error.
- Return type:
int
Mission Item¶
An ardupilot mission item.
- class MAVez.mission_item.Mission_Item(seq, frame, command, current, auto_continue, coordinate, type=0, param1=0, param2=0, param3=0, param4=0)¶
Bases:
object
Represents a mission item for ardupilot.
- Parameters:
seq (int) – Sequence number of the mission item.
frame (int) – Frame of reference for the mission item.
command (int) – Command to be executed.
current (int) – Whether this is the current mission item.
auto_continue (int) – Whether to automatically continue to the next item.
coordinate (Coordinate) – The coordinate for the mission item.
type (int) – Type of the mission item, default is 0.
param1 (float) – Parameter 1 for the command, default is 0.
param2 (float) – Parameter 2 for the command, default is 0.
param3 (float) – Parameter 3 for the command, default is 0.
param4 (float) – Parameter 4 for the command, default is 0.
- Returns:
An instance of the Mission_Item class.
- Return type:
- property message¶
The MAVLink message for the mission item.
- Returns:
The MAVLink message for the mission item.
- Return type:
mavutil.mavlink.MAVLink_mission_item_int_message