Skip to content
New issue

Have a question about this project? Sign up for a free GitHub account to open an issue and contact its maintainers and the community.

By clicking “Sign up for GitHub”, you agree to our terms of service and privacy statement. We’ll occasionally send you account related emails.

Already on GitHub? Sign in to your account

Autonomous Landing Module #235

Open
wants to merge 29 commits into
base: main
Choose a base branch
from
Open
Show file tree
Hide file tree
Changes from all commits
Commits
Show all changes
29 commits
Select commit Hold shift + click to select a range
178b772
intial commit
ellyokes253 Dec 29, 2024
3954351
added files
ellyokes253 Dec 29, 2024
b80e668
removed old module
ellyokes253 Dec 29, 2024
8b822e0
made class
ellyokes253 Jan 11, 2025
fd8241f
made changes
ellyokes253 Jan 12, 2025
265cae9
added worker
ellyokes253 Jan 13, 2025
6fd5f9e
made changes
ellyokes253 Jan 14, 2025
8b1c536
issues commiting, now fixed
ellyokes253 Jan 14, 2025
876b714
made changes
ellyokes253 Jan 22, 2025
0b07de1
linter issues fixed
ellyokes253 Jan 22, 2025
38aad9b
fixing linter issues
ellyokes253 Jan 23, 2025
1c5b247
fixing code and linter issues
ellyokes253 Jan 23, 2025
398edaa
continuation of debugging
ellyokes253 Jan 23, 2025
dc81d8e
fixing linter issues
ellyokes253 Jan 23, 2025
af13347
fixing logger initialization
ellyokes253 Jan 24, 2025
6f4c829
fixing last linter issues
ellyokes253 Jan 24, 2025
224a7dc
last few linter issues
ellyokes253 Jan 24, 2025
c0af0dc
last few changes
ellyokes253 Jan 24, 2025
fb1e009
updated changes
ellyokes253 Jan 25, 2025
44656ad
fixing small linter issue
ellyokes253 Jan 25, 2025
619f8d7
fixed run()
ellyokes253 Jan 30, 2025
fbfcc79
pulling new commit changes in common
ellyokes253 Jan 30, 2025
3bca007
fixing linter error
ellyokes253 Jan 30, 2025
3ff8098
using first bbox
ellyokes253 Jan 31, 2025
7aa2f46
added AutoLandingInformation object
ellyokes253 Feb 3, 2025
a6b98e6
fixing small mistakes
ellyokes253 Feb 3, 2025
e2428ef
redefined AutoLandingInformation class
ellyokes253 Feb 5, 2025
dec4a18
results of new merge
ellyokes253 Feb 7, 2025
1ff5d4e
added changes
ellyokes253 Feb 9, 2025
File filter

Filter by extension

Filter by extension

Conversations
Failed to load comments.
Loading
Jump to
Jump to file
Failed to load files.
Loading
Diff view
Diff view
Empty file.
114 changes: 114 additions & 0 deletions modules/auto_landing/auto_landing.py
Original file line number Diff line number Diff line change
@@ -0,0 +1,114 @@
"""
Auto-landing script that calculates the necessary parameters
for use with LANDING_TARGET MAVLink command.
"""

import math
import time


from ..common.modules.logger import logger
from .. import merged_odometry_detections


class AutoLandingInformation:
"""
Information necessary for the LANDING_TARGET MAVLink command.
"""

def __init__(self, angle_x: float, angle_y: float, target_dist: float) -> None:
"""
Information necessary for the LANDING_TARGET MAVLink command.

angle_x: Angle of the x coordinate of the bounding box within -π to π (rads).
angle_y: Angle of the y coordinate of the bounding box within -π to π (rads).
target_dist: Horizontal distance of vehicle to target (meters).
"""

self.angle_x = angle_x
self.angle_y = angle_y
self.target_dist = target_dist


class AutoLanding:
"""
Auto-landing script that calculates the necessary parameters
for use with LANDING_TARGET MAVLink command.
"""

__create_key = object()

@classmethod
def create(
cls,
fov_x: float,
fov_y: float,
im_h: float,
im_w: float,
maxlou05 marked this conversation as resolved.
Show resolved Hide resolved
period: float,
local_logger: logger.Logger,
) -> "tuple [bool, AutoLanding | None ]":
"""
fov_x: The horizontal camera field of view in degrees.
fov_y: The vertical camera field of view in degrees.
im_w: Width of image.
im_h: Height of image.
period: Wait time in seconds.

Returns an AutoLanding object.
"""

return True, AutoLanding(cls.__create_key, fov_x, fov_y, im_h, im_w, period, local_logger)

def __init__(
self,
class_private_create_key: object,
fov_x: float,
fov_y: float,
im_h: float,
im_w: float,
period: float,
local_logger: logger.Logger,
) -> None:
"""
Private constructor, use create() method.
"""
assert class_private_create_key is AutoLanding.__create_key, "Use create() method"

self.fov_x = fov_x
self.fov_y = fov_y
self.im_h = im_h
self.im_w = im_w
self.period = period
self.__logger = local_logger

def run(
self, odometry_detections: merged_odometry_detections.MergedOdometryDetections
) -> "tuple[bool, AutoLandingInformation]":
"""
Calculates the x and y angles in radians of the bounding box based on its center.

odometry_detections: A merged odometry dectections object.

Returns an AutoLandingInformation object.
"""

x_center, y_center = odometry_detections.detections[0].get_centre()

angle_x = (x_center - self.im_w / 2) * (self.fov_x * (math.pi / 180)) / self.im_w
angle_y = (y_center - self.im_h / 2) * (self.fov_y * (math.pi / 180)) / self.im_h

height_agl = odometry_detections.odometry_local.position.down * -1

x_dist = math.tan(angle_x) * height_agl
y_dist = math.tan(angle_y) * height_agl
ground_hyp = (x_dist**2 + y_dist**2) ** 0.5
target_to_vehicle_dist = (ground_hyp**2 + height_agl**2) ** 0.5

self.__logger.info(
f"X angle: {angle_x} Y angle: {angle_y}\nRequired horizontal correction: {ground_hyp} Distance from vehicle to target: {target_to_vehicle_dist}",
True,
)

time.sleep(self.period)
return True, AutoLandingInformation(angle_x, angle_y, target_to_vehicle_dist)
65 changes: 65 additions & 0 deletions modules/auto_landing/auto_landing_worker.py
Original file line number Diff line number Diff line change
@@ -0,0 +1,65 @@
"""
Auto-landing worker.
"""

import os
import pathlib

from utilities.workers import queue_proxy_wrapper
from utilities.workers import worker_controller
from . import auto_landing
from ..common.modules.logger import logger


def auto_landing_worker(
fov_x: float,
fov_y: float,
im_h: float,
im_w: float,
period: float,
input_queue: queue_proxy_wrapper.QueueProxyWrapper,
output_queue: queue_proxy_wrapper.QueueProxyWrapper,
controller: worker_controller.WorkerController,
) -> None:
"""
Worker process.

input_queue and output_queue are data queues.
controller is how the main process communicates to this worker process.
"""

worker_name = pathlib.Path(__file__).stem
process_id = os.getpid()
result, local_logger = logger.Logger.create(f"{worker_name}_{process_id}", True)
if not result:
print("ERROR: Worker failed to create logger")
return

# Get Pylance to stop complaining
assert local_logger is not None

local_logger.info("Logger initialized", True)

result, auto_lander = auto_landing.AutoLanding.create(
fov_x, fov_y, im_h, im_w, period, local_logger
)

if not result:
local_logger.error("Worker failed to create class object", True)
return

# Get Pylance to stop complaining
assert auto_lander is not None

while not controller.is_exit_requested():
controller.check_pause()

input_data = input_queue.queue.get()
if input_data is None:
continue

result, value = auto_lander.run(input_data)
if not result:
continue

output_queue.queue.put(value)