Skip to content
Merged
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
67 changes: 67 additions & 0 deletions radio/app/controllers/missionController.py
Original file line number Diff line number Diff line change
Expand Up @@ -61,6 +61,34 @@ def _convertCoordinate(self, coordinate) -> Number:
f"Invalid coordinate type {type(coordinate)}. Must be int or float."
)

def _getMissionName(self, mission_type: int) -> str:
"""
Get the name of the mission type.

Args:
mission_type (int): The type of mission to get the name for.
"""
if mission_type == TYPE_MISSION:
return "mission"
elif mission_type == TYPE_FENCE:
return "fence"
elif mission_type == TYPE_RALLY:
return "rally"
else:
raise ValueError(f"Invalid mission type {mission_type}")

def _getCommandName(self, command: int) -> str:
"""
Get the name of the command type.

Args:
command (int): The command to get the name for.
"""
try:
return mavutil.mavlink.enums["MAV_CMD"][command].name
except KeyError:
return f"Unknown command {command}"

def getCurrentMission(self, mission_type: int) -> Response:
"""
Get the current mission of a specific type from the drone.
Expand Down Expand Up @@ -648,6 +676,45 @@ def importMissionFromFile(self, mission_type: int, file_path: str) -> Response:
}

for wp in loader.wpoints:
# Check if mission type correlates to correct command
if (
(
mission_type == TYPE_RALLY
and wp.command != mavutil.mavlink.MAV_CMD_NAV_RALLY_POINT
)
or (
mission_type == TYPE_FENCE
and wp.command
not in [
mavutil.mavlink.MAV_CMD_NAV_FENCE_RETURN_POINT,
mavutil.mavlink.MAV_CMD_NAV_FENCE_POLYGON_VERTEX_INCLUSION,
mavutil.mavlink.MAV_CMD_NAV_FENCE_POLYGON_VERTEX_EXCLUSION,
mavutil.mavlink.MAV_CMD_NAV_FENCE_CIRCLE_INCLUSION,
mavutil.mavlink.MAV_CMD_NAV_FENCE_CIRCLE_EXCLUSION,
]
)
or (
mission_type == TYPE_MISSION
and wp.command
in [
mavutil.mavlink.MAV_CMD_NAV_RALLY_POINT,
mavutil.mavlink.MAV_CMD_NAV_FENCE_RETURN_POINT,
mavutil.mavlink.MAV_CMD_NAV_FENCE_POLYGON_VERTEX_INCLUSION,
mavutil.mavlink.MAV_CMD_NAV_FENCE_POLYGON_VERTEX_EXCLUSION,
mavutil.mavlink.MAV_CMD_NAV_FENCE_CIRCLE_INCLUSION,
mavutil.mavlink.MAV_CMD_NAV_FENCE_CIRCLE_EXCLUSION,
]
)
):
self.drone.logger.error(
f"Waypoint command {self._getCommandName(wp.command)} does not match mission type {self._getMissionName(mission_type)}"
)
return {
"success": False,
"message": f"Could not load the waypoint file. Waypoint command {self._getCommandName(wp.command)} does not match mission type {self._getMissionName(mission_type)}",
}

# Convert coordinates to the correct format
if hasattr(wp, "x") and hasattr(wp, "y"):
wp.x = self._convertCoordinate(wp.x)
wp.y = self._convertCoordinate(wp.y)
Expand Down
Loading