Controllers¶
Basic Controller¶
This module is responsible for controlling ardupilot.
- class MAVez.controller.Controller(connection_string='tcp:127.0.0.1:5762', baud=57600, logger=None, message_host='127.0.0.1', message_port=5555, message_topic='', timesync=False)¶
Bases:
objectController 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|None) – Logger instance for logging messages (optional).message_host (str) – The host for the messaging system. Default is “127.0.0.1”.
message_port (int) – The port for the messaging system. Default is 5555.
message_topic (str) – The topic prefix for the messaging system. Default is “”.
- Raises:
ConnectionError – If the connection to ardupilot fails.
- BAD_RESPONSE_ERROR = 102¶
- TIMEOUT_DURATION = 5¶
- TIMEOUT_ERROR = 101¶
- UNKNOWN_MODE = 111¶
- async 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
- async clock_synchronizer()¶
Periodically sync the flight controller clock with the system clock.
- 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
- async 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
- async disable_message_interval(message_type)¶
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
- async 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
- async enable_geofence()¶
Enable the geofence.
- Returns:
0 if the geofence was enabled successfully, 101 if the response timed out.
- Return type:
int
- async message_pump()¶
Continuously read MAVLink messages and push them into a queue.
- Returns:
None
- monotonic_time_ns()¶
Get the current monotonic time in nanoseconds since the controller started.
- Returns:
The current monotonic time in nanoseconds since the controller started.
- Return type:
int
- async receive_attitude(timeout=5)¶
Wait for an attitude message from ardupilot.
- Parameters:
timeout (int) – The timeout duration in seconds. Default is 5 seconds.
- Return type:
int|Any- Returns:
response if an attitude message was received, TIMEOUT_ERROR (101) if the response timed out.
- async receive_channel_input()¶
Wait for an RC_CHANNELS message from ardupilot.
- Parameters:
timeout (int) – The timeout duration in seconds. Default is 5 seconds.
- Return type:
int|Any- Returns:
response if an RC_CHANNELS message was received, 101 if the response timed out
- async receive_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
- async receive_gps(timeout=5, normalize_time=False)¶
Wait for a GLOBAL_POSITION_INT message from ardupilot.
- Parameters:
timeout (int) – The timeout duration in seconds. Default is 5 seconds.
normalize_time (bool) – If True, the timestamp will be normalized to the controller’s clock. Default is False.
- Returns:
A Coordinate object containing the GPS data if received, TIMEOUT_ERROR (101) if the response timed out.
- Return type:
- async 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
- async receive_message(message_type, timeout=5.0)¶
Wait for a specific MAVLink message type from ardupilot.
- Parameters:
message_type (str) – The type of MAVLink message to wait for.
timeout (float) – The timeout duration in seconds. Default is 5 seconds.
- Returns:
Dictionary representation of MAVLink message if successful, TIMEOUT_ERROR (101) if the response timed out.
- Return type:
Dict
- async receive_mission_ack(timeout=5.0)¶
Wait for a mission ack from ardupilot.
- Parameters:
timeout (float) – The timeout duration in seconds. Default is 5 seconds.
- Returns:
0 if a mission ack was received, error code if there was an error, 101 if the response timed out.
- Return type:
int
- async receive_mission_item_reached(timeout=240)¶
Wait for a mission item reached message from ardupilot.
- Parameters:
timeout (int) – The timeout duration in seconds. Default is 240 seconds.
- Returns:
The sequence number of the reached mission item if received, TIMEOUT_ERROR (101) if the response timed out.
- Return type:
int
- async receive_mission_request(timeout=5.0)¶
Wait for a mission request from ardupilot.
- Parameters:
timeout (float) – The timeout duration in seconds. Default is 5 seconds.
- Returns:
Mission index if a mission request was received, 101 if the response timed out, 102 if a bad response was received.
- Return type:
int
- async receive_timesync(timeout=5)¶
Wait for a timesync message from ardupilot.
- Parameters:
timeout (int) – The timeout duration in seconds. Default is 5 seconds.
- Return type:
int|Any- Returns:
response if a timesync message was received, TIMEOUT_ERROR (101) if the response timed out.
- async receive_wind()¶
Wait for a wind_cov message from ardupilot.
- Parameters:
timeout (int) – The timeout duration in seconds. Default is 5 seconds.
- Return type:
int|Any- Returns:
response if a wind_cov message was received, 101 if the response timed out
- request_timesync(current_time)¶
Request a timesync message from ardupilot.
- Parameters:
current_time (int) – The current time in nanoseconds.
- Returns:
0 if the timesync request was sent successfully.
- Return type:
int
- 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.
- Return type:
int
- async set_current_mission_index(index, reset=False)¶
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
- async set_home(home_coordinate=0, 0, 0, timestamp: 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
- async set_message_interval(message_type, interval)¶
Set the message interval for the specified message type.
- Parameters:
message_type (int) – The type of message to set the interval for.
interval (int) – The interval in microseconds 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
- async 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
- async 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
- async start()¶
Start the controller by initiating the message pump.
- Returns:
None
- async 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
- async stop()¶
Stop the controller by cancelling running tasks.
- Returns:
None
- async sync_clocks()¶
Sync the flight controller clock with the system clock.
- Returns:
0 if the clocks were synced successfully, otherwise an error code.
- Return type:
int
Flight Controller¶
This module is responsible for managing the flight of ardupilot.
- class MAVez.flight_controller.FlightController(connection_string='tcp:127.0.0.1:5762', baud=57600, logger=None, message_host='127.0.0.1', message_port=5555, message_topic='', timesync=False)¶
Bases:
ControllerManages the flight plan for ardupilot. Extends the Controller class to provide complex flight functionalities.
- Parameters:
connection_string (str) – The connection string to ardupilot.
baud (int) – The baud rate for the connection. Default is 57600.
logger (Logger | None) – Optional logger for logging flight events.
message_host (str) – The host for messaging.
message_host – The host for the messaging system. Default is “127.0.0.1”.
message_port (int) – The port for the messaging system. Default is 5555.
message_topic (str) – The topic prefix for the messaging system. Default is “”.
timesync (bool) – Whether to enable time synchronization. Default is False.
- Raises:
ConnectionError – If the connection to ardupilot fails.
- Returns:
An instance of the Flight_Controller class.
- Return type:
Flight_Controller
- BAD_RESPONSE_ERROR = 102¶
- INVALID_MISSION_ERROR = 301¶
- Literal = typing.Literal¶
- TIMEOUT_ERROR = 101¶
- UNKNOWN_MODE_ERROR = 111¶
- 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
- async auto_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
- 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
- async 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
- async set_geofence(geofence_filename)¶
Send and enable the geofence from a file.
- Parameters:
geofence_filename (str) – The file containing the geofence mission.
- Returns:
0 if the geofence was set successfully, otherwise an error code.
- Return type:
int
- async takeoff(takeoff_mission_filename)¶
Takeoff ardupilot.
- Parameters:
takeoff_mission_filename (str) – The file containing the takeoff mission.
- Returns:
0 if the takeoff was successful, otherwise an error code.
- Return type:
int
- async wait_for_channel_input(channel, value, 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.
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
- async wait_for_landing(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
- async wait_for_waypoint(target)¶
Wait for ardupilot to reach the current waypoint.
- Parameters:
target (int) – The target waypoint index to wait for.
- Returns:
0 if the waypoint was reached successfully, otherwise an error code.
- Return type:
int