Skip to content
New issue

Have a question about this project? Sign up for a free GitHub account to open an issue and contact its maintainers and the community.

By clicking “Sign up for GitHub”, you agree to our terms of service and privacy statement. We’ll occasionally send you account related emails.

Already on GitHub? Sign in to your account

fixed waypoints_to_spline_commands #31

Open
wants to merge 5 commits into
base: main
Choose a base branch
from
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
56 changes: 56 additions & 0 deletions modules/waypoints_to_spline_commands.py
Original file line number Diff line number Diff line change
@@ -0,0 +1,56 @@
"""
Function to convert list of waypoints to dronekit commands.
"""

import dronekit

from . import waypoint


MAVLINK_FRAME = dronekit.mavutil.mavlink.MAV_FRAME_GLOBAL_RELATIVE_ALT
MAVLINK_COMMAND = dronekit.mavutil.mavlink.MAV_CMD_NAV_SPLINE_WAYPOINT
ACCEPT_RADIUS = 10


def waypoints_to_spline_commands(waypoints: "list[waypoint.Waypoint]",
altitude: int) -> "tuple[bool, list[dronekit.Command] | None]":
"""
Convert list of waypoints to dronekit commands.

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

dronekit_command_list = []

for point in waypoints:
command = dronekit.Command(
0,
0,
0,
MAVLINK_FRAME,
MAVLINK_COMMAND,
0,
0,
0, # param1
ACCEPT_RADIUS,
0,
0,
point.latitude,
point.longitude,
altitude,
)
dronekit_command_list.append(command)

return True, dronekit_command_list
61 changes: 61 additions & 0 deletions tests/test_waypoints_to_spline_commands.py
Original file line number Diff line number Diff line change
@@ -0,0 +1,61 @@
"""
Test process.
"""

import dronekit

from modules import waypoint
from modules import waypoints_to_spline_commands


def test_waypoints_to_spline_commands_empty_input():
"""
Tests functionality correctness of waypoints_to_spline_commands on empty input.
"""
waypoints = []
altitude = 100

result, commands_actual = waypoints_to_spline_commands.waypoints_to_spline_commands(
waypoints,
Copy link
Contributor

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

Remove extra space after the comma.

altitude
Copy link
Contributor

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

Add comma at end of this line.

)

assert not result
assert commands_actual is None


def test_waypoints_to_spline_commands():
"""
Tests functionality correctness of waypoints_to_spline_commands.
"""
waypoints = [
waypoint.Waypoint("Waypoint 1", 42.123, -73.456),
waypoint.Waypoint("Waypoint 2", 42.789, -73.987),
waypoint.Waypoint("Waypoint 3", 42.555, -73.321),
]
altitude = 100

result, commands_actual = waypoints_to_spline_commands.waypoints_to_spline_commands(
waypoints,
altitude
Comment on lines +39 to +40
Copy link
Contributor

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

Same as above.

)

assert result

assert isinstance(commands_actual, list)
assert len(commands_actual) == len(waypoints)

for i, command in enumerate(commands_actual):
lat_expected = waypoints[i].latitude
lng_expected = waypoints[i].longitude

assert isinstance(command, dronekit.Command)
assert command.frame == waypoints_to_spline_commands.MAVLINK_FRAME
assert command.command == waypoints_to_spline_commands.MAVLINK_COMMAND
assert command.param1 == 0
assert command.param2 == waypoints_to_spline_commands.ACCEPT_RADIUS
assert command.param3 == 0
assert command.param4 == 0
assert command.x == lat_expected
assert command.y == lng_expected
assert command.z == altitude