Skip to content
This repository was archived by the owner on Nov 13, 2025. It is now read-only.

Commit 2f4f5bf

Browse files
committed
Complete autonomous landing module
1 parent ad75071 commit 2f4f5bf

File tree

3 files changed

+559
-18
lines changed

3 files changed

+559
-18
lines changed

modules/auto_landing/auto_landing.py

Lines changed: 197 additions & 4 deletions
Original file line numberDiff line numberDiff line change
@@ -4,11 +4,25 @@
44
"""
55

66
import math
7+
from enum import Enum
8+
from typing import Optional
9+
import threading
710

811
from .. import merged_odometry_detections
912
from ..common.modules.logger import logger
1013

1114

15+
class DetectionSelectionStrategy(Enum):
16+
"""
17+
Strategies for selecting which detection to use when multiple targets are detected.
18+
"""
19+
20+
NEAREST_TO_CENTER = "nearest_to_center" # Choose detection closest to image center
21+
LARGEST_AREA = "largest_area" # Choose detection with largest bounding box area
22+
HIGHEST_CONFIDENCE = "highest_confidence" # Choose detection with highest confidence
23+
FIRST_DETECTION = "first_detection" # Use first detection in list (original behavior)
24+
25+
1226
class AutoLandingInformation:
1327
"""
1428
Information necessary for the LANDING_TARGET MAVLink command.
@@ -44,17 +58,21 @@ def create(
4458
im_h: float,
4559
im_w: float,
4660
local_logger: logger.Logger,
61+
selection_strategy: DetectionSelectionStrategy = DetectionSelectionStrategy.NEAREST_TO_CENTER,
4762
) -> "tuple [bool, AutoLanding | None ]":
4863
"""
4964
fov_x: The horizontal camera field of view in degrees.
5065
fov_y: The vertical camera field of view in degrees.
5166
im_w: Width of image.
5267
im_h: Height of image.
68+
selection_strategy: Strategy for selecting which detection to use when multiple targets are detected.
5369
5470
Returns an AutoLanding object.
5571
"""
5672

57-
return True, AutoLanding(cls.__create_key, fov_x, fov_y, im_h, im_w, local_logger)
73+
return True, AutoLanding(
74+
cls.__create_key, fov_x, fov_y, im_h, im_w, local_logger, selection_strategy
75+
)
5876

5977
def __init__(
6078
self,
@@ -64,6 +82,7 @@ def __init__(
6482
im_h: float,
6583
im_w: float,
6684
local_logger: logger.Logger,
85+
selection_strategy: DetectionSelectionStrategy,
6786
) -> None:
6887
"""
6988
Private constructor, use create() method.
@@ -75,10 +94,75 @@ def __init__(
7594
self.im_h = im_h
7695
self.im_w = im_w
7796
self.__logger = local_logger
97+
self.__selection_strategy = selection_strategy
98+
99+
def _select_detection(self, detections: list) -> Optional[int]:
100+
"""
101+
Select which detection to use based on the configured strategy.
102+
103+
Returns the index of the selected detection, or None if no suitable detection found.
104+
"""
105+
if not detections:
106+
return None
107+
108+
if len(detections) == 1:
109+
return 0
110+
111+
if self.__selection_strategy == DetectionSelectionStrategy.FIRST_DETECTION:
112+
return 0
113+
114+
if self.__selection_strategy == DetectionSelectionStrategy.NEAREST_TO_CENTER:
115+
# Find detection closest to image center
116+
image_center_x = self.im_w / 2
117+
image_center_y = self.im_h / 2
118+
119+
min_distance = float("inf")
120+
selected_index = 0
121+
122+
for i, detection in enumerate(detections):
123+
det_center_x, det_center_y = detection.get_centre()
124+
distance = math.sqrt(
125+
(det_center_x - image_center_x) ** 2 + (det_center_y - image_center_y) ** 2
126+
)
127+
if distance < min_distance:
128+
min_distance = distance
129+
selected_index = i
130+
131+
return selected_index
132+
133+
if self.__selection_strategy == DetectionSelectionStrategy.LARGEST_AREA:
134+
# Find detection with largest bounding box area
135+
max_area = 0
136+
selected_index = 0
137+
138+
for i, detection in enumerate(detections):
139+
width = detection.x_2 - detection.x_1
140+
height = detection.y_2 - detection.y_1
141+
area = width * height
142+
if area > max_area:
143+
max_area = area
144+
selected_index = i
145+
146+
return selected_index
147+
148+
if self.__selection_strategy == DetectionSelectionStrategy.HIGHEST_CONFIDENCE:
149+
# Find detection with highest confidence
150+
max_confidence = 0
151+
selected_index = 0
152+
153+
for i, detection in enumerate(detections):
154+
if detection.confidence > max_confidence:
155+
max_confidence = detection.confidence
156+
selected_index = i
157+
158+
return selected_index
159+
160+
# Default fallback
161+
return 0
78162

79163
def run(
80164
self, odometry_detections: merged_odometry_detections.MergedOdometryDetections
81-
) -> "tuple[bool, AutoLandingInformation]":
165+
) -> "tuple[bool, AutoLandingInformation | None]":
82166
"""
83167
Calculates the x and y angles in radians of the bounding box based on its center.
84168
@@ -87,8 +171,26 @@ def run(
87171
Returns an AutoLandingInformation object.
88172
"""
89173

90-
# TODO: Devise better algorithm to pick which detection to land at if several are detected
91-
x_center, y_center = odometry_detections.detections[0].get_centre()
174+
# Check if we have any detections
175+
if not odometry_detections.detections:
176+
self.__logger.warning("No detections available for auto-landing", True)
177+
return False, None
178+
179+
# Select which detection to use
180+
selected_index = self._select_detection(odometry_detections.detections)
181+
if selected_index is None:
182+
self.__logger.error("Failed to select detection for auto-landing", True)
183+
return False, None
184+
185+
selected_detection = odometry_detections.detections[selected_index]
186+
187+
# Log selection information
188+
self.__logger.info(
189+
f"Selected detection {selected_index + 1}/{len(odometry_detections.detections)} using strategy: {self.__selection_strategy.value}",
190+
True,
191+
)
192+
193+
x_center, y_center = selected_detection.get_centre()
92194

93195
angle_x = (x_center - self.im_w / 2) * (self.fov_x * (math.pi / 180)) / self.im_w
94196
angle_y = (y_center - self.im_h / 2) * (self.fov_y * (math.pi / 180)) / self.im_h
@@ -108,3 +210,94 @@ def run(
108210
)
109211

110212
return True, AutoLandingInformation(angle_x, angle_y, target_to_vehicle_dist)
213+
214+
215+
class AutoLandingController:
216+
"""
217+
Controller for turning auto-landing on/off.
218+
"""
219+
220+
__create_key = object()
221+
222+
@classmethod
223+
def create(
224+
cls,
225+
auto_landing: AutoLanding,
226+
local_logger: logger.Logger,
227+
) -> "tuple[bool, AutoLandingController | None]":
228+
"""
229+
Create an AutoLandingController instance.
230+
231+
auto_landing: The AutoLanding instance to control.
232+
local_logger: Logger instance for logging.
233+
234+
Returns an AutoLandingController object.
235+
"""
236+
return True, AutoLandingController(cls.__create_key, auto_landing, local_logger)
237+
238+
def __init__(
239+
self,
240+
class_private_create_key: object,
241+
auto_landing: AutoLanding,
242+
local_logger: logger.Logger,
243+
) -> None:
244+
"""
245+
Private constructor, use create() method.
246+
"""
247+
assert class_private_create_key is AutoLandingController.__create_key, "Use create() method"
248+
249+
self.__auto_landing = auto_landing
250+
self.__logger = local_logger
251+
self.__enabled = False
252+
self.__enabled_lock = threading.Lock()
253+
254+
def is_enabled(self) -> bool:
255+
"""
256+
Check if auto-landing is enabled.
257+
"""
258+
with self.__enabled_lock:
259+
return self.__enabled
260+
261+
def enable(self) -> bool:
262+
"""
263+
Enable auto-landing system.
264+
265+
Returns True if successfully enabled, False otherwise.
266+
"""
267+
with self.__enabled_lock:
268+
if not self.__enabled:
269+
self.__enabled = True
270+
self.__logger.info("Auto-landing system enabled", True)
271+
return True
272+
self.__logger.warning("Auto-landing system already enabled", True)
273+
return False
274+
275+
def disable(self) -> bool:
276+
"""
277+
Disable auto-landing system.
278+
279+
Returns True if successfully disabled, False otherwise.
280+
"""
281+
with self.__enabled_lock:
282+
if self.__enabled:
283+
self.__enabled = False
284+
self.__logger.info("Auto-landing system disabled", True)
285+
return True
286+
self.__logger.warning("Auto-landing system already disabled", True)
287+
return False
288+
289+
def process_detections(
290+
self, odometry_detections: merged_odometry_detections.MergedOdometryDetections
291+
) -> "tuple[bool, AutoLandingInformation | None]":
292+
"""
293+
Process detections if auto-landing is enabled.
294+
295+
Returns landing information if processing was successful, None otherwise.
296+
"""
297+
with self.__enabled_lock:
298+
if not self.__enabled:
299+
return False, None
300+
301+
# Process the detections using the auto-landing module
302+
result, landing_info = self.__auto_landing.run(odometry_detections)
303+
return result, landing_info

0 commit comments

Comments
 (0)