From 637b582bbb6a170a3720b31b17c90e2aa6512524 Mon Sep 17 00:00:00 2001 From: Kush Makkapati Date: Sun, 13 Apr 2025 14:49:54 +0100 Subject: [PATCH 1/2] Update reposition function to use set global position int command --- .../app/controllers/flightModesController.py | 1 - radio/app/controllers/navController.py | 60 ++++++++++-------- radio/app/drone.py | 2 - radio/requirements.txt | Bin 3134 -> 3136 bytes 4 files changed, 35 insertions(+), 28 deletions(-) diff --git a/radio/app/controllers/flightModesController.py b/radio/app/controllers/flightModesController.py index 41dc4b37c..1ab678bf6 100644 --- a/radio/app/controllers/flightModesController.py +++ b/radio/app/controllers/flightModesController.py @@ -152,7 +152,6 @@ def setCurrentFlightMode(self, flightMode: int) -> Response: response = self.drone.master.recv_match( type="COMMAND_ACK", blocking=True, timeout=3 ) - print(response) if commandAccepted(response, mavutil.mavlink.MAV_CMD_DO_SET_MODE): self.drone.is_listening = True diff --git a/radio/app/controllers/navController.py b/radio/app/controllers/navController.py index b2f366026..c618d094d 100644 --- a/radio/app/controllers/navController.py +++ b/radio/app/controllers/navController.py @@ -194,38 +194,48 @@ def reposition(self, lat: float, lon: float, alt: float) -> Response: Returns: Response: The response from the reposition command """ + guidedModeSetResult = self.drone.flightModesController.setGuidedMode() + if not guidedModeSetResult["success"]: + return guidedModeSetResult + self.drone.is_listening = False - self.drone.sendCommandInt( - message=mavutil.mavlink.MAV_CMD_DO_REPOSITION, - param2=1, # Change to Guided mode immediately - x=lat, - y=lon, - z=alt, + self.drone.master.mav.set_position_target_global_int_send( + 0, + self.drone.target_system, + self.drone.target_component, + mavutil.mavlink.MAV_FRAME_GLOBAL_RELATIVE_ALT_INT, + 65016, + int(lat * 1e7), + int(lon * 1e7), + alt, + 0, + 0, + 0, + 0, + 0, + 0, + 0, + 0, ) - try: - response = self.drone.master.recv_match(type="COMMAND_ACK", blocking=True) - self.drone.is_listening = True + self.drone.logger.info(f"Reposition command sent to {lat}, {lon}, {alt}m") - if commandAccepted(response, mavutil.mavlink.MAV_CMD_DO_REPOSITION): - self.drone.logger.info("Reposition command send successfully") - return { - "success": True, - "message": "Reposition command sent successfully", - "data": { - "lat": lat, - "lon": lon, - "alt": alt, - }, - } - else: - return { - "success": False, - "message": "Could not reposition", - } + self.drone.is_listening = True + + try: + return { + "success": True, + "message": "Reposition command sent successfully", + "data": { + "lat": lat, + "lon": lon, + "alt": alt, + }, + } except serial.serialutil.SerialException: self.drone.is_listening = True + self.drone.logger.error("Reposition command not accepted, serial exception") return { "success": False, "message": "Could not reposition, serial exception", diff --git a/radio/app/drone.py b/radio/app/drone.py index fbb318bdf..777c321b5 100644 --- a/radio/app/drone.py +++ b/radio/app/drone.py @@ -485,8 +485,6 @@ def checkForMessages(self) -> None: elif msg.msgname == "STATUSTEXT": self.logger.info(msg.text) - # self.logger.debug(msg.msgname) - if msg.msgname in self.message_listeners: self.message_queue.put([msg.msgname, msg]) diff --git a/radio/requirements.txt b/radio/requirements.txt index 803c0801d8bb121340e4f254af3b3254e1ef4b59..50cbdb97756fd433ffaab62ec9e84c2f4f889d16 100644 GIT binary patch delta 18 ZcmdldaX@0jCr(yF20aGT&0je^nE*eP1@8a= delta 16 XcmX>gu}@;dCr)NP2BXd2IX#&GHq`~Y From acb55952f68f07ab1ed7830c9e1a9c9d8bdd4ca6 Mon Sep 17 00:00:00 2001 From: Kush Makkapati Date: Sun, 13 Apr 2025 14:53:36 +0100 Subject: [PATCH 2/2] Add comment for bitmask value --- radio/app/controllers/navController.py | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/radio/app/controllers/navController.py b/radio/app/controllers/navController.py index c618d094d..8a5dcca02 100644 --- a/radio/app/controllers/navController.py +++ b/radio/app/controllers/navController.py @@ -205,7 +205,7 @@ def reposition(self, lat: float, lon: float, alt: float) -> Response: self.drone.target_system, self.drone.target_component, mavutil.mavlink.MAV_FRAME_GLOBAL_RELATIVE_ALT_INT, - 65016, + 65016, # Bitmask to ignore all values except for x, y and z int(lat * 1e7), int(lon * 1e7), alt,