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

Added timeout to upload_commands and download_commands functions #48

Open
wants to merge 6 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
34 changes: 23 additions & 11 deletions mavlink/modules/flight_controller.py
Original file line number Diff line number Diff line change
Expand Up @@ -114,13 +114,14 @@ def get_home_location(

return True, location

def upload_commands(self, commands: "list[dronekit.Command]") -> bool:
def upload_commands(self, commands: "list[dronekit.Command]", timeout: float = 30.0) -> bool:
"""
Writes a mission to the drone from a list of commands (will overwrite any previous missions).

Parameters
----------
commands: List of commands.
timeout: Seconds (default of 30.0 seconds).

Returns
-------
Expand All @@ -132,7 +133,7 @@ def upload_commands(self, commands: "list[dronekit.Command]") -> bool:
try:
command_sequence = self.drone.commands
command_sequence.download()
command_sequence.wait_ready()
command_sequence.wait_ready(timeout)
command_sequence.clear()
for command in commands:
command_sequence.add(command)
Expand All @@ -148,7 +149,7 @@ def upload_commands(self, commands: "list[dronekit.Command]") -> bool:

return True

def upload_land_command(self, latitude: float, longitude: float) -> bool:
def upload_land_command(self, latitude: float, longitude: float, timeout: float) -> bool:
"""
Given a target latitude and longitude, overwrite the drone's current mission
with a corresponding land command.
Expand All @@ -157,6 +158,7 @@ def upload_land_command(self, latitude: float, longitude: float) -> bool:
----------
latitude: Decimal degrees.
longitude: Decimal degrees.
timeout: Seconds.

Returns
-------
Expand All @@ -180,7 +182,7 @@ def upload_land_command(self, latitude: float, longitude: float) -> bool:
0,
)

return self.upload_commands([landing_command])
return self.upload_commands([landing_command], timeout)

def is_drone_destination_final_waypoint(self) -> "tuple[bool, bool | None]":
"""
Expand Down Expand Up @@ -255,10 +257,14 @@ def get_flight_mode(self) -> "tuple[bool, drone_odometry.FlightMode | None]":
return True, drone_odometry.FlightMode.MOVING
return True, drone_odometry.FlightMode.MANUAL

def download_commands(self) -> "tuple[bool, list[dronekit.Command]]":
def download_commands(self, timeout: float = 30.0) -> "tuple[bool, list[dronekit.Command]]":
"""
Downloads the current list of commands from the drone.

Parameters
----------
timeout: Seconds (default of 30.0 seconds).

Returns
-------
tuple[bool, list[dronekit.Command]]
Expand All @@ -268,7 +274,7 @@ def download_commands(self) -> "tuple[bool, list[dronekit.Command]]":
try:
command_sequence = self.drone.commands
command_sequence.download()
command_sequence.wait_ready()
command_sequence.wait_ready(timeout)
commands = list(command_sequence)
return True, commands
except dronekit.TimeoutError:
Expand All @@ -278,17 +284,23 @@ def download_commands(self) -> "tuple[bool, list[dronekit.Command]]":
print("ERROR: Connection with drone reset. Unable to download commands.")
return False, []

def get_next_waypoint(self) -> "tuple[bool, drone_odometry.DronePosition | None]":
def get_next_waypoint(
self, timeout: float
) -> "tuple[bool, drone_odometry.DronePosition | None]":
"""
Gets the next waypoint.

Parameters
----------
timeout: Seconds.

Returns
-------
tuple[bool, drone_odometry.DronePosition | None]
A tuple where the first element is a boolean indicating success or failure,
and the second element is the next waypoint currently held by the drone.
"""
result, commands = self.download_commands()
result, commands = self.download_commands(timeout)
if not result:
return False, None

Expand All @@ -302,12 +314,12 @@ def get_next_waypoint(self) -> "tuple[bool, drone_odometry.DronePosition | None]
return False, None

def insert_waypoint(
self, index: int, latitude: float, longitude: float, altitude: float
self, index: int, latitude: float, longitude: float, altitude: float, timeout: float
) -> bool:
"""
Insert a waypoint into the current list of commands at a certain index and reupload the list to the drone.
"""
result, commands = self.download_commands()
result, commands = self.download_commands(timeout)
if not result:
return False

Expand All @@ -330,4 +342,4 @@ def insert_waypoint(

commands.insert(index, new_waypoint)

return self.upload_commands(commands)
return self.upload_commands(commands, timeout)
6 changes: 3 additions & 3 deletions mavlink/test_flight_controller.py
Original file line number Diff line number Diff line change
Expand Up @@ -48,15 +48,15 @@ def main() -> int:
time.sleep(DELAY_TIME)

# Download and print commands
success, commands = controller.download_commands()
success, commands = controller.download_commands(TIMEOUT)
if success:
print("Downloaded commands:")
for command in commands:
print(command)
else:
print("Failed to download commands.")

result, next_waypoint = controller.get_next_waypoint()
result, next_waypoint = controller.get_next_waypoint(TIMEOUT)
if result:
print("next waypoint lat: " + str(next_waypoint.latitude))
print("next waypoint lon: " + str(next_waypoint.longitude))
Expand All @@ -70,7 +70,7 @@ def main() -> int:
return -1

# Create and add land command
result = controller.upload_land_command(home.latitude, home.longitude)
result = controller.upload_land_command(home.latitude, home.longitude, TIMEOUT)
if not result:
print("Could not upload land command.")
return -1
Expand Down
Loading