Skip to main content

Documentation Index

Fetch the complete documentation index at: https://mintlify.com/Ardupilot/ardupilot/llms.txt

Use this file to discover all available pages before exploring further.

AC_WPNav is the waypoint navigation controller used by ArduCopter’s Auto, Guided, and related flight modes. It accepts destination waypoints — either as Location objects or NED position vectors — and continuously advances a target position along a smooth trajectory until the vehicle arrives. The library does not directly command motors; instead it feeds position, velocity, and acceleration targets into AC_PosControl, which in turn commands AC_AttitudeControl. Terrain following, object avoidance (via AC_WPNav_OA), and spline paths are all first-class features.

Relationship to AC_PosControl

AC_WPNav holds a reference to AC_PosControl and delegates all thrust calculation to it. The split of responsibility is:
  • AC_WPNav — trajectory generation: advance a target point along the route, enforce speed/acceleration/jerk limits, detect waypoint arrival.
  • AC_PosControl — control law: compare the target position/velocity/acceleration against the AHRS estimate and compute the roll/pitch angles and thrust vector that will track the target.
AC_WPNav calls _pos_control setters every loop to update the target state, then vehicle code reads back get_roll_rad(), get_pitch_rad(), and get_yaw_rad() (or get_thrust_vector()) from AC_WPNav’s wrapper accessors and passes them to AC_AttitudeControl.

Trajectory generation

Two trajectory types are available, selected per mission segment:

S-curve (default)

Jerk-limited kinematic profiles with separate horizontal and vertical S-curves. Three overlapping curve objects (_scurve_prev_leg, _scurve_this_leg, _scurve_next_leg) allow lookahead blending so the vehicle slows precisely at the waypoint radius without stopping unless required.

Spline

Hermite spline paths that pass smoothly through waypoints without stopping. The current and next spline segments (_spline_this_leg, _spline_next_leg) are computed from set_spline_destination_NED_m(). Used when MAV_CMD_NAV_SPLINE_WAYPOINT is in the mission.

Key methods

Initializes the waypoint and spline controller. Sets speed and acceleration limits, computes jerk and snap constraints from the attitude controller’s capabilities, and establishes the starting point for the first leg. Must be called before setting any destination.
void wp_and_spline_init_m(
    float speed_ms = 0.0f,
    Vector3p stopping_point_ned_m = Vector3p{});
Sets the waypoint destination as an NED position vector in meters from the EKF origin. If is_terrain_alt is true, the Z component is interpreted as altitude above terrain rather than above the origin. The controller reinitializes the current leg automatically if a previous navigation was in progress.
virtual bool set_wp_destination_NED_m(
    const Vector3p& destination_ned_m,
    bool is_terrain_alt = false,
    float arc_rad = 0.0);
A Location-based overload is also available:
bool set_wp_destination_loc(
    const Location& destination,
    float arc_rad = 0.0);
Advances the target position along the current trajectory segment and updates AC_PosControl with the new target state. Should be called at 100 Hz or higher. Returns false if a terrain data lookup fails mid-flight.
virtual bool update_wpnav();
Returns true once the vehicle has come within the waypoint acceptance radius (WPNAV_RADIUS) of the destination. The flag is set by advance_wp_target_along_track() and cleared when a new destination is set.
virtual bool reached_wp_destination() const { return _flags.reached_destination; }
Returns the current horizontal distance in meters between the vehicle and the active waypoint destination.
virtual float get_wp_distance_to_destination_m() const;
Returns the bearing from the vehicle’s current position to the destination waypoint, in radians clockwise from North.
virtual float get_wp_bearing_to_destination_rad() const;
Runtime speed overrides. These update the active trajectory limits so that a DO_CHANGE_SPEED mission command or a GCS speed override takes effect immediately on the current leg.
void set_speed_NE_ms(float speed_ms);
void set_speed_up_ms(float speed_up_ms);
void set_speed_down_ms(float speed_down_ms);
Pauses or resumes progression along the active waypoint track. While paused, the target position stops advancing and the vehicle decelerates to hover at the paused location. Used by object avoidance when an obstacle is detected.
void set_pause()  { _paused = true; }
void set_resume() { _paused = false; }

Key parameters

Speed limits

ParameterDescriptionDefault
WPNAV_SPEEDDefault horizontal speed (cm/s)500
WPNAV_SPEED_UPDefault climb rate (cm/s)250
WPNAV_SPEED_DNDefault descent rate (cm/s)150

Geometric limits

ParameterDescriptionDefault
WPNAV_RADIUSWaypoint acceptance radius (cm)200
WPNAV_ACCELHorizontal acceleration (cm/s²)250
WPNAV_ACCEL_CCorner acceleration for turns (cm/s²)0 (2× ACCEL)
WPNAV_ACCEL_ZVertical acceleration (cm/s²)100
WPNAV_JERKMaximum jerk for S-curve shaping (m/s³)1.0

Terrain following

ParameterDescription
WPNAV_RFND_USEEnable rangefinder for terrain following (1 = enabled)
WPNAV_TER_MARGINAltitude margin before aborting terrain following (m)

Terrain following integration

Terrain altitude commands set _is_terrain_alt = true. Each call to advance_wp_target_along_track() then queries either the rangefinder (via set_rangefinder_terrain_U_m()) or the AP_Terrain database to find the current terrain height and adjusts the vertical target accordingly. If neither source is available, update_wpnav() returns false and the calling mode should abort or revert to absolute altitude.
// Provide rangefinder data to the WPNav controller each loop:
wpnav.set_rangefinder_terrain_U_m(
    rangefinder_enabled,    // bool: rangefinder is active
    rangefinder_healthy,    // bool: reading is valid
    terrain_altitude_m);    // float: terrain height above EKF origin (m)
Two terrain sources are reported by get_terrain_source():
  • TERRAIN_FROM_RANGEFINDER — real-time, short-range, no map required.
  • TERRAIN_FROM_TERRAINDATABASE — uses the AP_Terrain SD card database for long-range terrain awareness.

Integration with AP_Mission

AP_Mission is responsible for decoding MAV_CMD_NAV_WAYPOINT and similar commands and calling into AC_WPNav. The typical call sequence from ArduCopter/mode_auto.cpp is:
// On a new NAV_WAYPOINT command:
Location dest = cmd.content.location;
if (!copter.wp_nav->set_wp_destination_loc(dest)) {
    // terrain data unavailable — abort
    return false;
}

// Each loop at 100 Hz:
copter.wp_nav->update_wpnav();

// Check arrival:
if (copter.wp_nav->reached_wp_destination()) {
    mission.advance_current_nav_cmd();
}

Relationship to AC_Loiter

AC_Loiter is a separate controller (also backed by AC_PosControl) that holds position when no waypoint destination is active. It handles pilot stick inputs for position offset and braking. AC_WPNav and AC_Loiter share the same AC_PosControl instance but are never active simultaneously.

Source location

libraries/AC_WPNav/AC_WPNav.h — waypoint navigation controller
libraries/AC_AttitudeControl/AC_PosControl.h — position controller used internally

Build docs developers (and LLMs) love