mavros_examples.waypoint_mission_manager module
- class mavros_examples.waypoint_mission_manager.WaypointMissionManager(*args: Any, **kwargs: Any)
Bases:
NodeManager node.
- clear_waypoints() bool
Clear all waypoints from the flight controller.
- Returns:
True if successful, False otherwise
- create_sample_mission(home_lat: float = -35.363262, home_lon: float = 149.165237, home_alt: float = 2.0) List[mavros_msgs.msg.Waypoint]
Create a sample square mission with takeoff and landing.
- Parameters:
home_lat – Home latitude
home_lon – Home longitude
home_alt – Home altitude
- Returns:
List of waypoints
- create_waypoint(lat: float, lon: float, alt: float, frame: int = 0, command: int = 16, is_current: bool = False, autocontinue: bool = True, param1: float = 0.0, param2: float = 0.0, param3: float = 0.0, param4: float = 0.0) mavros_msgs.msg.Waypoint
Create a MAVLink waypoint.
- Parameters:
lat – Latitude in degrees
lon – Longitude in degrees
alt – Altitude in meters
frame – MAVLink frame (0=GLOBAL, 3=GLOBAL_RELATIVE_ALT, etc.)
command – MAVLink command (16=WAYPOINT, 22=TAKEOFF, 21=LAND, etc.)
is_current – Whether this is the current waypoint
autocontinue – Auto-continue to next waypoint
param1-4 – Command-specific parameters
- Returns:
Waypoint message
- static get_command_name(command: int) str
Convert MAVLink command number to name.
- static get_frame_name(frame: int) str
Convert MAVLink frame number to name.
- print_waypoint_info(waypoints: List[mavros_msgs.msg.Waypoint])
Print information about waypoints.
- pull_waypoints() List[mavros_msgs.msg.Waypoint] | None
Download waypoints from the flight controller.
- Returns:
List of waypoints or None if failed
- push_waypoints(waypoints: List[mavros_msgs.msg.Waypoint]) bool
Upload waypoints to the flight controller.
- Parameters:
waypoints – List of Waypoint messages
- Returns:
True if successful, False otherwise
- set_current_waypoint(wp_seq: int) bool
Set the current active waypoint.
- Parameters:
wp_seq – Waypoint sequence number to set as current
- Returns:
True if successful, False otherwise
- set_mode(mode: str = 'AUTO') bool
Set the flight mode.
- Parameters:
mode – Flight mode string (e.g., ‘AUTO’, ‘GUIDED’, ‘STABILIZE’, ‘LOITER’)
- Returns:
True if successful, False otherwise
- wait_for_services()
Wait for all MAVROS services to become available.
- waypoint_reached_callback(msg: mavros_msgs.msg.WaypointReached)
- waypoints_callback(msg: mavros_msgs.msg.WaypointList)
- mavros_examples.waypoint_mission_manager.main(args=None)