Skip to content

Commit 8f64341

Browse files
committed
Fix ack bug
1 parent 2584840 commit 8f64341

File tree

3 files changed

+16
-16
lines changed

3 files changed

+16
-16
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.7.2"
14+
version = "3.7.3"
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.7.2'
7+
version='3.7.3'
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: 14 additions & 14 deletions
Original file line numberDiff line numberDiff line change
@@ -1,5 +1,5 @@
11
# mav_controller.py
2-
# version: 3.6.0
2+
# version: 3.6.1
33
# Author: Theodore Tasman
44
# Creation Date: 2025-01-30
55
# Last Modified: 2026-03-16
@@ -288,7 +288,7 @@ async def receive_mission_ack(self, timeout: float = 5.0) -> int:
288288
if message == self.TIMEOUT_ERROR:
289289
self.logger.error("[Controller] Receive mission ack timed out")
290290
return self.TIMEOUT_ERROR
291-
elif message.get('type'):
291+
elif message.get('type') is not None:
292292
if message['type'] == 0: # MAV_MISSION_ACCEPTED
293293
self.logger.debug("[Controller] Received mission ack: MAV_MISSION_ACCEPTED")
294294
return 0
@@ -399,7 +399,7 @@ async def set_mode(self, mode: str) -> int:
399399
self.logger.error("[Controller] Set mode command timed out")
400400
return self.TIMEOUT_ERROR
401401
# TODO: verify command being acknowledged is MAV_CMD_DO_SET_MODE
402-
elif message.get('result'):
402+
elif message.get('result') is not None:
403403
if message['result'] == 0:
404404
self.logger.info(f"[Controller] Set mode to {mode}")
405405
return 0
@@ -442,7 +442,7 @@ async def arm(self, force=False) -> int:
442442
return self.TIMEOUT_ERROR
443443

444444
# TODO: verify command being acknowledged is MAV_CMD_COMPONENT_ARM_DISARM
445-
elif message.get('result'):
445+
elif message.get('result') is not None:
446446
if message['result'] == 0:
447447
self.logger.info("[Controller] Vehicle armed successfully")
448448
return 0
@@ -486,7 +486,7 @@ async def disarm(self, force=False) -> int:
486486
return self.TIMEOUT_ERROR
487487

488488
# TODO: verify command being acknowledged is MAV_CMD_COMPONENT_ARM_DISARM
489-
elif message.get('result'):
489+
elif message.get('result') is not None:
490490
if message['result'] == 0:
491491
self.logger.info("[Controller] Disarmed successfully")
492492
return 0
@@ -527,7 +527,7 @@ async def enable_geofence(self) -> int:
527527
return self.TIMEOUT_ERROR
528528

529529
# TODO: verify command being acknowledged is MAV_CMD_DO_FENCE_ENABLE
530-
elif message.get('result'):
530+
elif message.get('result') is not None:
531531
if message['result'] == 0:
532532
self.logger.info("[Controller] Geofence enabled successfully")
533533
return 0
@@ -571,7 +571,7 @@ async def disable_geofence(self, floor_only=False) -> int:
571571
return self.TIMEOUT_ERROR
572572

573573
# TODO: verify command being acknowledged is MAV_CMD_DO_FENCE_ENABLE
574-
elif message.get('result'):
574+
elif message.get('result') is not None:
575575
if message['result'] == 0:
576576
self.logger.info("[Controller] Geofence disabled successfully")
577577
return 0
@@ -628,7 +628,7 @@ async def set_home(self, home_coordinate=Coordinate(0, 0, 0)) -> int:
628628
return self.TIMEOUT_ERROR
629629

630630
# TODO: verify command being acknowledged is MAV_CMD_DO_SET_HOME
631-
elif message.get('result'):
631+
elif message.get('result') is not None:
632632
if message['result'] == 0:
633633
self.logger.info(f"[Controller] Home location set to {home_coordinate}")
634634
return 0
@@ -670,7 +670,7 @@ async def set_servo(self, servo_number: int, pwm: int) -> int:
670670
if message == self.TIMEOUT_ERROR:
671671
self.logger.error("[Controller] Set servo command timed out")
672672
return self.TIMEOUT_ERROR
673-
elif message.get('result'):
673+
elif message.get('result') is not None:
674674
if message['result'] == 0:
675675
self.logger.info(f"[Controller] Set servo {servo_number} to {pwm} PWM")
676676
return 0
@@ -776,7 +776,7 @@ async def receive_landing_status(self, timeout=TIMEOUT_DURATION) -> int:
776776
if message == self.TIMEOUT_ERROR:
777777
self.logger.error("[Controller] Receive landing status timed out")
778778
return self.TIMEOUT_ERROR
779-
elif message.get('landed_state'):
779+
elif message.get('landed_state') is not None:
780780
self.logger.debug(f"[Controller] Received landing status: {MAVLandedState.string(message['landed_state'])}")
781781
return message['landed_state'] if message['landed_state'] is not None else self.BAD_RESPONSE_ERROR
782782
else:
@@ -815,7 +815,7 @@ async def set_message_interval(self, message_type: MAVMessage, interval: int) ->
815815
if message == self.TIMEOUT_ERROR:
816816
self.logger.error("[Controller] Set message interval command timed out")
817817
return self.TIMEOUT_ERROR
818-
elif message.get('result'):
818+
elif message.get('result') is not None:
819819
if message['result'] == 0:
820820
self.logger.info(f"[Controller] Set message interval for {message_type} to {interval} μs")
821821
return 0
@@ -857,7 +857,7 @@ async def disable_message_interval(self, message_type: MAVMessage) -> int:
857857
if message == self.TIMEOUT_ERROR:
858858
self.logger.error("[Controller] Disable message interval command timed out")
859859
return self.TIMEOUT_ERROR
860-
elif message.get('result'):
860+
elif message.get('result') is not None:
861861
if message['result'] == 0:
862862
self.logger.info(f"[Controller] Disabled message interval for {message_type}")
863863
return 0
@@ -915,7 +915,7 @@ async def set_current_mission_index(self, index: int, reset: bool = False) -> in
915915
if message == self.TIMEOUT_ERROR:
916916
self.logger.error("[Controller] Set current mission index command timed out")
917917
return self.TIMEOUT_ERROR
918-
elif message.get('result'):
918+
elif message.get('result') is not None:
919919
if message['result'] == 0:
920920
self.logger.debug(f"[Controller] Set current mission index to {index}")
921921
return 0
@@ -957,7 +957,7 @@ async def start_mission(self, start_index, end_index) -> int:
957957
if message == self.TIMEOUT_ERROR:
958958
self.logger.error("[Controller] Start mission command timed out")
959959
return self.TIMEOUT_ERROR
960-
elif message.get('result'):
960+
elif message.get('result') is not None:
961961
if message['result'] == 0:
962962
self.logger.debug(f"[Controller] Started mission from {start_index} to {end_index}")
963963
return 0

0 commit comments

Comments
 (0)