Skip to content
Open
Show file tree
Hide file tree
Changes from all commits
Commits
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
3 changes: 1 addition & 2 deletions bin/run-nav.sh
Original file line number Diff line number Diff line change
Expand Up @@ -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"
4 changes: 2 additions & 2 deletions install/shepard.service
Original file line number Diff line number Diff line change
Expand Up @@ -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
25 changes: 25 additions & 0 deletions src/flight_tests/demo_flight.py
Original file line number Diff line number Diff line change
@@ -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()
23 changes: 23 additions & 0 deletions src/flight_tests/mavctl-test.py
Original file line number Diff line number Diff line change
@@ -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()
113 changes: 0 additions & 113 deletions src/flight_tests/precision_land_test_FH.py

This file was deleted.

30 changes: 30 additions & 0 deletions src/flight_tests/precision_landing.py
Original file line number Diff line number Diff line change
@@ -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)
2 changes: 1 addition & 1 deletion src/flight_tests/vel_control_test.py
Original file line number Diff line number Diff line change
Expand Up @@ -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)
Expand Down
43 changes: 43 additions & 0 deletions src/modules/autopilot/mavctl_advanced.py
Original file line number Diff line number Diff line change
@@ -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)
Loading
Loading