-
Notifications
You must be signed in to change notification settings - Fork 37
Autonomous Landing Module #235
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
Changes from 26 commits
178b772
3954351
b80e668
8b822e0
fd8241f
265cae9
6fd5f9e
8b1c536
876b714
0b07de1
38aad9b
1c5b247
398edaa
dc81d8e
af13347
6f4c829
224a7dc
c0af0dc
fb1e009
44656ad
619f8d7
fbfcc79
3bca007
3ff8098
7aa2f46
a6b98e6
e2428ef
dec4a18
1ff5d4e
e882a42
17cd52a
File filter
Filter by extension
Conversations
Jump to
Diff view
Diff view
There are no files selected for viewing
Original file line number | Diff line number | Diff line change |
---|---|---|
@@ -0,0 +1,126 @@ | ||
""" | ||
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 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 | ||
) -> "AutoLandingInformation": | ||
There was a problem hiding this comment. Choose a reason for hiding this commentThe reason will be displayed to describe this comment to others. Learn more. Change this to accurately get the output: 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() | ||
There was a problem hiding this comment. Choose a reason for hiding this commentThe reason will be displayed to describe this comment to others. Learn more. Add comment with TODO: come up with a better algorithm to pick which detection to land at, if many are detected in one frame. |
||
|
||
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 | ||
There was a problem hiding this comment. Choose a reason for hiding this commentThe reason will be displayed to describe this comment to others. Learn more. Maybe a comment here that says height above ground level (AGL), and that down is how many meters down you are from home position, which is on the ground. Hence the * -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) | ||
There was a problem hiding this comment. Choose a reason for hiding this commentThe reason will be displayed to describe this comment to others. Learn more. Can we move this to the worker and not the class' run() function? So remove the period from the class __init__ and create as well |
||
return AutoLandingInformation.create(angle_x, angle_y, target_to_vehicle_dist) | ||
|
||
|
||
class AutoLandingInformation: | ||
There was a problem hiding this comment. Choose a reason for hiding this commentThe reason will be displayed to describe this comment to others. Learn more. Reorder this so it is the first class in the file |
||
""" | ||
Information necessary for the LANDING_TARGET MAVlink command | ||
""" | ||
|
||
__create_key = object() | ||
|
||
@classmethod | ||
def create( | ||
cls, angle_x: float, angle_y: float, target_dist: float | ||
There was a problem hiding this comment. Choose a reason for hiding this commentThe reason will be displayed to describe this comment to others. Learn more. This method can be removed: you dont really need the create method, just move the doc string inside the constructor. |
||
) -> "tuple[bool, AutoLandingInformation | None]": | ||
""" | ||
Object containing the x and y angles in radians respectively, and the target distance in meters. | ||
""" | ||
return True, AutoLandingInformation(cls.__create_key, angle_x, angle_y, target_dist) | ||
|
||
def __init__( | ||
self, class_private_create_key: object, angle_x: float, angle_y: float, target_dist: float | ||
) -> None: | ||
""" | ||
Private constructor, use create() method. | ||
""" | ||
assert ( | ||
class_private_create_key is AutoLandingInformation.__create_key | ||
), "Use create() method" | ||
|
||
self.angle_x = angle_x | ||
self.angle_y = angle_y | ||
self.target_dist = target_dist |
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 | ||
Comment on lines
+9
to
+12
There was a problem hiding this comment. Choose a reason for hiding this commentThe reason will be displayed to describe this comment to others. Learn more. Can you put this in alphabetical order? So just put the last two on top |
||
|
||
|
||
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 | ||
There was a problem hiding this comment. Choose a reason for hiding this commentThe reason will be displayed to describe this comment to others. Learn more. See comment about period |
||
) | ||
|
||
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) | ||
There was a problem hiding this comment. Choose a reason for hiding this commentThe reason will be displayed to describe this comment to others. Learn more. Place wait(period) down here, after this |
There was a problem hiding this comment.
Choose a reason for hiding this comment
The reason will be displayed to describe this comment to others. Learn more.
Can you put this in alphabetical order? So .. goes before ..common