diff --git a/mavlink/modules/flight_controller.py b/mavlink/modules/flight_controller.py index ccae179..e1af0bc 100644 --- a/mavlink/modules/flight_controller.py +++ b/mavlink/modules/flight_controller.py @@ -176,6 +176,16 @@ def upload_land_command(self, latitude: float, longitude: float) -> bool: def is_drone_destination_final_waypoint(self) -> "tuple[bool, bool | None]": """ Returns if the drone's destination is the final waypoint in the mission. + + Returns + ------- + tuple[bool, bool | None] + The first boolean in the tuple represents if retrieving the mission + information is successful. + - If it is not successful, the second parameter will be None. + - If it is successful, the second parameter will be a boolean + indicating if the drone's destination is set to the final + waypoint in the mission. """ waypoint_count = self.drone.commands.count current_waypoint = self.drone.commands.next diff --git a/mavlink/test_mission_ended.py b/mavlink/test_mission_ended.py index fe2fa46..1daa04a 100644 --- a/mavlink/test_mission_ended.py +++ b/mavlink/test_mission_ended.py @@ -34,8 +34,8 @@ def upload_mission(controller: flight_controller.FlightController, ---------- controller: "flight_controller.FlightController" waypoints: "list[tuple[float, float, float]]" - The three values in the tuple represent latitude (degrees), - longitude (degrees), and altitude (metres) respectively. + The three values in the tuple represent latitude (decimal degrees), + longitude (decimal degrees), and altitude (metres) respectively. Returns -------