Skip to content

Commit

Permalink
This commit does not belong to any branch on this repository, and may belong to a fork outside of the repository.
fixed more formatting issues
Browse files Browse the repository at this point in the history
eshaan-mehta committed Feb 21, 2024

Verified

This commit was created on GitHub.com and signed with GitHub’s verified signature. The key has expired.
1 parent d9e99da commit 18ebbf9
Showing 3 changed files with 9 additions and 8 deletions.
15 changes: 8 additions & 7 deletions modules/check_stop_condition.py
Original file line number Diff line number Diff line change
@@ -1,14 +1,13 @@
"""
Checks whether the drone has reached its max flight time and sends it back to launch.
"""

import dronekit

from . import upload_commands


MAVLINK_RTL_LANDING_FRAME = dronekit.mavutil.mavlink.MAV_FRAME_GLOBAL
MAVLINK_RTL_LANDING_COMMAND = dronekit.mavutil.mavlink.MAV_CMD_NAV_RETURN_TO_LAUNCH
MAVLINK_RTL_FRAME = dronekit.mavutil.mavlink.MAV_FRAME_GLOBAL
MAVLINK_RTL_COMMAND = dronekit.mavutil.mavlink.MAV_CMD_NAV_RETURN_TO_LAUNCH


def check_stop_condition(start_time: float,
@@ -36,12 +35,12 @@ def check_stop_condition(start_time: float,
if current_time - start_time < maximum_flight_time:
return False

drone_landing_command = dronekit.Command(
rtl_command = dronekit.Command(
0,
0,
0,
MAVLINK_RTL_LANDING_FRAME,
MAVLINK_RTL_LANDING_COMMAND,
MAVLINK_RTL_FRAME,
MAVLINK_RTL_COMMAND,
0,
0,
0, # param1
@@ -54,6 +53,8 @@ def check_stop_condition(start_time: float,
)

# Invoke upload_commands to clear previous commands and direct drone back to launch location
upload_commands.upload_commands(drone, [drone_landing_command])
result = upload_commands.upload_commands(drone, [rtl_command])
if not result:
print("Unable to upload rtl command to drone command sequence.")

return True
1 change: 1 addition & 0 deletions path_2024.py
Original file line number Diff line number Diff line change
@@ -102,6 +102,7 @@ def run() -> int:
is_returning_to_launch = check_stop_condition.check_stop_condition(start_time, current_time, drone, MAXIMUM_FLIGHT_TIME)
if is_returning_to_launch:
break

print(f"Elapsed time (s): {current_time - start_time}")

time.sleep(DELAY)
1 change: 0 additions & 1 deletion tests/test_check_stop_condition.py
Original file line number Diff line number Diff line change
@@ -1,7 +1,6 @@
"""
Test the drone stop condition.
"""

import sys
import time

0 comments on commit 18ebbf9

Please sign in to comment.