2626from MAVez .enums .mav_landed_state import MAVLandedState
2727from MAVez .enums .mav_mission_result import MAVMissionResult
2828from MAVez .enums .mav_result import MAVResult
29+ from MAVez .enums .mav_message import MAVMessage
2930
3031
3132class 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
0 commit comments