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

Commit b526565

Browse files
authored
Autonomous Landing Module (#235)
* intial commit * added files * removed old module * made class * made changes * added worker * made changes * issues commiting, now fixed * made changes * linter issues fixed * fixing linter issues * fixing code and linter issues * continuation of debugging * fixing linter issues * fixing logger initialization * fixing last linter issues * last few linter issues * last few changes * updated changes * fixing small linter issue * fixed run() * pulling new commit changes in common * fixing linter error * using first bbox * added AutoLandingInformation object * fixing small mistakes * redefined AutoLandingInformation class * added changes * fixed linter issues
1 parent 371c45f commit b526565

File tree

3 files changed

+176
-0
lines changed

3 files changed

+176
-0
lines changed

modules/auto_landing/__init__.py

Whitespace-only changes.
Lines changed: 110 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -0,0 +1,110 @@
1+
"""
2+
Auto-landing script that calculates the necessary parameters
3+
for use with LANDING_TARGET MAVLink command.
4+
"""
5+
6+
import math
7+
8+
from .. import merged_odometry_detections
9+
from ..common.modules.logger import logger
10+
11+
12+
class AutoLandingInformation:
13+
"""
14+
Information necessary for the LANDING_TARGET MAVLink command.
15+
"""
16+
17+
def __init__(self, angle_x: float, angle_y: float, target_dist: float) -> None:
18+
"""
19+
Information necessary for the LANDING_TARGET MAVLink command.
20+
21+
angle_x: Angle of the x coordinate of the bounding box within -π to π (rads).
22+
angle_y: Angle of the y coordinate of the bounding box within -π to π (rads).
23+
target_dist: Horizontal distance of vehicle to target (meters).
24+
"""
25+
26+
self.angle_x = angle_x
27+
self.angle_y = angle_y
28+
self.target_dist = target_dist
29+
30+
31+
class AutoLanding:
32+
"""
33+
Auto-landing script that calculates the necessary parameters
34+
for use with LANDING_TARGET MAVLink command.
35+
"""
36+
37+
__create_key = object()
38+
39+
@classmethod
40+
def create(
41+
cls,
42+
fov_x: float,
43+
fov_y: float,
44+
im_h: float,
45+
im_w: float,
46+
local_logger: logger.Logger,
47+
) -> "tuple [bool, AutoLanding | None ]":
48+
"""
49+
fov_x: The horizontal camera field of view in degrees.
50+
fov_y: The vertical camera field of view in degrees.
51+
im_w: Width of image.
52+
im_h: Height of image.
53+
54+
Returns an AutoLanding object.
55+
"""
56+
57+
return True, AutoLanding(cls.__create_key, fov_x, fov_y, im_h, im_w, local_logger)
58+
59+
def __init__(
60+
self,
61+
class_private_create_key: object,
62+
fov_x: float,
63+
fov_y: float,
64+
im_h: float,
65+
im_w: float,
66+
local_logger: logger.Logger,
67+
) -> None:
68+
"""
69+
Private constructor, use create() method.
70+
"""
71+
assert class_private_create_key is AutoLanding.__create_key, "Use create() method"
72+
73+
self.fov_x = fov_x
74+
self.fov_y = fov_y
75+
self.im_h = im_h
76+
self.im_w = im_w
77+
self.__logger = local_logger
78+
79+
def run(
80+
self, odometry_detections: merged_odometry_detections.MergedOdometryDetections
81+
) -> "tuple[bool, AutoLandingInformation]":
82+
"""
83+
Calculates the x and y angles in radians of the bounding box based on its center.
84+
85+
odometry_detections: A merged odometry dectections object.
86+
87+
Returns an AutoLandingInformation object.
88+
"""
89+
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()
92+
93+
angle_x = (x_center - self.im_w / 2) * (self.fov_x * (math.pi / 180)) / self.im_w
94+
angle_y = (y_center - self.im_h / 2) * (self.fov_y * (math.pi / 180)) / self.im_h
95+
96+
# This is height above ground level (AGL)
97+
# down is how many meters down you are from home position, which is on the ground
98+
height_agl = odometry_detections.odometry_local.position.down * -1
99+
100+
x_dist = math.tan(angle_x) * height_agl
101+
y_dist = math.tan(angle_y) * height_agl
102+
ground_hyp = (x_dist**2 + y_dist**2) ** 0.5
103+
target_to_vehicle_dist = (ground_hyp**2 + height_agl**2) ** 0.5
104+
105+
self.__logger.info(
106+
f"X angle: {angle_x} Y angle: {angle_y}\nRequired horizontal correction: {ground_hyp} Distance from vehicle to target: {target_to_vehicle_dist}",
107+
True,
108+
)
109+
110+
return True, AutoLandingInformation(angle_x, angle_y, target_to_vehicle_dist)
Lines changed: 66 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -0,0 +1,66 @@
1+
"""
2+
Auto-landing worker.
3+
"""
4+
5+
import os
6+
import pathlib
7+
import time
8+
9+
from utilities.workers import queue_proxy_wrapper
10+
from utilities.workers import worker_controller
11+
from . import auto_landing
12+
from ..common.modules.logger import logger
13+
14+
15+
def auto_landing_worker(
16+
fov_x: float,
17+
fov_y: float,
18+
im_h: float,
19+
im_w: float,
20+
period: float,
21+
input_queue: queue_proxy_wrapper.QueueProxyWrapper,
22+
output_queue: queue_proxy_wrapper.QueueProxyWrapper,
23+
controller: worker_controller.WorkerController,
24+
) -> None:
25+
"""
26+
Worker process.
27+
28+
period: Wait time in seconds.
29+
input_queue and output_queue are data queues.
30+
controller is how the main process communicates to this worker process.
31+
"""
32+
33+
worker_name = pathlib.Path(__file__).stem
34+
process_id = os.getpid()
35+
result, local_logger = logger.Logger.create(f"{worker_name}_{process_id}", True)
36+
if not result:
37+
print("ERROR: Worker failed to create logger")
38+
return
39+
40+
# Get Pylance to stop complaining
41+
assert local_logger is not None
42+
43+
local_logger.info("Logger initialized", True)
44+
45+
result, auto_lander = auto_landing.AutoLanding.create(fov_x, fov_y, im_h, im_w, local_logger)
46+
47+
if not result:
48+
local_logger.error("Worker failed to create class object", True)
49+
return
50+
51+
# Get Pylance to stop complaining
52+
assert auto_lander is not None
53+
54+
while not controller.is_exit_requested():
55+
controller.check_pause()
56+
57+
input_data = input_queue.queue.get()
58+
if input_data is None:
59+
continue
60+
61+
result, value = auto_lander.run(input_data)
62+
if not result:
63+
continue
64+
65+
output_queue.queue.put(value)
66+
time.sleep(period)

0 commit comments

Comments
 (0)