Skip to content

Commit 8d2a037

Browse files
committed
Create mission from file, use enums
1 parent bba1b9a commit 8d2a037

File tree

5 files changed

+28
-15
lines changed

5 files changed

+28
-15
lines changed

docs/source/conf.py

Lines changed: 1 addition & 1 deletion
Original file line numberDiff line numberDiff line change
@@ -11,7 +11,7 @@
1111
project = "MAVez"
1212
copyright = "2025, The Pennsylvania State University Unmanned Aerial Systems Club"
1313
author = "The Pennsylvania State University Unmanned Aerial Systems Club"
14-
version = "3.6.1"
14+
version = "3.7.0"
1515

1616
# -- General configuration ---------------------------------------------------
1717
# https://www.sphinx-doc.org/en/master/usage/configuration.html#general-configuration

pyproject.toml

Lines changed: 1 addition & 1 deletion
Original file line numberDiff line numberDiff line change
@@ -4,7 +4,7 @@ build-backend = "setuptools.build_meta"
44

55
[project]
66
name='MAVez'
7-
version='3.6.1'
7+
version='3.7.0'
88
description='An intuitive MAVLink library for ArduPilot via pymavlink'
99
authors=[
1010
{name='The Pennsylvania State University Unmanned Aerial Systems Club', email='psuuasofficial@gmail.com'}

src/MAVez/controller.py

Lines changed: 7 additions & 6 deletions
Original file line numberDiff line numberDiff line change
@@ -26,6 +26,7 @@
2626
from MAVez.enums.mav_landed_state import MAVLandedState
2727
from MAVez.enums.mav_mission_result import MAVMissionResult
2828
from MAVez.enums.mav_result import MAVResult
29+
from MAVez.enums.mav_message import MAVMessage
2930

3031

3132
class Controller:
@@ -362,7 +363,7 @@ def send_clear_mission(self) -> int:
362363
self.logger.info("[Controller] Sent clear mission")
363364
return 0
364365

365-
async def set_mode(self, mode) -> int:
366+
async def set_mode(self, mode: str) -> int:
366367
"""
367368
Set the ardupilot mode.
368369
@@ -638,7 +639,7 @@ async def set_home(self, home_coordinate=Coordinate(0, 0, 0)) -> int:
638639
self.logger.error("[Controller] Bad response received for set home location")
639640
return self.BAD_RESPONSE_ERROR
640641

641-
async def set_servo(self, servo_number, pwm) -> int:
642+
async def set_servo(self, servo_number: int, pwm: int) -> int:
642643
"""
643644
Set the a servo to a specified PWM value.
644645
@@ -782,7 +783,7 @@ async def receive_landing_status(self, timeout=TIMEOUT_DURATION) -> int:
782783
self.logger.error("[Controller] Bad response received for landing status")
783784
return self.BAD_RESPONSE_ERROR
784785

785-
async def set_message_interval(self, message_type: int, interval: int) -> int:
786+
async def set_message_interval(self, message_type: MAVMessage, interval: int) -> int:
786787
"""
787788
Set the message interval for the specified message type.
788789
@@ -799,7 +800,7 @@ async def set_message_interval(self, message_type: int, interval: int) -> int:
799800
0, # target_component
800801
mavutil.mavlink.MAV_CMD_SET_MESSAGE_INTERVAL, # command
801802
0, # confirmation
802-
message_type, # param1
803+
message_type.value, # param1
803804
interval, # param2
804805
0, # param3
805806
0, # param4
@@ -825,7 +826,7 @@ async def set_message_interval(self, message_type: int, interval: int) -> int:
825826
self.logger.error("[Controller] Bad response received for set message interval")
826827
return self.BAD_RESPONSE_ERROR
827828

828-
async def disable_message_interval(self, message_type) -> int:
829+
async def disable_message_interval(self, message_type: MAVMessage) -> int:
829830
"""
830831
Disable the message interval for the specified message type.
831832
@@ -841,7 +842,7 @@ async def disable_message_interval(self, message_type) -> int:
841842
0, # target_component
842843
mavutil.mavlink.MAV_CMD_SET_MESSAGE_INTERVAL, # command
843844
0, # confirmation
844-
message_type, # param1
845+
message_type.value, # param1
845846
-1, # param2 # -1 disables the message
846847
0, # param3
847848
0, # param4

src/MAVez/flight_controller.py

Lines changed: 7 additions & 6 deletions
Original file line numberDiff line numberDiff line change
@@ -15,6 +15,7 @@
1515
from logging import Logger
1616
from MAVez.mission import Mission
1717
from MAVez.controller import Controller
18+
from MAVez.enums.mav_message import MAVMessage
1819
import time
1920

2021
class FlightController(Controller):
@@ -137,7 +138,7 @@ async def takeoff(self, takeoff_mission_filename: str) -> int:
137138

138139
return 0
139140

140-
def append_mission(self, filename) -> int:
141+
def append_mission(self, filename: str) -> int:
141142
"""
142143
Append a mission to the mission list.
143144
@@ -159,7 +160,7 @@ def append_mission(self, filename) -> int:
159160
self.mission_queue.append(mission)
160161
return 0
161162

162-
async def wait_for_waypoint(self, target) -> int:
163+
async def wait_for_waypoint(self, target: int) -> int:
163164
"""
164165
Wait for ardupilot to reach the current waypoint.
165166
@@ -252,8 +253,8 @@ async def wait_for_landing(self, timeout=60) -> int:
252253

253254
# start receiving landing status
254255
response = await self.set_message_interval(
255-
message_type=245, interval=100000
256-
) # 245 is landing status (EXTENDED_SYS_STATE), 1e6 is 1 second
256+
message_type=MAVMessage.EXTENDED_SYS_STATE, interval=100000 # 1 second
257+
)
257258
if response:
258259
self.logger.critical("[Flight] Failed waiting for landing.")
259260
return response
@@ -281,8 +282,8 @@ async def wait_for_landing(self, timeout=60) -> int:
281282

282283
# stop receiving landing status
283284
response = await self.disable_message_interval(
284-
message_type=245
285-
) # 245 is landing status (EXTENDED_SYS_STATE)
285+
message_type=MAVMessage.EXTENDED_SYS_STATE
286+
)
286287
if response:
287288
self.logger.error("[Flight] Error waiting for landing.")
288289
return response

src/MAVez/mission.py

Lines changed: 12 additions & 1 deletion
Original file line numberDiff line numberDiff line change
@@ -9,6 +9,7 @@
99
An ardupilot mission.
1010
"""
1111

12+
from typing import Optional
1213
from uas_messenger.message import Message
1314

1415
from MAVez.mission_item import MissionItem
@@ -74,6 +75,16 @@ def decode_error(self, error_code: int) -> str:
7475

7576
return error_codes.get(error_code, f"\nUNKNOWN ERROR ({error_code})\n")
7677

78+
@classmethod
79+
def from_file(cls, controller: Controller, filepath: str, type: int=0) -> Optional['Mission']:
80+
mission = cls(controller, type)
81+
res = mission.load_mission_from_file(filepath)
82+
if res != 0:
83+
if controller.logger:
84+
controller.logger.error(f"[Mission] Failed to load mission: {mission.decode_error(res)}")
85+
return None
86+
return mission
87+
7788
def load_mission_from_file(
7889
self, filename: str, start: int=0, end: int=-1, first_seq: int=-1, overwrite: bool=True
7990
):
@@ -323,7 +334,7 @@ def get_mission_length(filepath: str, logger: logging.Logger | None = None) -> i
323334
with open(filepath, 'r') as f:
324335
return len(f.readlines()) - 1 # Subtract 1 for the header line
325336
except Exception as e:
326-
print(f"Error reading mission file {filepath}: {e}")
337+
logger.error(f"[Mission] Error reading mission file {filepath}: {e}") if logger else None
327338
return -1
328339

329340

0 commit comments

Comments
 (0)