From b6dca2b80ae2d62b0e073973b11d040b2cd558cd Mon Sep 17 00:00:00 2001 From: fadilm777 Date: Sun, 10 Aug 2025 20:38:41 -0400 Subject: [PATCH 1/9] added land function --- mavctl/messages/Navigator.py | 53 ++++++++++++++++++++++++++++++++++++ mavctl/messages/advanced.py | 30 +++++++++++++++++--- 2 files changed, 79 insertions(+), 4 deletions(-) diff --git a/mavctl/messages/Navigator.py b/mavctl/messages/Navigator.py index ebd6b36..7b11af9 100644 --- a/mavctl/messages/Navigator.py +++ b/mavctl/messages/Navigator.py @@ -1,3 +1,4 @@ +from typing import Literal, Optional from pymavlink import mavutil import time from messages import util @@ -232,6 +233,58 @@ def vtol_takeoff(self, altitude, pitch=15): self.wait_target_reached(LocationLocal(0, 0, -altitude)) + def land(self, + land_mode: Literal[0,1,2], + abort_alt: float = 0, + yaw_angle: Optional[float] = None, + latitude: Optional[float] = None, + longitude: Optional[float] = None, + ): + """ + Initiate a landing sequence. + + Parameters: + abort_alt (float): + Minimum target altitude if landing is aborted + use system default if not specified. Units: meters. + + land_mode (0, 1, 2): + Precision land mode: + 0: Precision land disabled + 1: opportunistic + 2: required + + yaw_angle (float, optional): + Desired yaw angle in degrees. + Default is to follow the current system yaw heading mode + + latitude (float, optional): + Latitude in decimal degrees. + + longitude (float, optional): + Longitude in decimal degrees. + """ + + # Runtime validation + if land_mode not in (0, 1, 2): + raise ValueError("land_mode must be 0, 1, or 2.") + + if land_mode == 0 and (latitude is None or longitude is None): + raise ValueError("specify latitude and longitude for disabled precision landing") + + self.mav.mav.command_long_send( + self.mav.target_system, + self.mav.target_component, + mavutil.mavlink.MAV_CMD_NAV_LAND, + 0, + abort_alt, + land_mode, + 0, + yaw_angle, + latitude, + longitude, + 0) + #TODO:Add some sort of blocking function to stop execution till drone has landed def return_to_launch(self): print("MAVCTL: RTL") diff --git a/mavctl/messages/advanced.py b/mavctl/messages/advanced.py index f81a675..2e744ac 100644 --- a/mavctl/messages/advanced.py +++ b/mavctl/messages/advanced.py @@ -1,7 +1,10 @@ -import time +import time +from typing import Literal +from math import radians, atan + +from mavctl.messages.Navigator import Navigator from messages import util from messages.location import LocationGlobal, LocationGlobalRelative, LocationLocal -from math import radians, atan from messages.util import Heading, LatLon_to_Distance # This file is meant for implementing more advanced features in mavctl @@ -9,8 +12,9 @@ # This tests the wait target reached and has been verified to work def simple_goto_local(master, x, y, z): - - # Mimics simple_goto from dronekit, includes the right yaw angle so that the drone faces where it needs to go. + """Mimics simple_goto from dronekit, + includes the right yaw angle so that + the drone faces where it needs to go.""" type_mask = master.generate_typemask([0, 1, 2, 9]) angle = atan(y/x) @@ -27,3 +31,21 @@ def simple_goto_global(master, lat, lon, alt): print("Waiting for drone to reach target") master.wait_target_reached_global(LocationGlobal(lat, lon, alt)) print("reached target") + +def do_precision_landing(master: Navigator, + mode: Literal["REQUIRED", "OPPORTUNISTIC"]) -> None: + """ + This function sets the drone into precision landing mode. + + Parameters: + mode (str): Either "REQUIRED" or "OPPORTUNISTIC". + + REQUIRED: + The vehicle searches for a target if none is visible when + landing is initiated, and performs precision landing if found. + + OPPORTUNISTIC: + The vehicle uses precision landing only if the target is visible + at landing initiation; otherwise it performs a normal landing. + """ + pass From 83949d345e922696359cb56aaf85174c27373b97 Mon Sep 17 00:00:00 2001 From: fadilm777 Date: Tue, 12 Aug 2025 16:02:51 -0400 Subject: [PATCH 2/9] added precision landing advanced function --- mavctl/messages/Navigator.py | 42 +++++++++++++++++++++++++++++++----- mavctl/messages/advanced.py | 18 ++++++++++++++-- 2 files changed, 53 insertions(+), 7 deletions(-) diff --git a/mavctl/messages/Navigator.py b/mavctl/messages/Navigator.py index 7b11af9..351c927 100644 --- a/mavctl/messages/Navigator.py +++ b/mavctl/messages/Navigator.py @@ -1,21 +1,34 @@ -from typing import Literal, Optional -from pymavlink import mavutil +from typing import Literal, Optional, Tuple +from dataclasses import dataclass import time +from math import sqrt + +from pymavlink import mavutil + from messages import util from messages.location import LocationGlobal, LocationGlobalRelative, LocationLocal, Velocity -from math import sqrt + +@dataclass +class LandingTarget: + """ + Data class to store position of landing target in MAV_FRAME_BODY_FRD frame. + FRD local frame aligned to the vehicle's attitude (x: Forward, y: Right, z: Down) + with an origin that travels with vehicle. + """ + x: float + y: float + z: float class Navigator: def __init__(self, mav): self.mav = mav - + self.TOLERANCE_CE = 0.05 # For checking if the target position has been reached. This is a coefficient which is multiplied by the distance travelled. # The reason why a coefficient method was chosen is because the position tolerance should be a function of distance as opposed to being a constant # This method is preferred so that what happened at AEAC 2025 doesnt happen again. - def arm(self): """ Arms the drone. @@ -504,3 +517,22 @@ def wait_target_reached_global(self, target, timeout = 30): return True + def broadcast_landing_target(self, landing_target: LandingTarget) -> None: + """ + This function broadcasts the position of the landing target in MAV_FRAME_BODY_FRD frame. + """ + + time_usec = int(time.time() * 1000000) # convert to microseconds + + self.mav.mav.landing_target_send(time_usec=time_usec, + frame=mavutil.mavlink.MAV_FRAME_BODY_FRD, + x=landing_target.x, + y=landing_target.y, + z=landing_target.z, + q=(1,0,0,0), + type=mavutil.mavlink.LANDING_TARGET_TYPE_VISION_OTHER, + position_valid=1) + + #TODO: Add implementation to return altitude reported by altimeter + def get_rel_altitude(self) -> float: + raise NotImplementedError diff --git a/mavctl/messages/advanced.py b/mavctl/messages/advanced.py index 2e744ac..cc70da7 100644 --- a/mavctl/messages/advanced.py +++ b/mavctl/messages/advanced.py @@ -2,7 +2,7 @@ from typing import Literal from math import radians, atan -from mavctl.messages.Navigator import Navigator +from mavctl.messages.Navigator import LandingTarget, Navigator from messages import util from messages.location import LocationGlobal, LocationGlobalRelative, LocationLocal from messages.util import Heading, LatLon_to_Distance @@ -33,11 +33,15 @@ def simple_goto_global(master, lat, lon, alt): print("reached target") def do_precision_landing(master: Navigator, + imaging_analysis_delegate, mode: Literal["REQUIRED", "OPPORTUNISTIC"]) -> None: """ This function sets the drone into precision landing mode. + Only call this function when broadcasting landing target. Parameters: + imaging_analysis_delegate: an object to the ImageAnalysisDelegate class + mode (str): Either "REQUIRED" or "OPPORTUNISTIC". REQUIRED: @@ -48,4 +52,14 @@ def do_precision_landing(master: Navigator, The vehicle uses precision landing only if the target is visible at landing initiation; otherwise it performs a normal landing. """ - pass + def callback(_, coords): + altitude = master.get_rel_altitude() + target = LandingTarget(x=coords[0], y=coords[1], z=altitude) + master.broadcast_landing_target(target) + + imaging_analysis_delegate.subscribe(callback) + + if mode == "OPPORTUNISTIC": + master.land(land_mode=1) + elif mode == "REQUIRED": + master.land(land_mode=2) From 5fcce8a845b8f107ef5d63fefc5daa3a669e1355 Mon Sep 17 00:00:00 2001 From: fadilm777 Date: Tue, 12 Aug 2025 16:06:03 -0400 Subject: [PATCH 3/9] some comment fixes --- mavctl/messages/Navigator.py | 3 --- mavctl/messages/advanced.py | 1 - 2 files changed, 4 deletions(-) diff --git a/mavctl/messages/Navigator.py b/mavctl/messages/Navigator.py index 351c927..a4e3118 100644 --- a/mavctl/messages/Navigator.py +++ b/mavctl/messages/Navigator.py @@ -279,9 +279,6 @@ def land(self, """ # Runtime validation - if land_mode not in (0, 1, 2): - raise ValueError("land_mode must be 0, 1, or 2.") - if land_mode == 0 and (latitude is None or longitude is None): raise ValueError("specify latitude and longitude for disabled precision landing") diff --git a/mavctl/messages/advanced.py b/mavctl/messages/advanced.py index cc70da7..620c400 100644 --- a/mavctl/messages/advanced.py +++ b/mavctl/messages/advanced.py @@ -37,7 +37,6 @@ def do_precision_landing(master: Navigator, mode: Literal["REQUIRED", "OPPORTUNISTIC"]) -> None: """ This function sets the drone into precision landing mode. - Only call this function when broadcasting landing target. Parameters: imaging_analysis_delegate: an object to the ImageAnalysisDelegate class From 4f757edc3df38e3cf6ca60eb8e047b508a9ba369 Mon Sep 17 00:00:00 2001 From: HameedFawwaz Date: Tue, 12 Aug 2025 23:42:36 -0600 Subject: [PATCH 4/9] Resolved TODOs --- mavctl/messages/Navigator.py | 26 +++++++++++++++++++++----- mavctl/messages/advanced.py | 2 +- mavctl/messages/location.py | 8 ++++++++ 3 files changed, 30 insertions(+), 6 deletions(-) diff --git a/mavctl/messages/Navigator.py b/mavctl/messages/Navigator.py index a4e3118..8d2b938 100644 --- a/mavctl/messages/Navigator.py +++ b/mavctl/messages/Navigator.py @@ -6,7 +6,7 @@ from pymavlink import mavutil from messages import util -from messages.location import LocationGlobal, LocationGlobalRelative, LocationLocal, Velocity +from messages.location import LocationGlobal, LocationGlobalRelative, LocationLocal, Velocity, Altitude @dataclass class LandingTarget: @@ -194,6 +194,20 @@ def get_velocity(self): return Velocity(north, east, down) + def get_altitude(self): + """ + Gets the current system altitude, of various types + """ + msg = self.mav.recv_match(type='ALTITUDE', blocking=True) + if msg: + mono = msg.altitude_monotonic + amsl = msg.altiude_amsl + local = msg.altitude_local + relative = msg.altitude_relative + terrain = msg.altitude_terrain + clearance = msg.bottom_clearance + + return Altitude(mono, amsl, local, relative, terrain, clearance) def takeoff(self, altitude, pitch=15): @@ -294,7 +308,12 @@ def land(self, latitude, longitude, 0) - #TODO:Add some sort of blocking function to stop execution till drone has landed + + current_position = self.get_local_position() + target = (current_position.north, current_position.down, 0) + + self.wait_target_reached(target) + def return_to_launch(self): print("MAVCTL: RTL") @@ -530,6 +549,3 @@ def broadcast_landing_target(self, landing_target: LandingTarget) -> None: type=mavutil.mavlink.LANDING_TARGET_TYPE_VISION_OTHER, position_valid=1) - #TODO: Add implementation to return altitude reported by altimeter - def get_rel_altitude(self) -> float: - raise NotImplementedError diff --git a/mavctl/messages/advanced.py b/mavctl/messages/advanced.py index 620c400..33379ab 100644 --- a/mavctl/messages/advanced.py +++ b/mavctl/messages/advanced.py @@ -52,7 +52,7 @@ def do_precision_landing(master: Navigator, at landing initiation; otherwise it performs a normal landing. """ def callback(_, coords): - altitude = master.get_rel_altitude() + altitude = master.get_altitude().terrain # Gets the altitude above the terrain (as seen by an altimeter) target = LandingTarget(x=coords[0], y=coords[1], z=altitude) master.broadcast_landing_target(target) diff --git a/mavctl/messages/location.py b/mavctl/messages/location.py index 36f2aaf..dc20821 100644 --- a/mavctl/messages/location.py +++ b/mavctl/messages/location.py @@ -26,6 +26,14 @@ def __init__(self, north, east, down): self.east = east self.down = down +class Altitude(object): + def __init__(self, mono, amsl, local, relative, terrain, clearance): + self.mono = mono + self.amsl = amsl + self.local = local + self.relative = relative + self.terrain = terrain + self.clearance = clearance class Battery(object): From 6d7af2b395043098df27eaa29050396c983be33b Mon Sep 17 00:00:00 2001 From: fadilm777 Date: Sat, 13 Sep 2025 10:56:37 -0600 Subject: [PATCH 5/9] move advanced function --- mavctl/messages/advanced.py | 33 +-------------------------------- 1 file changed, 1 insertion(+), 32 deletions(-) diff --git a/mavctl/messages/advanced.py b/mavctl/messages/advanced.py index 33379ab..8be762f 100644 --- a/mavctl/messages/advanced.py +++ b/mavctl/messages/advanced.py @@ -1,5 +1,5 @@ import time -from typing import Literal +from typing import Callable, Literal from math import radians, atan from mavctl.messages.Navigator import LandingTarget, Navigator @@ -31,34 +31,3 @@ def simple_goto_global(master, lat, lon, alt): print("Waiting for drone to reach target") master.wait_target_reached_global(LocationGlobal(lat, lon, alt)) print("reached target") - -def do_precision_landing(master: Navigator, - imaging_analysis_delegate, - mode: Literal["REQUIRED", "OPPORTUNISTIC"]) -> None: - """ - This function sets the drone into precision landing mode. - - Parameters: - imaging_analysis_delegate: an object to the ImageAnalysisDelegate class - - mode (str): Either "REQUIRED" or "OPPORTUNISTIC". - - REQUIRED: - The vehicle searches for a target if none is visible when - landing is initiated, and performs precision landing if found. - - OPPORTUNISTIC: - The vehicle uses precision landing only if the target is visible - at landing initiation; otherwise it performs a normal landing. - """ - def callback(_, coords): - altitude = master.get_altitude().terrain # Gets the altitude above the terrain (as seen by an altimeter) - target = LandingTarget(x=coords[0], y=coords[1], z=altitude) - master.broadcast_landing_target(target) - - imaging_analysis_delegate.subscribe(callback) - - if mode == "OPPORTUNISTIC": - master.land(land_mode=1) - elif mode == "REQUIRED": - master.land(land_mode=2) From 3ebf782aaf560bf629d26c31ec18f02bdd72b0a5 Mon Sep 17 00:00:00 2001 From: fadilm777 Date: Sat, 13 Sep 2025 13:43:19 -0600 Subject: [PATCH 6/9] navigator renaming --- mavctl/messages/{Navigator.py => navigator.py} | 6 +++--- 1 file changed, 3 insertions(+), 3 deletions(-) rename mavctl/messages/{Navigator.py => navigator.py} (99%) diff --git a/mavctl/messages/Navigator.py b/mavctl/messages/navigator.py similarity index 99% rename from mavctl/messages/Navigator.py rename to mavctl/messages/navigator.py index 8d2b938..233299b 100644 --- a/mavctl/messages/Navigator.py +++ b/mavctl/messages/navigator.py @@ -15,9 +15,9 @@ class LandingTarget: FRD local frame aligned to the vehicle's attitude (x: Forward, y: Right, z: Down) with an origin that travels with vehicle. """ - x: float - y: float - z: float + forward: float + right: float + altitude: float class Navigator: From eb02a4ea4fc2d2a12db435d881efd1afb6ab9d3d Mon Sep 17 00:00:00 2001 From: Fawwaz Hameed Date: Sat, 13 Sep 2025 20:42:01 -0600 Subject: [PATCH 7/9] still broken :(( --- mavctl/messages/advanced.py | 8 +++---- mavctl/messages/navigator.py | 43 +++++++++++++++++++++++++----------- mavctl/messages/util.py | 3 +-- 3 files changed, 35 insertions(+), 19 deletions(-) diff --git a/mavctl/messages/advanced.py b/mavctl/messages/advanced.py index 8be762f..98ac971 100644 --- a/mavctl/messages/advanced.py +++ b/mavctl/messages/advanced.py @@ -2,10 +2,10 @@ from typing import Callable, Literal from math import radians, atan -from mavctl.messages.Navigator import LandingTarget, Navigator -from messages import util -from messages.location import LocationGlobal, LocationGlobalRelative, LocationLocal -from messages.util import Heading, LatLon_to_Distance +from mavctl.messages.navigator import LandingTarget, Navigator +from mavctl.messages import util +from mavctl.messages.location import LocationGlobal, LocationGlobalRelative, LocationLocal +from mavctl.messages.util import Heading, LatLon_to_Distance # This file is meant for implementing more advanced features in mavctl diff --git a/mavctl/messages/navigator.py b/mavctl/messages/navigator.py index 233299b..52aa81f 100644 --- a/mavctl/messages/navigator.py +++ b/mavctl/messages/navigator.py @@ -5,8 +5,8 @@ from pymavlink import mavutil -from messages import util -from messages.location import LocationGlobal, LocationGlobalRelative, LocationLocal, Velocity, Altitude +from mavctl.messages import util +from mavctl.messages.location import LocationGlobal, LocationGlobalRelative, LocationLocal, Velocity, Altitude @dataclass class LandingTarget: @@ -140,6 +140,26 @@ def get_global_position(self): alt = msg.alt / 1000 return LocationGlobal(lat, lon, alt) + + def get_geovector(point): + origin = self.get_global_position() + distance = util.LatLon_to_Distance(point, origin) + bearing = radians(util.Heading(point, origin)) + + vectorX = distance * sin(bearing) + vectorY = distance * cos(bearing) + + xRot = vectorX * cos(heading) - vectorY * sin(heading) + yRot = vectorx * sin(heading) + vectorY * cos(heading) + + return (xRot, yRot) + + def get_heading(self): + msg = self.mav.recv_match(type='GLOBAL_POSITION_INT', blocking=True) + if msg: + hdg = hdg / 100 + return hdg + def get_local_position(self): """ @@ -263,9 +283,9 @@ def vtol_takeoff(self, altitude, pitch=15): def land(self, land_mode: Literal[0,1,2], abort_alt: float = 0, - yaw_angle: Optional[float] = None, - latitude: Optional[float] = None, - longitude: Optional[float] = None, + yaw_angle: Optional[float] = 0, + latitude: Optional[float] = 0, + longitude: Optional[float] = 0, ): """ Initiate a landing sequence. @@ -294,8 +314,7 @@ def land(self, # Runtime validation if land_mode == 0 and (latitude is None or longitude is None): - raise ValueError("specify latitude and longitude for disabled precision landing") - + raise ValueError("specify latitude and longitude for disabled precision landing") self.mav.mav.command_long_send( self.mav.target_system, self.mav.target_component, @@ -310,9 +329,10 @@ def land(self, 0) current_position = self.get_local_position() + current_position.alt = 0 target = (current_position.north, current_position.down, 0) - self.wait_target_reached(target) + self.wait_target_reached(current_position) def return_to_launch(self): @@ -331,11 +351,6 @@ def return_to_launch(self): 0 ) - - - - - def generate_typemask(self, keeps): # Generates typemask based on which values to be included mask = 0 @@ -539,6 +554,8 @@ def broadcast_landing_target(self, landing_target: LandingTarget) -> None: """ time_usec = int(time.time() * 1000000) # convert to microseconds + + print(landing_target) self.mav.mav.landing_target_send(time_usec=time_usec, frame=mavutil.mavlink.MAV_FRAME_BODY_FRD, diff --git a/mavctl/messages/util.py b/mavctl/messages/util.py index 9f2df42..d70dea5 100644 --- a/mavctl/messages/util.py +++ b/mavctl/messages/util.py @@ -1,7 +1,7 @@ import math from math import radians, degrees, cos, sin, atan2, sqrt from pymavlink import mavutil -from messages.location import LocationGlobal, LocationGlobalRelative, LocationLocal +from mavctl.messages.location import LocationGlobal, LocationGlobalRelative, LocationLocal def distance_to_target(target1, target2): @@ -74,4 +74,3 @@ def Heading(point1, point2): return heading - From e644980364cec47add18f7f0a3d6f53e2b64b3b2 Mon Sep 17 00:00:00 2001 From: Fawwaz Hameed Date: Sun, 14 Sep 2025 11:59:07 -0600 Subject: [PATCH 8/9] no precision landing ft for today --- mavctl/messages/advanced.py | 8 ++++---- mavctl/messages/navigator.py | 20 +++++++++----------- mavctl/messages/util.py | 2 +- 3 files changed, 14 insertions(+), 16 deletions(-) diff --git a/mavctl/messages/advanced.py b/mavctl/messages/advanced.py index 98ac971..9f6fb59 100644 --- a/mavctl/messages/advanced.py +++ b/mavctl/messages/advanced.py @@ -2,10 +2,10 @@ from typing import Callable, Literal from math import radians, atan -from mavctl.messages.navigator import LandingTarget, Navigator -from mavctl.messages import util -from mavctl.messages.location import LocationGlobal, LocationGlobalRelative, LocationLocal -from mavctl.messages.util import Heading, LatLon_to_Distance +from src.modules.mavctl.mavctl.messages.navigator import LandingTarget, Navigator +from src.modules.mavctl.mavctl.messages import util +from src.modules.mavctl.mavctl.messages.location import LocationGlobal, LocationGlobalRelative, LocationLocal +from src.modules.mavctl.mavctl.messages.util import Heading, LatLon_to_Distance # This file is meant for implementing more advanced features in mavctl diff --git a/mavctl/messages/navigator.py b/mavctl/messages/navigator.py index 52aa81f..7ace20a 100644 --- a/mavctl/messages/navigator.py +++ b/mavctl/messages/navigator.py @@ -5,8 +5,8 @@ from pymavlink import mavutil -from mavctl.messages import util -from mavctl.messages.location import LocationGlobal, LocationGlobalRelative, LocationLocal, Velocity, Altitude +from src.modules.mavctl.mavctl.messages import util +from src.modules.mavctl.mavctl.messages.location import LocationGlobal, LocationGlobalRelative, LocationLocal, Velocity, Altitude @dataclass class LandingTarget: @@ -556,13 +556,11 @@ def broadcast_landing_target(self, landing_target: LandingTarget) -> None: time_usec = int(time.time() * 1000000) # convert to microseconds print(landing_target) - self.mav.mav.landing_target_send(time_usec=time_usec, - frame=mavutil.mavlink.MAV_FRAME_BODY_FRD, - x=landing_target.x, - y=landing_target.y, - z=landing_target.z, - q=(1,0,0,0), - type=mavutil.mavlink.LANDING_TARGET_TYPE_VISION_OTHER, - position_valid=1) - + target_num=0, + frame=mavutil.mavlink.MAV_FRAME_LOCAL_OFFSET_NED, + angle_x=landing_target.forward, + angle_y=landing_target.right, + distance=landing_target.altitude, + size_x=0.52, + size_y=0.52) diff --git a/mavctl/messages/util.py b/mavctl/messages/util.py index d70dea5..f655908 100644 --- a/mavctl/messages/util.py +++ b/mavctl/messages/util.py @@ -1,7 +1,7 @@ import math from math import radians, degrees, cos, sin, atan2, sqrt from pymavlink import mavutil -from mavctl.messages.location import LocationGlobal, LocationGlobalRelative, LocationLocal +from src.modules.mavctl.mavctl.messages.location import LocationGlobal, LocationGlobalRelative, LocationLocal def distance_to_target(target1, target2): From 2fbb69026fcb47539df5386c7cd80a01f71cf30f Mon Sep 17 00:00:00 2001 From: Fawwaz Hameed Date: Tue, 23 Sep 2025 21:20:33 -0600 Subject: [PATCH 9/9] precision land modifications --- mavctl/messages/navigator.py | 12 ++++++------ 1 file changed, 6 insertions(+), 6 deletions(-) diff --git a/mavctl/messages/navigator.py b/mavctl/messages/navigator.py index 7ace20a..6f9a675 100644 --- a/mavctl/messages/navigator.py +++ b/mavctl/messages/navigator.py @@ -557,10 +557,10 @@ def broadcast_landing_target(self, landing_target: LandingTarget) -> None: print(landing_target) self.mav.mav.landing_target_send(time_usec=time_usec, - target_num=0, - frame=mavutil.mavlink.MAV_FRAME_LOCAL_OFFSET_NED, - angle_x=landing_target.forward, - angle_y=landing_target.right, + target_num=1, + frame=mavutil.mavlink.MAV_FRAME_BODY_FRD, + angle_x=-landing_target.forward, + angle_y=-landing_target.right, distance=landing_target.altitude, - size_x=0.52, - size_y=0.52) + size_x=0, + size_y=0)