Skip to content

Commit

Permalink
Add Altitude to Task 2 (#58)
Browse files Browse the repository at this point in the history
* Created LocationGroundAndAltitude class

* Fixed indentation issues

* Fixed formatting issues

* Created module to read CSV with altitude and added test cases

* Fix format issues

* Created overloaded dict to list function

* Fixed formatting

* Renamed function in waypoint_dict_to_list

* Created waypoint to command function with LocationGroundAndAltitude

* Fixed formatting issues

* Added new modules to path_2024.py

* Fixed formatting issues

* Fixed formatting issues on CI

* Fixed formatting issues on CI - Part 2

* Addressed nits

* Fixed linter issues
  • Loading branch information
mgupta27 authored Apr 21, 2024
1 parent a588955 commit 0506fe1
Show file tree
Hide file tree
Showing 11 changed files with 305 additions and 37 deletions.
24 changes: 13 additions & 11 deletions 2024/waypoints/competition_task_2.csv
Original file line number Diff line number Diff line change
@@ -1,11 +1,13 @@
name,latitude,longitude
1,48.509661,-71.645100
2,48.509183,-71.643465
3,48.507690,-71.644438
4,48.507667,-71.646092
5,48.507642,-71.646416
6,48.507547,-71.646720
7,48.507413,-71.646954
8,48.507256,-71.647120
9,48.507103,-71.647212
10,48.506962,-71.647268
name,latitude,longitude,altitude
1,48.509661,-71.645100,106.68
2,48.509183,-71.643465,106.68
3,48.509183,-71.643465,76.2
4,48.507690,-71.644438,76.2
5,48.507690,-71.644438,60.96
6,48.507667,-71.646092,60.96
7,48.507642,-71.646416,60.96
8,48.507547,-71.646720,60.96
9,48.507413,-71.646954,60.96
10,48.507256,-71.647120,60.96
11,48.507103,-71.647212,60.96
12,48.506962,-71.647268,30.48
30 changes: 15 additions & 15 deletions 2024/waypoints/wrestrc.csv
Original file line number Diff line number Diff line change
@@ -1,15 +1,15 @@
name,latitude,longitude
1,43.4338974,-80.5773193
2,43.433985,-80.577853
3,43.4341087,-80.5783774
4,43.4342606,-80.5791324
5,43.4343726,-80.5796206
6,43.434322,-80.5797641
7,43.4339802,-80.5799559
8,43.4338399,-80.5799478
9,43.4334163,-80.579115
10,43.4332634,-80.5782366
11,43.433314,-80.5780595
12,43.4337425,-80.5778342
13,43.4337805,-80.5776612
14,43.4337367,-80.5773863
name,latitude,longitude,altitude
1,43.4338974,-80.5773193,50
2,43.433985,-80.577853,50
3,43.4341087,-80.5783774,50
4,43.4342606,-80.5791324,50
5,43.4343726,-80.5796206,50
6,43.434322,-80.5797641,50
7,43.4339802,-80.5799559,50
8,43.4338399,-80.5799478,50
9,43.4334163,-80.579115,50
10,43.4332634,-80.5782366,50
11,43.433314,-80.5780595,50
12,43.4337425,-80.5778342,50
13,43.4337805,-80.5776612,50
14,43.4337367,-80.5773863,50
30 changes: 30 additions & 0 deletions modules/load_waypoint_name_to_coordinates_map.py
Original file line number Diff line number Diff line change
Expand Up @@ -4,6 +4,8 @@

import pathlib

from . import waypoint

from .common.kml.modules import location_ground


Expand Down Expand Up @@ -33,3 +35,31 @@ def load_waypoint_name_to_coordinates_map(
return True, name_to_coordinates_map

return False, None


def load_waypoint_name_to_coordinates_and_altitude_map(
waypoint_file_path: pathlib.Path,
) -> "tuple[bool, dict[str, waypoint.Waypoint]]":
"""
Creates a name to coordinate and altitude dictionary from the CSV file.
"""
if not waypoint_file_path.exists():
return False, None

name_to_coordinates_and_altitude_map = {}
with open(waypoint_file_path, encoding="utf-8") as file:
for line in file:
# Skp header and empty lines
parts = line.split(",")
if line in "name,latitude,longitude,altitude\n" or len(parts) < 4:
continue

name, latitude, longitude, altitude = parts
name_to_coordinates_and_altitude_map[name] = waypoint.Waypoint(
name, float(latitude), float(longitude), float(altitude)
)

if len(name_to_coordinates_and_altitude_map) > 0:
return True, name_to_coordinates_and_altitude_map

return False, None
54 changes: 54 additions & 0 deletions modules/waypoint.py
Original file line number Diff line number Diff line change
@@ -0,0 +1,54 @@
"""
Class to store LocationGround and corresponding altitude.
"""

from .common.kml.modules import location_ground


class Waypoint:
"""
LocationGroundAndAltitude represents a geographical ground location and an altitude
with a name, latitude, longitude, and altitude.
Attributes:
name (str): The name or label for the location.
latitude (float): The latitude coordinate in decimal degrees.
longitude (float): The longitude coordinate in decimal degrees.
altitude (float): The altitude coordinate in metres.
Methods:
__init__(name, latitude, longitude, altitude): Initializes a LocationGroundAndAltitude object.
__eq__(other): Checks if two LocationGroundAndAltitude objects are equal.
__repr__(): Returns a string representation of the LocationGroundAndAltitude object.
"""

def __init__(self, name: str, latitude: float, longitude: float, altitude: float) -> None:
"""
Constructor for the LocationGroundAndAltitude object.
Args:
name (str): The name or label for the location.
latitude (float): The latitude coordinate in decimal degrees.
longitude (float): The longitude coordinate in decimal degrees.
altitude (float): The altitude of the coordinate in metres.
"""
self.location_ground = location_ground.LocationGround(name, latitude, longitude)
self.altitude = altitude

def __eq__(self, other: "Waypoint") -> bool:
"""
Checks if two LocationGroundAndAltitude objects are equal.
Args:
other (LocationGroundAndAltitude): The other LocationGroundAndAltitude object to compare to.
"""
if not isinstance(other, Waypoint):
return False

return self.location_ground == other.location_ground and self.altitude == other.altitude

def __repr__(self) -> str:
"""
String representation
"""
return f"LocationGroundAndAltitude: {repr(self.location_ground)}, altitude: {self.altitude}"
27 changes: 27 additions & 0 deletions modules/waypoints_dict_to_list.py
Original file line number Diff line number Diff line change
Expand Up @@ -2,6 +2,7 @@
Module to convert waypoints dict to waypoints list.
"""

from . import waypoint
from .common.kml.modules import location_ground


Expand Down Expand Up @@ -29,3 +30,29 @@ def waypoints_dict_to_list(
waypoints_list = list(waypoint_name_to_coordinates.values())

return True, waypoints_list


def waypoints_dict_with_altitude_to_list(
waypoint_name_to_coordinates_and_altitude: "dict[str, waypoint.Waypoint]",
) -> "tuple[bool, list[waypoint.Waypoint]]":
"""
Converts dictionary of waypoints into a list.
Parameters
----------
waypoint_name_to_coordinates_and_altitude: dict[str, LocationGroundAndAltitude]
Waypoint mapping of name to (latitude, longitude, altitude).
Returns
-------
bool: Whether waypoint data conversion was a success.
list[Waypoint]: List of the waypoint coordinates and altitude.
"""
# Check for empty input dictionary
if len(waypoint_name_to_coordinates_and_altitude) == 0:
return False, None

# Create list of all the values in the input dictionary, ie. the LocationGround
waypoints_list = list(waypoint_name_to_coordinates_and_altitude.values())

return True, waypoints_list
40 changes: 38 additions & 2 deletions modules/waypoints_to_commands.py
Original file line number Diff line number Diff line change
Expand Up @@ -4,7 +4,7 @@

import dronekit

from . import generate_command
from . import generate_command, waypoint
from .common.kml.modules import location_ground


Expand All @@ -20,7 +20,7 @@ def waypoints_to_commands(
Parameters
----------
waypoints: list[LocationGround]
list of locationGround objects containing names and coordinates in decimal degrees.
list of LocationGround objects containing names and coordinates in decimal degrees.
altitude: float
altitude in meters to command the drone to.
Expand All @@ -43,3 +43,39 @@ def waypoints_to_commands(
dronekit_command_list.append(command)

return True, dronekit_command_list


def waypoints_with_altitude_to_commands(
waypoints: "list[waypoint.Waypoint]",
) -> "tuple[bool, list[dronekit.Command] | None]":
"""
Convert list of waypoints to dronekit commands.
Parameters
----------
waypoints: list[LocationGroundAndAltitude]
list of LocationGroundAndAltitude objects containing names, coordinates in decimal degrees, and altitude in metres.
Returns
-------
tuple[bool, list[dronekit.Command] | None]:
(False, None) if empty waypoints list,
(True, dronekit commands that can be sent to the drone) otherwise.
"""
if len(waypoints) == 0:
return False, None

dronekit_command_list = []

for point in waypoints:
command = generate_command.waypoint(
0.0,
ACCEPT_RADIUS,
point.location_ground.latitude,
point.location_ground.longitude,
point.altitude,
)

dronekit_command_list.append(command)

return True, dronekit_command_list
15 changes: 9 additions & 6 deletions path_2024.py
Original file line number Diff line number Diff line change
Expand Up @@ -41,32 +41,32 @@ def main() -> int:
(
result,
waypoint_name_to_coordinates,
) = load_waypoint_name_to_coordinates_map.load_waypoint_name_to_coordinates_map(
) = load_waypoint_name_to_coordinates_map.load_waypoint_name_to_coordinates_and_altitude_map(
WAYPOINT_FILE_PATH,
)
if not result:
print("ERROR: load_waypoint_name_to_coordinates_map")
return -1

result, waypoints_list = waypoints_dict_to_list.waypoints_dict_to_list(
result, waypoints_list = waypoints_dict_to_list.waypoints_dict_with_altitude_to_list(
waypoint_name_to_coordinates
)
if not result:
print("ERROR: Unable to convert waypoints from dict to list")
return -1

location_ground_list = list(map(lambda waypoint: waypoint.location_ground, waypoints_list))
result, _ = ground_locations_to_kml.ground_locations_to_kml(
waypoints_list,
location_ground_list,
KML_FILE_PREFIX,
LOG_DIRECTORY_PATH,
)
if not result:
print("ERROR: Unable to generate KML file")
return -1

result, waypoint_commands = waypoints_to_commands.waypoints_to_commands(
result, waypoint_commands = waypoints_to_commands.waypoints_with_altitude_to_commands(
waypoints_list,
ALTITUDE,
)
if not result:
print("Error: waypoints_to_commands")
Expand All @@ -76,7 +76,10 @@ def main() -> int:
loiter_coordinate = waypoints_list[-1]

result, takeoff_loiter_commands = add_takeoff_and_loiter_command.add_takeoff_and_loiter_command(
waypoint_commands, loiter_coordinate.latitude, loiter_coordinate.longitude, ALTITUDE
waypoint_commands,
loiter_coordinate.location_ground.latitude,
loiter_coordinate.location_ground.longitude,
loiter_coordinate.altitude,
)
if not result:
print("Error: add_takeoff_and_loiter_command")
Expand Down
3 changes: 3 additions & 0 deletions tests/test_csv/test_normal_csv_with_altitude.csv
Original file line number Diff line number Diff line change
@@ -0,0 +1,3 @@
name,latitude,longitude,altitude
WARG,43.47323264522664,-80.54011639872981,10.0
University of Waterloo Station for 301 ION,43.4735247614021,-80.54144667502672,10.0
57 changes: 56 additions & 1 deletion tests/unit/test_load_waypoint_name_to_coordinates_map.py
Original file line number Diff line number Diff line change
Expand Up @@ -4,7 +4,7 @@

import pathlib

from modules import load_waypoint_name_to_coordinates_map
from modules import load_waypoint_name_to_coordinates_map, waypoint
from modules.common.kml.modules import location_ground


Expand Down Expand Up @@ -38,6 +38,37 @@ def test_normal_file() -> None:
assert actual == expected


def test_normal_file_with_altitude() -> None:
"""
Normal CSV file with altitude.
"""
# Setup
normal_csv_file_with_altitude_path = pathlib.Path(
"tests", "test_csv", "test_normal_csv_with_altitude.csv"
)
excepted = {
"WARG": waypoint.Waypoint("WARG", 43.47323264522664, -80.54011639872981, 10.0),
"University of Waterloo Station for 301 ION": waypoint.Waypoint(
"University of Waterloo Station for 301 ION",
43.4735247614021,
-80.54144667502672,
10.0,
),
}

# Run
(
result,
actual,
) = load_waypoint_name_to_coordinates_map.load_waypoint_name_to_coordinates_and_altitude_map(
normal_csv_file_with_altitude_path,
)

# Test
assert result
assert actual == excepted


def test_empty_file() -> None:
"""
Empty CSV file.
Expand All @@ -54,6 +85,18 @@ def test_empty_file() -> None:
assert not result
assert actual is None

# Run
(
result,
actual,
) = load_waypoint_name_to_coordinates_map.load_waypoint_name_to_coordinates_and_altitude_map(
empty_csv_file_path,
)

# Test
assert not result
assert actual is None


def test_nonexistent_file() -> None:
"""
Expand All @@ -70,3 +113,15 @@ def test_nonexistent_file() -> None:
# Test
assert not result
assert actual is None

# Run
(
result,
actual,
) = load_waypoint_name_to_coordinates_map.load_waypoint_name_to_coordinates_and_altitude_map(
nonexistent_file_path,
)

# Test
assert not result
assert actual is None
Loading

0 comments on commit 0506fe1

Please sign in to comment.