Skip to content

Commit

Permalink
Python formatting tools
Browse files Browse the repository at this point in the history
  • Loading branch information
Xierumeng committed Feb 20, 2024
1 parent 04c9885 commit eb714be
Show file tree
Hide file tree
Showing 30 changed files with 780 additions and 555 deletions.
7 changes: 7 additions & 0 deletions .github/workflows/run-tests.yml
Original file line number Diff line number Diff line change
Expand Up @@ -40,6 +40,13 @@ jobs:
- name: Install zbar library
run: sudo apt-get install libzbar0

# Run linters and formatters
- name: Linters and formatters
run: |
black --check .
flake8 .
pylint .
# Run tests with PyTest
- name: Run tests
run: pytest -vv
22 changes: 17 additions & 5 deletions connection_check.py
Original file line number Diff line number Diff line change
@@ -1,6 +1,7 @@
"""
For testing MAVLink connection with DroneKit-Python.
"""

import time

import dronekit
Expand Down Expand Up @@ -99,19 +100,30 @@ def read_data(drone: dronekit.Vehicle) -> bool:
print("Next waypoint index: " + str(command_sequence.next))


if __name__ == "__main__":
def main() -> int:
"""
Main function.
"""
# TODO: Fails when wait_ready=True, debugging why this is
# wait_ready=False is dangerous
drone = dronekit.connect(CONNECTION_ADDRESS, wait_ready=False)
dronekit_vehicle = dronekit.connect(CONNECTION_ADDRESS, wait_ready=False)

if WRITE_TEST:
write_test_mission(drone)
write_test_mission(dronekit_vehicle)

if READ_TEST:
for _ in range(0, 40):
read_data(drone)
read_data(dronekit_vehicle)
time.sleep(0.5)

drone.close()
dronekit_vehicle.close()

return 0


if __name__ == "__main__":
result_main = main()
if result_main < 0:
print(f"ERROR: Status code: {result_main}")

print("Done!")
7 changes: 4 additions & 3 deletions modules/add_takeoff_and_landing_command.py
Original file line number Diff line number Diff line change
Expand Up @@ -11,8 +11,9 @@
MAVLINK_LANDING_COMMAND = dronekit.mavutil.mavlink.MAV_CMD_NAV_RETURN_TO_LAUNCH


def add_takeoff_and_landing_command(commands: "list[dronekit.Command]",
altitude: float) -> "tuple[bool, list[dronekit.Command] | None]":
def add_takeoff_and_landing_command(
commands: "list[dronekit.Command]", altitude: float
) -> "tuple[bool, list[dronekit.Command] | None]":
"""
Prepends a takeoff command and appends a landing command to a list of dronekit commands.
Expand All @@ -25,7 +26,7 @@ def add_takeoff_and_landing_command(commands: "list[dronekit.Command]",
Returns
-------
tuple[bool, list[dronekit.Command] | None]:
tuple[bool, list[dronekit.Command] | None]:
(False, None) if empty commands list,
(True, dronekit commands with takeoff and land commands that can be sent to the drone) otherwise.
"""
Expand Down
2 changes: 1 addition & 1 deletion modules/common
10 changes: 7 additions & 3 deletions modules/diversion_qr_to_waypoint_list.py
Original file line number Diff line number Diff line change
@@ -1,6 +1,7 @@
"""
Function to parse diversion QR string into a list of vertices and a rejoin waypoint.
"""

import re


Expand All @@ -16,7 +17,7 @@ def diversion_qr_to_waypoint_list(qr_text: str) -> "tuple[bool, tuple[list[str],
Returns
-------
tuple[bool, tuple[list[Waypoint], Waypoint] | None]
tuple[bool, tuple[list[Waypoint], Waypoint] | None]
Returns False, None if the string is invalid or if the list is empty.
"""
# Check if string is of valid form
Expand All @@ -25,11 +26,14 @@ def diversion_qr_to_waypoint_list(qr_text: str) -> "tuple[bool, tuple[list[str],
return False, None

# Separate qr_text into diversion_waypoints and rejoin_waypoint strings
diversion_waypoints_string, sep, rejoin_waypoint_string = qr_text.partition('.')
diversion_waypoints_string, _, rejoin_waypoint_string = qr_text.partition(".")

# Extract semicolon-separated list of diversion waypoint names without leading/trailing whitespace
diversion_waypoints = [
text.strip(" ") for text in diversion_waypoints_string.replace("Avoid the area bounded by:", "", 1).split(";")
text.strip(" ")
for text in diversion_waypoints_string.replace("Avoid the area bounded by:", "", 1).split(
";"
)
]

# Remove remaining cases of empty names
Expand Down
12 changes: 8 additions & 4 deletions modules/load_waypoint_name_to_coordinates_map.py
Original file line number Diff line number Diff line change
@@ -1,13 +1,15 @@
"""
Name-coordinate mapping from CSV file.
"""

import pathlib

from .common.kml.modules import location_ground


def load_waypoint_name_to_coordinates_map(waypoint_file_path: pathlib.Path) \
-> "tuple[bool, dict[str, location_ground.LocationGround]]":
def load_waypoint_name_to_coordinates_map(
waypoint_file_path: pathlib.Path,
) -> "tuple[bool, dict[str, location_ground.LocationGround]]":
"""
Creates a name to coordinate dictionary from the CSV file.
"""
Expand All @@ -18,12 +20,14 @@ def load_waypoint_name_to_coordinates_map(waypoint_file_path: pathlib.Path) \
with open(waypoint_file_path, encoding="utf-8") as file:
for line in file:
# Skip header and empty lines
parts = line.split(',')
parts = line.split(",")
if line in "name,latitude,longitude\n" or len(parts) < 3:
continue

name, latitude, longitude = parts
name_to_coordinates_map[name] = location_ground.LocationGround(name, float(latitude), float(longitude))
name_to_coordinates_map[name] = location_ground.LocationGround(
name, float(latitude), float(longitude)
)

if len(name_to_coordinates_map) > 0:
return True, name_to_coordinates_map
Expand Down
2 changes: 1 addition & 1 deletion modules/qr_input.py
Original file line number Diff line number Diff line change
Expand Up @@ -45,7 +45,7 @@ def qr_input(device: "int | str") -> "tuple[bool, str | None]":
break

# Exit early on manual quit
if cv2.waitKey(1) == ord('q'):
if cv2.waitKey(1) == ord("q"):
break

# Cleanup
Expand Down
3 changes: 2 additions & 1 deletion modules/qr_to_waypoint_names.py
Original file line number Diff line number Diff line change
@@ -1,11 +1,12 @@
"""
Module to parse QR string to waypoints.
"""

import re


def qr_to_waypoint_names(qr_text: str) -> "tuple[bool, list[str] | None]":
"""
"""
Function for parsing QR text into list of waypoints.
Example of valid string: "Follow route: Waterloo; Aerial; Robotics; Group 15"
Example of invalid string: "Avoid the area bounded by: Zulu; Bravo; Tango; Uniform. Rejoin the route at Lima"
Expand Down
8 changes: 4 additions & 4 deletions modules/waypoint_names_to_coordinates.py
Original file line number Diff line number Diff line change
Expand Up @@ -5,15 +5,15 @@
from .common.kml.modules import location_ground


def waypoint_names_to_coordinates(waypoint_names: "list[str]",
waypoint_mapping: "dict[str, location_ground.LocationGround]") \
-> "tuple[bool, list[location_ground.LocationGround]]":
def waypoint_names_to_coordinates(
waypoint_names: "list[str]", waypoint_mapping: "dict[str, location_ground.LocationGround]"
) -> "tuple[bool, list[location_ground.LocationGround]]":
"""
Converts a list of waypoint names to their corresponding coordinates based on a waypoint mapping.
Args:
waypoint_names (list[str]): A list of waypoint names.
waypoint_mapping (dict[str, LocationGround]): A dictionary mapping waypoint names to their
waypoint_mapping (dict[str, LocationGround]): A dictionary mapping waypoint names to their
corresponding LocationGround objects with coordinates.
Returns:
Expand Down
7 changes: 4 additions & 3 deletions modules/waypoint_tracking.py
Original file line number Diff line number Diff line change
Expand Up @@ -6,8 +6,9 @@
import dronekit


def get_current_waypoint_info(drone: dronekit.Vehicle) \
-> "tuple[bool, tuple[int, tuple[float, float] | None] | None]":
def get_current_waypoint_info(
drone: dronekit.Vehicle,
) -> "tuple[bool, tuple[int, tuple[float, float] | None] | None]":
"""
Function to retrieve information about the current waypoint sequence and destination
Expand All @@ -19,7 +20,7 @@ def get_current_waypoint_info(drone: dronekit.Vehicle) \
Returns
-------
tuple[bool, tuple[int, tuple[float, float] | None] | None]:
(True, destination waypoint information), where information is (index, location).
(True, destination waypoint information), where information is (index, location).
location can be None.
"""
# Download the mission commands from the drone
Expand Down
5 changes: 3 additions & 2 deletions modules/waypoints_dict_to_list.py
Original file line number Diff line number Diff line change
Expand Up @@ -5,8 +5,9 @@
from .common.kml.modules import location_ground


def waypoints_dict_to_list(waypoint_name_to_coordinates: "dict[str, location_ground.LocationGround]") \
-> "tuple[bool, list[location_ground.LocationGround]]":
def waypoints_dict_to_list(
waypoint_name_to_coordinates: "dict[str, location_ground.LocationGround]",
) -> "tuple[bool, list[location_ground.LocationGround]]":
"""
Converts dictionary of waypoints into a list.
Expand Down
7 changes: 4 additions & 3 deletions modules/waypoints_to_commands.py
Original file line number Diff line number Diff line change
Expand Up @@ -12,8 +12,9 @@
ACCEPT_RADIUS = 10


def waypoints_to_commands(waypoints: "list[location_ground.LocationGround]",
altitude: int) -> "tuple[bool, list[dronekit.Command] | None]":
def waypoints_to_commands(
waypoints: "list[location_ground.LocationGround]", altitude: int
) -> "tuple[bool, list[dronekit.Command] | None]":
"""
Convert list of waypoints to dronekit commands.
Expand All @@ -26,7 +27,7 @@ def waypoints_to_commands(waypoints: "list[location_ground.LocationGround]",
Returns
-------
tuple[bool, list[dronekit.Command] | None]:
tuple[bool, list[dronekit.Command] | None]:
(False, None) if empty waypoints list,
(True, dronekit commands that can be sent to the drone) otherwise dronekit commands that can be sent to the drone.
"""
Expand Down
35 changes: 20 additions & 15 deletions path_2023.py
Original file line number Diff line number Diff line change
@@ -1,6 +1,7 @@
"""
Task 1 path.
Reads waypoints from QR code and sends drone commands.
"""

import pathlib
import time

Expand All @@ -27,19 +28,20 @@
DELAY = 0.1 # seconds


# Required for checks
# pylint: disable-next=too-many-branches,too-many-return-statements
def run() -> int:
# Code copied into path_2024.py
# pylint: disable=duplicate-code
def main() -> int:
"""
Reads waypoints from QR code and sends drone commands.
Main function.
"""
# Wait ready is false as the drone may be on the ground
drone = dronekit.connect(CONNECTION_ADDRESS, wait_ready = False)
drone = dronekit.connect(CONNECTION_ADDRESS, wait_ready=False)

result, waypoint_name_to_coordinates = \
result, waypoint_name_to_coordinates = (
load_waypoint_name_to_coordinates_map.load_waypoint_name_to_coordinates_map(
WAYPOINT_FILE_PATH,
)
)
if not result:
print("ERROR: load_waypoint_name_to_coordinates_map")
return -1
Expand All @@ -53,7 +55,8 @@ def run() -> int:

result, _ = ground_locations_to_kml.ground_locations_to_kml(
waypoints_list,
KML_FILE_PREFIX, KML_FILE_PARENT_DIRECTORY,
KML_FILE_PREFIX,
KML_FILE_PARENT_DIRECTORY,
)
if not result:
print("ERROR: Unable to generate KML file")
Expand Down Expand Up @@ -82,8 +85,9 @@ def run() -> int:
print("Error: waypoints_to_commands")
return -1

result, takeoff_landing_commands = \
result, takeoff_landing_commands = (
add_takeoff_and_landing_command.add_takeoff_and_landing_command(waypoint_commands, ALTITUDE)
)
if not result:
print("Error: add_takeoff_and_landing_command")
return -1
Expand Down Expand Up @@ -111,11 +115,12 @@ def run() -> int:
return 0


# pylint: enable=duplicate-code


if __name__ == "__main__":
# Not a constant
# pylint: disable-next=invalid-name
result_run = run()
if result_run < 0:
print("ERROR")
result_main = main()
if result_main < 0:
print(f"ERROR: Status code: {result_main}")

print("Done")
print("Done!")
30 changes: 15 additions & 15 deletions path_2024.py
Original file line number Diff line number Diff line change
@@ -1,6 +1,7 @@
"""
Path template.
Reads in hardcoded waypoints from CSV file and sends drone commands.
"""

import pathlib
import time

Expand All @@ -23,21 +24,20 @@
DELAY = 0.1 # seconds


# Required for checks
# pylint: disable-next=too-many-return-statements
def run() -> int:
def main() -> int:
"""
Reads in hardcoded waypoints from CSV file and sends drone commands.
Main function.
"""
# Wait ready is false as the drone may be on the ground
drone = dronekit.connect(CONNECTION_ADDRESS, wait_ready = False)
drone = dronekit.connect(CONNECTION_ADDRESS, wait_ready=False)

# Read in hardcoded waypoints from CSV file
# Waypoints are stored in order of insertion, starting with the top row
result, waypoint_name_to_coordinates = \
result, waypoint_name_to_coordinates = (
load_waypoint_name_to_coordinates_map.load_waypoint_name_to_coordinates_map(
WAYPOINT_FILE_PATH,
)
)
if not result:
print("ERROR: load_waypoint_name_to_coordinates_map")
return -1
Expand All @@ -51,7 +51,8 @@ def run() -> int:

result, _ = ground_locations_to_kml.ground_locations_to_kml(
waypoints_list,
KML_FILE_PREFIX, KML_FILE_PARENT_DIRECTORY,
KML_FILE_PREFIX,
KML_FILE_PARENT_DIRECTORY,
)
if not result:
print("ERROR: Unable to generate KML file")
Expand All @@ -65,11 +66,12 @@ def run() -> int:
print("Error: waypoints_to_commands")
return -1

result, takeoff_landing_commands = \
result, takeoff_landing_commands = (
add_takeoff_and_landing_command.add_takeoff_and_landing_command(
waypoint_commands,
ALTITUDE,
)
)
if not result:
print("Error: add_takeoff_and_landing_command")
return -1
Expand Down Expand Up @@ -98,10 +100,8 @@ def run() -> int:


if __name__ == "__main__":
# Not a constant
# pylint: disable-next=invalid-name
result_run = run()
if result_run < 0:
print("ERROR")
result_main = main()
if result_main < 0:
print(f"ERROR: Status code: {result_main}")

print("Done")
print("Done!")
Loading

0 comments on commit eb714be

Please sign in to comment.