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

Read Mavlink from CSV file. Modules completed with tests #65

Merged
merged 4 commits into from
Jul 18, 2024
Merged
Show file tree
Hide file tree
Changes from 2 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
139 changes: 139 additions & 0 deletions modules/advanced_csv_to_commands.py
Original file line number Diff line number Diff line change
@@ -0,0 +1,139 @@
"""
An command generator with advanced parameters and greater flexibility
"""

import pathlib

import dronekit


VALID_FRAMES = {
"global": dronekit.mavutil.mavlink.MAV_FRAME_GLOBAL,
"global_relative_alt": dronekit.mavutil.mavlink.MAV_FRAME_GLOBAL_RELATIVE_ALT,
}

VALID_COMMANDS = {
"land": dronekit.mavutil.mavlink.MAV_CMD_NAV_LAND,
"return_to_launch": dronekit.mavutil.mavlink.MAV_CMD_NAV_RETURN_TO_LAUNCH,
"takeoff": dronekit.mavutil.mavlink.MAV_CMD_NAV_TAKEOFF,
"waypoint": dronekit.mavutil.mavlink.MAV_CMD_NAV_WAYPOINT,
"waypoint_spline": dronekit.mavutil.mavlink.MAV_CMD_NAV_SPLINE_WAYPOINT,
"loiter_timed": dronekit.mavutil.mavlink.MAV_CMD_NAV_LOITER_TIME,
"loiter_unlimited": dronekit.mavutil.mavlink.MAV_CMD_NAV_LOITER_UNLIM,
"do_jump": dronekit.mavutil.mavlink.MAV_CMD_DO_JUMP,
}


def generate_command_advanced(
frame: str,
command_type: str,
param1: float, # I'm anxious about this because of do_jump which requires ints
Copy link
Contributor

Choose a reason for hiding this comment

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

This function can dispatch to more specialized functions to construct the various commands.

param2: float,
param3: float,
param4: float,
param5: float,
param6: float,
param7: float,
) -> "tuple[bool,dronekit.Command]":
Copy link
Contributor

Choose a reason for hiding this comment

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

"tuple[bool, dronekit.Command | None]"

"""
Parameters:

frame: The command's frame of reference. Frame should be one of the following two values.
- global (usually used for landing or return to launch)
- global_relative_alt (all other commands, such as waypoint, spline waypoint, etc.)

command_type: The command type. Depending on this value, params 1 through 7 will take on different meanings. This should be one of the following enums:
- land:
- return_to_launch: Return to the home location where the vehicle was last armed.
- takeoff
- waypoint: Navigate to the specified waypoint
- waypoint_spline
- loiter_timed: Loiter at the specified location for an specified amount of time
- loiter_unlimited: Loiter at the specified location for an unlimited amount of time
- do_jump: Jump to the specified command in the mission list.
Copy link
Contributor

Choose a reason for hiding this comment

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

I think linking the Confluence document is sufficient, no need to repeat the information from the dictionary above or the information in the document.


param1 through param7: These take different meanings depending on the command type. See the documentation for meanings:
https://uwarg-docs.atlassian.net/wiki/spaces/CV/pages/2567274629/Encoded+MAVLink+commands
Alteratively, here is the official documentation:
https://ardupilot.org/copter/docs/common-mavlink-mission-command-messages-mav_cmd.html#commands-supported-by-copter

Returns: Whether or not the command was successful, and the mission command.
"""

# Invalid command
if command_type not in VALID_COMMANDS:
return False, None

# Invalid frame type
if frame not in VALID_FRAMES:
return False, None

return True, dronekit.Command(
0,
0,
0,
VALID_FRAMES[frame],
VALID_COMMANDS[command_type],
0,
0,
param1,
param2,
param3,
param4,
param5,
param6,
param7,
)


def csv_to_commands_list(
mission_file_path: pathlib.Path,
) -> "tuple[bool, list[dronekit.Command]]":
"""
A method that reads a list of advanced commands from a csv file and generates a mission.
Parameters:
- mission_file_path: The advanced csv file containing the different mission commands

Returns:
- Whether or not the mission was successfully created
- A list of dronekit commands that represent the mission

"""
# Does the file path exist?
Copy link
Contributor

Choose a reason for hiding this comment

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

Remove.

if not mission_file_path.exists():
return False, None

mission = []
with open(mission_file_path, encoding="utf-8") as file:
for line in file:
# Skip header and empty lines
parts = line.split(",")
Copy link
Contributor

Choose a reason for hiding this comment

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

Move below the conditional below.

if line in "frame,command_type,param1,param2,param3,param4,param5,param6,param7\n":
continue

# If the parameters are messed up
if len(parts) != 9:
return False, None

frame, command_type, param1, param2, param3, param4, param5, param6, param7 = parts
success, command = generate_command_advanced(
Copy link
Contributor

Choose a reason for hiding this comment

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

result, command =

frame,
command_type,
float(param1),
float(param2),
float(param3),
float(param4),
float(param5),
float(param6),
float(param7),
)
# Was the command successfully generated?
Copy link
Contributor

Choose a reason for hiding this comment

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

Remove.

if not success:
return False, None

mission.append(command)

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

return False, None
Copy link
Contributor

Choose a reason for hiding this comment

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

Switch:

if len(mission) == 0:
    return False, None

return True, mission

1 change: 1 addition & 0 deletions tests/test_csv/test_empty_advanced_csv.csv
Original file line number Diff line number Diff line change
@@ -0,0 +1 @@
frame,command_type,param1,param2,param3,param4,param5,param6,param7
9 changes: 9 additions & 0 deletions tests/test_csv/test_incorrect_num_params_csv.csv
Original file line number Diff line number Diff line change
@@ -0,0 +1,9 @@
frame,command_type,param1,param2,param3,param4,param5,param6,param7
global_relative_alt,takeoff,0,0,0,0,0,0,50
global_relative_alt,loiter_timed,6,0,0,0,43.47323264522664,-80.5401164,50
global_relative_alt,loiter_unlimited,0,0,0,43.47,-80.55,50
global_relative_alt,waypoint,0,0.1,0,0,43.47352476,-80.54144668,10
global_relative_alt,waypoint_spline,0,0,0,0,43.47323264522664,-80.5401164,10
global,return_to_launch,0,0,0,0,0,0,0
global,land,0,0,0,0,0,0,0
global_relative_alt,do_jump,4,2,0,0,0,0,0
9 changes: 9 additions & 0 deletions tests/test_csv/test_invalid_command_name.csv
Original file line number Diff line number Diff line change
@@ -0,0 +1,9 @@
frame,command_type,param1,param2,param3,param4,param5,param6,param7
global_relative_alt,takeoff,0,0,0,0,0,0,50
global_relative_alt,loiter_timed,6,0,0,0,43.47323264522664,-80.5401164,50
global_relative_alt,loiter_unlimited,0,0,0,0,43.47,-80.55,50
global_relative_alt,wayypoint,0,0.1,0,0,43.47352476,-80.54144668,10
global_relative_alt,waypoint_spline,0,0,0,0,43.47323264522664,-80.5401164,10
global,return_to_launch,0,0,0,0,0,0,0
global,land,0,0,0,0,0,0,0
global_relative_alt,do_jump,4,2,0,0,0,0,0
9 changes: 9 additions & 0 deletions tests/test_csv/test_invalid_frame_name.csv
Original file line number Diff line number Diff line change
@@ -0,0 +1,9 @@
frame,command_type,param1,param2,param3,param4,param5,param6,param7
global_relative_alt,takeoff,0,0,0,0,0,0,50
global_relative_alt,loiter_timed,6,0,0,0,43.47323264522664,-80.5401164,50
global_relative_alt,loiter_unlimited,0,0,0,0,43.47,-80.55,50
global_relative_alt,waypoint,0,0.1,0,0,43.47352476,-80.54144668,10
global_relative_alt,waypoint_spline,0,0,0,0,43.47323264522664,-80.5401164,10
globbal,return_to_launch,0,0,0,0,0,0,0
global,land,0,0,0,0,0,0,0
global_relative_alt,do_jump,4,2,0,0,0,0,0
9 changes: 9 additions & 0 deletions tests/test_csv/test_normal_advanced_csv.csv
Original file line number Diff line number Diff line change
@@ -0,0 +1,9 @@
frame,command_type,param1,param2,param3,param4,param5,param6,param7
global_relative_alt,takeoff,0,0,0,0,0,0,50
global_relative_alt,loiter_timed,6,0,0,0,43.47323264522664,-80.5401164,50
global_relative_alt,loiter_unlimited,0,0,0,0,43.47,-80.55,50
global_relative_alt,waypoint,0,0.1,0,0,43.47352476,-80.54144668,10
global_relative_alt,waypoint_spline,0,0,0,0,43.47323264522664,-80.5401164,10
global,return_to_launch,0,0,0,0,0,0,0
global,land,0,0,0,0,0,0,0
global_relative_alt,do_jump,4,2,0,0,0,0,0
98 changes: 98 additions & 0 deletions tests/unit/test_advanced_csv_to_commands.py
Original file line number Diff line number Diff line change
@@ -0,0 +1,98 @@
"""
Testing the advanced_csv_to_commands module
"""

import pathlib

import dronekit

from modules import advanced_csv_to_commands
from modules import generate_command


def test_normal_file() -> None:
"""
A normal advanced CSV file
"""
normal_advanced_csv_path = pathlib.Path("tests", "test_csv", "test_normal_advanced_csv.csv")

expected_mission = [
generate_command.takeoff(50),
generate_command.loiter_timed(6.0, 43.47323264522664, -80.5401164, 50),
generate_command.loiter_unlimited(43.47, -80.55, 50),
generate_command.waypoint(0, 0.1, 43.47352476, -80.54144668, 10),
generate_command.waypoint_spline(0, 43.47323264522664, -80.5401164, 10),
generate_command.return_to_launch(),
generate_command.landing(),
generate_command.do_jump(4, 2),
]

success, mission = advanced_csv_to_commands.csv_to_commands_list(normal_advanced_csv_path)

# Test
assert success
assert isinstance(mission, list)
assert len(mission) == len(expected_mission)

for idx, command in enumerate(mission):
assert isinstance(command, dronekit.Command)
assert command.frame == expected_mission[idx].frame
assert command.command == expected_mission[idx].command
assert command.param1 == expected_mission[idx].param1
assert command.param2 == expected_mission[idx].param2
assert command.param3 == expected_mission[idx].param3
assert command.param4 == expected_mission[idx].param4
assert command.x == expected_mission[idx].x
assert command.y == expected_mission[idx].y
assert command.z == expected_mission[idx].z


def test_empty_csv() -> None:
"""
CSV file is empty, expected to fail
"""
empty_advanced_csv_path = pathlib.Path("tests", "test_csv", "test_empty_advanced_csv.csv")
success, mission = advanced_csv_to_commands.csv_to_commands_list(empty_advanced_csv_path)
assert not success
assert mission is None


def test_invalid_command_name() -> None:
"""
waypoint is misspelled as "wayypoint", expected to fail
"""
invalid_command_name_path = pathlib.Path("tests", "test_csv", "test_invalid_command_name.csv")
success, mission = advanced_csv_to_commands.csv_to_commands_list(invalid_command_name_path)
assert not success
assert mission is None


def test_invalid_frame_name() -> None:
"""
global is misspelled as "globbal", expected to fail
"""
invalid_frame_name_path = pathlib.Path("tests", "test_csv", "test_invalid_frame_name.csv")
success, mission = advanced_csv_to_commands.csv_to_commands_list(invalid_frame_name_path)
assert not success
assert mission is None


def test_file_path_does_not_exist() -> None:
"""
The file path does not exist, expected to fail
"""
invalid_path = pathlib.Path("tests", "test_csv", "path_DNE.csv")
success, mission = advanced_csv_to_commands.csv_to_commands_list(invalid_path)
assert not success
assert mission is None


def test_bad_line() -> None:
"""
A line does not have the correct number of parameters.
Fourth line (third command) is missing a 0 and therefore an invalid command
"""
invalid_path = pathlib.Path("tests", "test_csv", "test_incorrect_num_params_csv.csv")
success, mission = advanced_csv_to_commands.csv_to_commands_list(invalid_path)
assert not success
assert mission is None
Loading