diff --git a/bin/run-nav.sh b/bin/run-nav.sh index 28b5e89..f83160b 100755 --- a/bin/run-nav.sh +++ b/bin/run-nav.sh @@ -6,5 +6,4 @@ imgfile="log/$(date +'%x-%X').imglog" mkdir -p "$(dirname "$logfile")" mkdir -p "$(dirname "$imgfile")" -PYTHONUNBUFFERED=1 PYTHONPATH=".:dep/labeller:dep/labeller/third_party/yolov5" python3 src/aeac2025/task2.py 2>&1 | tee "$logfile" & -PYTHONUNBUFFERED=1 PYTHONPATH=".:dep/labeller:dep/labeller/third_party/yolov5" python3 src/video_server/server.py 2>&1 | tee "$imgfile" +PYTHONUNBUFFERED=1 PYTHONPATH=".:dep/labeller:dep/labeller/third_party/yolov5" python3 src/flight_tests/mavctl-test.py 2>&1 | tee "$logfile" diff --git a/install/shepard.service b/install/shepard.service index 8a1e835..39b640a 100644 --- a/install/shepard.service +++ b/install/shepard.service @@ -3,8 +3,8 @@ Description=Shepard After=login.target [Service] -ExecStart=/home/uaarg/Documents/shepard/bin/run-nav.sh -WorkingDirectory=/home/uaarg/Documents/shepard +ExecStart=/home/uaarg/shepard/bin/run-nav.sh +WorkingDirectory=/home/uaarg/shepard [Install] WantedBy=multi-user.target diff --git a/src/flight_tests/demo_flight.py b/src/flight_tests/demo_flight.py new file mode 100644 index 0000000..90fa25e --- /dev/null +++ b/src/flight_tests/demo_flight.py @@ -0,0 +1,25 @@ +from src.modules.imaging.analysis import BeaconAnalysisDelegate +from src.modules.mavctl.mavctl.connect import conn +from src.modules.mavctl.mavctl.messages.navigator import Navigator, LandingTarget +from src.modules.mavctl.mavctl.messages.messenger import Messenger +from src.modules.mavctl.mavctl.messages import advanced +from src.modules.mavctl.mavctl.messages.location import LocationGlobal +import src.modules.autopilot.mavctl_advanced as mavctl_advanced +import time + +CONN_STR = "udp:127.0.0.1:14551" +mav = conn.connect(CONN_STR) +master = Navigator(mav) +messenger = Messenger(14553) +messenger.send("MAVCTL: Online") + +while master.set_mode_wait() and master.wait_vehicle_armed(): + pass + +master.takeoff(10) +time.sleep(5) +advanced.simple_goto_local(master, 50, 50, 20) +time.sleep(20) +advanced.simple_goto_local(master, 50, -50, 20) +time.sleep(10) +master.return_to_launch() diff --git a/src/flight_tests/mavctl-test.py b/src/flight_tests/mavctl-test.py new file mode 100644 index 0000000..bc93b82 --- /dev/null +++ b/src/flight_tests/mavctl-test.py @@ -0,0 +1,23 @@ +from src.modules.mavctl.connect.conn import Connect +from pymavlink import mavutil +from src.modules.mavctl.messages.navigator import Navigator +from src.modules.mavctl.messages.messenger import Messenger +from src.modules.mavctl.messages import advanced +import time + +CONN_STR = "tcp:127.0.0.1:14550" + +mav = Connect(ip = CONN_STR) +master = Navigator(mav.mav) + +while master.wait_vehicle_armed(): + pass + +while not master.set_mode_wait(): + pass + +master.takeoff(10) +time.sleep(5) +advanced.simple_goto_global(master, 53.496970, -113.545194, 20) + +master.return_to_launch() diff --git a/src/flight_tests/precision_land_test_FH.py b/src/flight_tests/precision_land_test_FH.py deleted file mode 100644 index b03bc05..0000000 --- a/src/flight_tests/precision_land_test_FH.py +++ /dev/null @@ -1,113 +0,0 @@ -''' -Idea behind this flight test script is to fly to a waypoint and test the built-in precision landing component. - -Eventually this script will be adapted to support the ability to send rangefinder data to the pixhawk so that more accurate precision landing is possible. - -''' - -import time -import threading - -from dronekit import connect, VehicleMode, LocationGlobal - -from src.modules.autopilot import navigator -from src.modules.autopilot import lander -import src.modules.autopilot.altimeter as altimeter - -from src.modules.imaging import analysis -from src.modules.imaging import camera -from src.modules.imaging import debug -from src.modules.imaging import location -from dep.labeller.benchmarks import yolo - -mavlink_delegate = location.MAVLinkDelegate() -location_provider = location.MAVLinkLocationProvider(mavlink_delegate) -location_provider = location.DebugLocationProvider() -location_provider.debug_change_location(altitude=1) - -detector = yolo.YoloDetector(weights="landing_nano.pt") -cam = camera.RPiCamera() -debugger = debug.ImageAnalysisDebugger() -debugger = None -img_analysis = analysis.ImageAnalysisDelegate(detector, cam, location_provider, - debugger) -mavlink_delegate.run() - -CONN_STR = "udp:127.0.0.1:14551" -MESSENGER_PORT = 14552 - -drone = connect(CONN_STR, wait_ready=False) - -nav = navigator.Navigator(drone, MESSENGER_PORT) -lander = lander.Lander() -altimeter = altimeter.XM125(average_window=5) -altimeter.begin() - - -nav.send_status_message("Shepard is online") - -while not (drone.armed and drone.mode == VehicleMode("GUIDED")): - pass - -nav.send_status_message("Executing mission") -time.sleep(2) - -nav.takeoff(10) -start_coords = drone.location.global_relative_frame -time.sleep(2) - -MAX_GROUND_SPEED = 20 -TIME = 5 * 60 # 5 minutes -ALTITUDE = 15 -precision_land_enable = False - - -img_analysis.subscribe(lambda _, x, y: precision_land(x, y)) -img_analysis.start() - - - -waypoint = [10, 10, 20] - - -# MODIFY THIS AS REQUIRED -speed = nav.optimum_speed(TIME, [waypoint]) - -#checking to ensure ground speed is safe -assert speed > 0 -assert speed < MAX_GROUND_SPEED - -#drone.groundspeed = speed -#nav.send_status_message(f"Ground speed set to {speed} m/s") - -# workaround to get the speed to set properly for the actual waypoints -nav.set_position_relative(0, 0) - -time.sleep(1) -nav.set_speed(speed) -time.sleep(1) - - -nav.send_status_message(f"Moving to pre-set waypoints") -nav.set_altitude_position(waypoint[0], - waypoint[1], - waypoint[2], - battery=None, - hard_cutoff_enable=False) - -precision_land_enable = True - -type_mask = nav.generate_typemask([0, 1, 2]) - -current_alt = drone.location.global_relative_frame.alt - -def precision_land(x, y): - - # NEEDS TO BE MODIFIED TO ACTUALLY GO TO COORDINATES RELEVATIVE TO THE ORIGIN OF THIS REFERENCE FRAME - current_alt = drone.location.global_relative_frame.alt - if precision_land_enable and current_alt >= 0.5: - nav.set_position_target_local_ned(x = x, y = y, z = 0, type_mask=type_mask) - elif current_alt < 0.5: - nav.land() - precision_land_enable = False - diff --git a/src/flight_tests/precision_landing.py b/src/flight_tests/precision_landing.py new file mode 100644 index 0000000..1141e5c --- /dev/null +++ b/src/flight_tests/precision_landing.py @@ -0,0 +1,30 @@ +from src.modules.imaging.analysis import BeaconAnalysisDelegate +from src.modules.mavctl.mavctl.messages.navigator import Navigator, LandingTarget +from src.modules.mavctl.mavctl.connect.conn import Connect +from src.modules.mavctl.mavctl.messages.messenger import Messenger +from src.modules.mavctl.mavctl.messages import advanced +from src.modules.mavctl.mavctl.messages.location import LocationGlobal +import src.modules.autopilot.mavctl_advanced as mavctl_advanced +import time + +CONN_STR = "udp:127.0.0.1:14550" +beaconCoordinate = LocationGlobal(53.495534, -113.538215, 10) + + +connect = Connect(ip=CONN_STR) +master = Navigator(connect.mav) + +beacon = BeaconAnalysisDelegate(beaconCoordinate=beaconCoordinate, navigator=master) + + + +while master.set_mode_wait() and master.wait_vehicle_armed(): + pass +master.takeoff(10) +time.sleep(5) +print("Takeoff complete after sleeping 5 seconds") +master.land(2) +while True: + master.broadcast_landing_target(landing_target=landing_target) + print("Landing Target Broadcasted") + time.sleep(0.5) diff --git a/src/flight_tests/vel_control_test.py b/src/flight_tests/vel_control_test.py index fffd1cf..9750aac 100644 --- a/src/flight_tests/vel_control_test.py +++ b/src/flight_tests/vel_control_test.py @@ -8,7 +8,7 @@ from src.modules.autopilot import navigator from src.modules.autopilot import lander -CONN_STR = "udp:127.0.0.1:14551" +CONN_STR = "tcp:127.0.0.1:14550" MESSENGER_PORT = 14552 drone = connect(CONN_STR, wait_ready=False) diff --git a/src/modules/autopilot/mavctl_advanced.py b/src/modules/autopilot/mavctl_advanced.py new file mode 100644 index 0000000..ed8fc54 --- /dev/null +++ b/src/modules/autopilot/mavctl_advanced.py @@ -0,0 +1,43 @@ +from typing import Callable, Literal +from src.modules.mavctl.mavctl.messages.navigator import Navigator, LandingTarget +from src.modules.imaging.analysis import AnalysisDelegate, AnalysisResult + +def do_precision_landing(master: Navigator, + analysisDelegate: AnalysisDelegate, + mode: Literal["REQUIRED", "OPPORTUNISTIC"]) -> None: + print("do_precision_landing start point") + """ + This function sets the drone into precision landing mode. + + Parameters: + analysis_subscriber: A function that accepts a callback function which updates + the landing target coordinates + + 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(position: AnalysisResult): + if position: + altitude = master.get_altitude().terrain # Gets the altitude above the terrain (as seen by an altimeter) + target = LandingTarget(right=position.right, + forward=position.front, + altitude=altitude) + + master.broadcast_landing_target(target) + print("after the callback func def") + + analysisDelegate.subscribe(callback) + + print("subscription occurred") + + if mode == "OPPORTUNISTIC": + master.land(land_mode=1) + elif mode == "REQUIRED": + master.land(land_mode=2) diff --git a/src/modules/autopilot/navigator.py b/src/modules/autopilot/navigator.py index 417388b..f02bd58 100644 --- a/src/modules/autopilot/navigator.py +++ b/src/modules/autopilot/navigator.py @@ -19,7 +19,11 @@ class Navigator: def __init__(self, vehicle, messenger_port): self.vehicle = vehicle self.mavlink_messenger = Messenger(messenger_port) - + + + + def send_message(self, msg): + self.__message(msg) def send_status_message(self, message): self.__message(message) @@ -403,122 +407,30 @@ def __condition_yaw(self, heading, relative=False): # send command to vehicle self.vehicle.send_mavlink(msg) - @staticmethod - def time_left(string_land_time): - """ - Calculates the time between now and the time passed as a string arguement. - - :param string_land_time: the target landing time as a string in the format "HH:MM:SS" - - :return: time left in seconds - """ - time_now = datetime.now().time() - - land_time = datetime.strptime(string_land_time, "%H:%M:%S") - - seconds_now = (time_now.hour * 360) + (time_now.minute * - 60) + (time_now.second) - - seconds_land = (land_time.hour * 360) + (land_time.minute * - 60) + (land_time.second) - - return seconds_land - seconds_now - - def optimum_speed(self, time_left, waypoints): - """ - Finds the optimum horizontal speed required to go from current position to all waypoints and land within the given time - - :param time_left: The time left to land in [seconds], initially the land time minus the takeoff time. - :param waypoints: List of all remaining way points to go to. - :return: required ground speed in [m/s]. - """ - - self.__message("Calculating optimum horizontal speed") - - total_distance = self.__get_distance_metres( - self.vehicle.location.global_relative_frame, waypoints[0]) - for i in range(1, len(waypoints)): - total_distance += self.__get_distance_metres( - waypoints[i - 1], waypoints[i]) - - speed_required = total_distance / time_left - self.__message( - f"Speed required to travel {total_distance} m in {time_left} s is {speed_required} m/s" - ) - - return speed_required - - def sufficient_battery(self, battery, voltage_required=10.0): - """ - Returns True or False based on whether or not the drone has enough battery to do another lap. - Each lap is when drone starts at Alpha, goes to Bravo and comes back to Alpha. - So we check if drone has little more battery than what is required for twice the distance between Alpha and Bravo. - - :param voltage_required: value of voltage required to travel the lap distance - (Distance between Alpha and Bravo in Alma is 3km, so hard code this to voltage required for 6km of flight) - :param battery: instance of the MAVLinkBatteryStatusProvider - :return: a Boolean value, True indicating the drone has sufficient battery for another lap. - """ + def send_land_message(angle_x, angle_y, distance, size_x, size_y): - self.__message("Attempting to read voltage reading") - while True: - try: - voltage = battery.voltage() - break - except ValueError: - pass - time.sleep(0.1) + """Sends a precision landing message to MAVlink + + https://mavlink.io/en/messages/common.html#LANDING_TARGET - self.__message(f"Current battery voltage is {voltage} V") + https://mavlink.io/en/services/landing_target.html - if voltage < voltage_required: - return False + :param angle_x: The x angular offset of landing zone from the center of a downward facing camera [Units: radians] + :param angle_y: the y angular offset of the landing zone from the center of a downward facing camera [Units: radians] + :param distance: The distance between the drone and the landing zone (the OVERALL distance not the x or y distance) [Units: meters] + :param size_x: The size of the landing target with respect to the x axis. [Units: radians] + :param size_y: the size of the landing target with respect to the y axis [Units: radians]""" - return True - - def generate_typemask(self, keeps): - # Generates typemask based on which values to be included - mask = 0 - for bit in keeps: - mask |= (0 << bit) - return mask - - def set_position_target_local_ned(self, time_boot_ms=0, coordinate_frame=mavutil.mavlink.MAV_FRAME_LOCAL_NED, type_mask=0x07FF, x=0, y=0, z=0, vx=0, vy=0, vz=0, afx=0, afy=0, afz=0, yaw=0, yaw_rate=0): - msg = self.vehicle.message_factory.set_position_target_local_ned_encode( - time_boot_ms, # Time since system boot - 0, # Target System ID - 0, # Target Component ID - coordinate_frame, # Coordinate Frame - type_mask, # Typemask of POSITION_TARGET_TYPEMASK - x, - y, - z, - vx, - vy, - vz, - afx, - afy, - afz, - yaw, - yaw_rate + + msg = self.vehicle.message_factory.landing_target_encode( + angle_x, + angle_y, + distance, + size_x, + size_y + ) - self.vehicle.send_mavlink(msg) - - -''' - def cancel_command(self, command_id=mavutil.mavlink.SET_POSITION_TARGET_LOCAL_NED): - msg = self.vehicle.message_factory.command_long_encode( - 0, - 0, - mavutil.mavlink.COMMAND_CANCEL, - 0, - 0, - command_id - ) - - self.vehicle.send_mavlink(msg)''' - - + self.vehicle.flush() diff --git a/src/modules/georeference/inference_georeference.py b/src/modules/georeference/inference_georeference.py index 385f3fb..4ae3c2d 100644 --- a/src/modules/georeference/inference_georeference.py +++ b/src/modules/georeference/inference_georeference.py @@ -10,6 +10,7 @@ where X, Y are in meters """ # TODO: Requires a circular-import... but we only need these for type annotations +from dataclasses import dataclass import numpy as np from math import cos, tan, atan, radians, degrees, sqrt import pyproj @@ -21,6 +22,16 @@ if TYPE_CHECKING: from ..imaging.analysis import CameraAttributes, Inference +@dataclass +class Coordinate: + ''' + Data Class for storing global coordinates + + ''' + + lat: float + lon: float + def LonLat_To_XY(lon, lat, zone=12): """ diff --git a/src/modules/imaging/analysis.py b/src/modules/imaging/analysis.py index 0f50188..a725a9d 100644 --- a/src/modules/imaging/analysis.py +++ b/src/modules/imaging/analysis.py @@ -1,16 +1,19 @@ -from typing import Callable, Optional, List, Callable, Any +from abc import abstractmethod +from dataclasses import dataclass +from typing import Callable, Optional, List, Callable, Any, Tuple import threading + +from pymavlink.mavutil import location # from multiprocessing import Process from dep.labeller.benchmarks.detector import LandingPadDetector, BoundingBox +from src.modules.mavctl.mavctl.messages.location import LocationGlobal from .camera import CameraProvider from .debug import ImageAnalysisDebugger from ..georeference.inference_georeference import get_object_location from .location import LocationProvider -from ..autopilot.navigator import Navigator from PIL import Image -import os - +from src.modules.mavctl.mavctl.messages.navigator import Navigator class CameraAttributes: def __init__(self): @@ -19,7 +22,7 @@ def __init__(self): self.resolution = (1920, 1080) -class Inference: +class ImagingInference: def __init__(self, bounding_box: BoundingBox, relative_alt): camera_attributes = CameraAttributes() position = bounding_box.position @@ -28,8 +31,80 @@ def __init__(self, bounding_box: BoundingBox, relative_alt): self.y = (position.y + size.y / 2) / camera_attributes.resolution[1] self.relative_alt = relative_alt +@dataclass +class AnalysisResult: + """ + Represents the result of an analysis performed by an `AnalysisDelegate`. + + This data class stores the relative position of the detected target + with respect to the drone's current location and orientation. + + Attributes: + front (float): The forward offset of the target in meters. + Positive values indicate the target is ahead of the drone, + negative values indicate it is behind. + left (float): The lateral offset of the target in meters. + Positive values indicate the target is to the right of the drone, + negative values indicate it is to the left. + """ + front: float + right: float + +class AnalysisDelegate: + + def __init__(self) -> None: + self.thread: threading.Thread + self.loop = False + self.subscribers: List[Callable[[AnalysisResult], None]] = [] + + @abstractmethod + def _analyze_unit(self): + """Analyse and subscribe the result of analysis to subscribers""" + raise NotImplementedError + + def start(self): + """ + Will start the analysis process in another thread. + """ + if self.loop is False: + self.loop = True + self.thread = threading.Thread(target=self._analysis_loop) + self.thread.start() + + def stop(self): + self.loop = False + assert self.thread is not None + self.thread.join() -class ImageAnalysisDelegate: + def _analysis_loop(self): + """ + Indefinitely run analysis. This should be run in another thread; + use `start()` to do so. + """ + while self.loop: + print("loop started") + self._analyze_unit() + + def subscriberService(self, analysis_result: AnalysisResult): + """Service function that subscribes the reult to every subscriber""" + for subscriber in self.subscribers: + subscriber(analysis_result) + + def subscribe(self, callback: Callable[[AnalysisResult], None]): + """ + Subscribe to analysis updates. For example: + + def myhandler(image: Image.Image, bounding_box: BoundingBox): + if bounding_box is None: + print("No bounding box detected") + else: + print("Bounding box detected") + + imaging_process.subscribe(myhandler) + """ + self.subscribers.append(callback) + +class ImageAnalysisDelegate(AnalysisDelegate): """ Implements an imaging inference loops and provides several methods which can be used to query the latest image analysis results. @@ -40,15 +115,13 @@ class ImageAnalysisDelegate: Pass an `ImageAnalysisDebugger` when constructing to see a window with live results. - - TODO: geolocate the landing pad using the drone's location. """ def __init__(self, detector: LandingPadDetector, camera: CameraProvider, - location_provider: LocationProvider = None, - navigation_provider: Navigator = None, + location_provider: Optional[LocationProvider] = None, + navigation_provider: Optional[Navigator] = None, debugger: Optional[ImageAnalysisDebugger] = None): self.detector = detector self.camera = camera @@ -60,11 +133,11 @@ def __init__(self, self.location_provider = location_provider self.navigation_provider = navigation_provider - self.subscribers: List[Callable[[Image.Image, float, float], Any]] = [] self.camera_attributes = CameraAttributes() - self.thread = None - self.loop = True - def get_inference(self, bounding_box: BoundingBox) -> Inference: + + super().__init__() + + def get_inference(self, bounding_box: BoundingBox) -> ImagingInference: if self.location_provider is not None: altitude = self.location_provider.altitude() elif self.navigation_provider is not None: @@ -72,23 +145,11 @@ def get_inference(self, bounding_box: BoundingBox) -> Inference: else: raise ValueError("No altitude information provider available.") - inference = Inference(bounding_box, altitude) + inference = ImagingInference(bounding_box, altitude) return inference - def start(self): - """ - Will start the image analysis process in another thread. - """ - self.loop = True - self.thread = threading.Thread(target=self._analysis_loop) - # process = Process(target=self._analysis_loop) - self.thread.start() - # process.start() - # Use `threading` to start `self._analysis_loop` in another thread. - - def stop(self): - self.loop = False - self.thread.join() + def _analyze_unit(self): + self._analyze_image() def _analyze_image(self): """ @@ -104,34 +165,32 @@ def _analyze_image(self): if bounding_box is not None: self.debugger.set_bounding_box(bounding_box) - for subscriber in self.subscribers: - if bounding_box: - inference = self.get_inference(bounding_box) - if inference: - x, y = get_object_location(self.camera_attributes, - inference) - subscriber(im, (x, y)) - else: - subscriber(im, None) + if bounding_box: + inference = self.get_inference(bounding_box) + if inference: + x, y = get_object_location(self.camera_attributes, + inference) + analysis_result = AnalysisResult(front=y, right=x) + self.subscriberService(analysis_result) - def _analysis_loop(self): - """ - Indefinitely run image analysis. This should be run in another thread; - use `start()` to do so. - """ - while self.loop: - self._analyze_image() +class BeaconAnalysisDelegate(AnalysisDelegate): - def subscribe(self, callback: Callable): + def __init__(self, beaconCoordinate: LocationGlobal, navigator: Navigator) -> None: """ - Subscribe to image analysis updates. For example: - - def myhandler(image: Image.Image, bounding_box: BoundingBox): - if bounding_box is None: - print("No bounding box detected") - else: - print("Bounding box detected") - - imaging_process.subscribe(myhandler) + Parameters: + beaconCoordinate: Coordinates of the beacon you wish to assign. format: (latitude, longitude) """ - self.subscribers.append(callback) + print("beacon has been inited") + super().__init__() + self.beaconCoordinate = beaconCoordinate + self.navigator = navigator + + def _analyze_unit(self): + geovector = self.navigator.get_geovector(self.beaconCoordinate) + print(geovector) + result = AnalysisResult(front=geovector[1], right=geovector[0]) + self.subscriberService(result) + pass + + def set_beacon_coordinate(self, beaconCoordinate: Tuple[float, float]) -> None: + self.beaconCoordinate = beaconCoordinate diff --git a/src/modules/imaging/detector.py b/src/modules/imaging/detector.py index 6f1d7d4..e322f40 100644 --- a/src/modules/imaging/detector.py +++ b/src/modules/imaging/detector.py @@ -3,6 +3,7 @@ from PIL import Image import numpy as np import cv2 +from cv2 import aruco from dep.labeller.loader import Vec2 from dep.labeller.benchmarks.detector import BoundingBox, LandingPadDetector @@ -29,3 +30,32 @@ def predict(self, image: Image.Image) -> Optional[BoundingBox]: return BoundingBox(Vec2(x, y), Vec2(w, h)) + +class ArucoDetector(): + + def predict(self, image: Image.Image) -> Optional[BoundingBox]: + img = cv2.cvtColor(np.array(image), cv2.COLOR_RGB2BGR) + + aruco_dict = cv2.aruco.getPredefinedDictionary(cv2.aruco.DICT_4X4_50) + + params = cv2.aruco.DetectorParemeters() + + corners, ids, rejected = cv2.aruco.detectMarkers(img, aruco_dict, parameters=params) + + if ids: + for c in zip(corners, ids): + + pts = c[0] + + x_min = pts[:, 0].min() + x_max = pts[:, 0].max() + y_min = pts[:, 1].min() + y_max = pts[:, 1].max() + + x = (x_min + x_max) / 2 + y = (y_min + y_max) / 2 + w = (x_max - x_min) + h = (y_max - y_min) + + return BoundingBox(Vec2(x, y), Vec2(w, h)) + diff --git a/src/modules/mavctl b/src/modules/mavctl index 6cd7dc9..2fbb690 160000 --- a/src/modules/mavctl +++ b/src/modules/mavctl @@ -1 +1 @@ -Subproject commit 6cd7dc96476bff4faf3292631adbba8936e61651 +Subproject commit 2fbb69026fcb47539df5386c7cd80a01f71cf30f