Summary
The NAV_FENCE family of commands defines the geometry of ArduPilot's Geofence system directly within the mission list. This allows the vehicle to carry its own "Containment Logic" in non-volatile memory, ensuring that even if the ground station link is lost, the drone remains bound by the pre-approved spatial boundaries.
Status
Supported (All Vehicles)
Directionality
- RX (Receive): The vehicle receives these commands during a mission upload (specifically when using the MAVLink Fence Protocol).
Commands and Storage
- 5000: Return Point: The "Safe Zone" where the drone will fly if a fence breach occurs. (Only 1 allowed).
- 5001: Polygon Inclusion: The drone must stay inside the shape defined by these vertices.
- 5002: Polygon Exclusion: The drone must not enter the shape.
- 5003: Circle Inclusion: A circular keep-in zone.
- 5004: Circle Exclusion: A circular keep-out zone.
- Mechanism: Stored as specialized location items in the
AP_Missionbuffer.
Execution (Engineer's View)
Containment Mathematics
The AC_Fence library implements Point-in-Polygon (PIP) algorithms to monitor the vehicle's position.
- Ray Casting: For polygons (5001, 5002), the autopilot mathematically casts a ray from the vehicle's position. If the number of intersections with the polygon edges is odd, the vehicle is inside.
- Distance-Squared: For circles (5003, 5004), the autopilot calculates the 2D distance:
$$ D^2 = (Lat_v - Lat_c)^2 + (Lon_v - Lon_c)^2 $$
If $D > \text{Radius}$ for an Inclusion circle, a breach is triggered. - The Floor and Ceiling: While not defined by these commands, the Geofence system also monitors altitude via global parameters like
FENCE_ALT_MAX.
Data Fields (MAVLink)
param1(Count/Radius): Vertex count for polygons, or Radius (m) for circles.x(Latitude): Vertex coordinate.y(Longitude): Vertex coordinate.z(Altitude): Reserved.
Theory: The "Safe Pipe"
NAV_FENCE commands enable Mission-Geometric Coupling.
- The Problem: A drone is programmed to fly a path. But what if a sensor fails and the drone drifts?
- The Solution: By wrapping the
NAV_WAYPOINTitems with aNAV_FENCE_POLYGON_VERTEX_INCLUSIONsequence, the operator defines a high-integrity "Pipe." The drone is physically unable to exit this pipe while the mission is active.
Practical Use Cases
- Sensitive Airspace Protection:
- Scenario: A drone is mapping near an airport runway.
- Action: Use
NAV_FENCE_POLYGON_VERTEX_EXCLUSIONto draw a box around the runway. The drone will treat this as a "Solid Object" and trigger a failsafe if it approaches the boundary.
- Indoor/Hangar Safety:
- Scenario: Flying inside a warehouse.
- Action:
NAV_FENCE_CIRCLE_INCLUSIONcentered on the hangar to ensure the drone never crashes into the walls if it loses its local positioning fix.
Key Parameters
FENCE_TYPE: Bitmask selection of which fences are active (Circle, Polygon, etc.).FENCE_MARGIN: The distance (meters) before the boundary where the drone will begin to brake.
Key Codebase Locations
- libraries/AC_Fence/AC_Fence.cpp: Ray-casting and distance math.
- libraries/GCS_MAVLink/MissionItemProtocol_Fence.cpp: Fence packet parsing.
NAV_WAYPOINT
Summary
The NAV_WAYPOINT command is the fundamental building block of autonomous missions. It defines a 3D coordinate (Latitude, Longitude, Altitude) that the vehicle must navigate to. Depending on the vehicle type and parameters, the vehicle may either stop at the waypoint or transition smoothly through it towards the next destination.
Status
Supported (All Vehicles)
Directionality
- RX (Receive): The vehicle receives this command as part of a mission upload (
MISSION_ITEMorMISSION_ITEM_INT).
Mission Storage (AP_Mission)
When a NAV_WAYPOINT is stored in ArduPilot's EEPROM, the parameters are packed for efficiency:
- Copter:
param1(Delay) is stored in thep1field. - Plane:
param2(Acceptance Radius) andparam3(Pass-by Distance) are packed into thep1field.
Execution (Engineer's View)
ArduCopter Implementation
In Copter, the command is triggered in ModeAuto::do_nav_wp (mode_auto.cpp).
- Path Generation: The location is passed to the
AC_WPNavlibrary. ArduCopter uses S-Curve trajectory generation to ensure smooth acceleration and deceleration. - Cornering Logic:
- If Delay (p1) is 0, the flight controller looks ahead to the next waypoint. It plans a path that rounds the corner, maintaining velocity.
- If Delay (p1) is greater than 0, the vehicle is forced to stop exactly at the coordinate and wait for the specified time before proceeding.
- Yaw Control: The vehicle will typically face the next waypoint unless a
CONDITION_YAWorROIcommand has overridden the heading logic.
ArduPlane Implementation
In Plane, the logic resides in commands_logic.cpp.
- L1 Controller: Plane uses an L1 guidance algorithm which creates a lateral acceleration command to guide the aircraft onto the track between waypoints.
- Acceptance Radius (p2): Defines a cylinder around the waypoint. As soon as the aircraft enters this cylinder, the waypoint is considered "complete." If set to 0, the global
WP_RADIUSparameter is used. - Pass-By (p3): Allows the plane to start the turn early. If the aircraft comes within
p3meters of the waypoint, it transitions to the next leg.
Data Fields (MAVLink)
param1(Delay): Time to loiter at the waypoint in seconds (Copter only).param2(Acceptance Radius): Distance in meters at which the waypoint is considered reached (Plane only).param3(Pass-by Distance): For planes, the distance at which the aircraft should begin its turn towards the next waypoint.param4(Yaw): Desired yaw angle (Copter only).x(Latitude): Target latitude.y(Longitude): Target longitude.z(Altitude): Target altitude.
Practical Use Cases
- Survey Grid:
- Scenario: Mapping a field with a camera.
- Action: A series of
NAV_WAYPOINTcommands are used to define the "lawnmower" pattern.Delayis set to 0 for continuous flight.
- Inspection Stop:
- Scenario: Inspecting a power line insulator.
- Action: The drone flies to a
NAV_WAYPOINTpositioned near the insulator with aDelayof 5 seconds, allowing the camera to capture high-quality images while stationary.
Key Codebase Locations
- ArduCopter/mode_auto.cpp:1547:
do_nav_wpimplementation for Copter. - ArduPlane/commands_logic.cpp: Plane mission command logic.
- libraries/AP_Mission/AP_Mission.cpp:1065: Mission storage packing for waypoints.
NAV_LOITER_UNLIM
Summary
The NAV_LOITER_UNLIM command instructs the vehicle to fly to a specified location and loiter (circle or hover) there indefinitely. This is a "blocking" command; the mission will not proceed to the next waypoint unless the pilot manually skips the item or changes the flight mode.
Status
Supported (All Vehicles)
Directionality
- RX (Receive): The vehicle receives this command as part of a mission upload.
Mission Storage (AP_Mission)
- Packet Param 3 (Radius/Direction):
- Stored in the internal
p1field. - Radius: The absolute value is stored as a 16-bit integer (meters).
- Direction: The sign indicates direction (
-= Counter-Clockwise,+= Clockwise).
- Stored in the internal
- Packet Param 4 (Yaw/XTrack):
- For Copter,
param4represents the desired yaw (0 to 360 deg). - For Plane,
param4> 0 enables "Tangent Exit" crosstracking.
- For Copter,
Execution (Engineer's View)
ArduCopter Implementation
In Copter, the command triggers ModeAuto::do_loiter_unlimited (mode_auto.cpp).
- Target Acquisition: The location is passed to the
AC_WPNavlibrary. - Behavior:
- The copter flies to the target Lat/Lon/Alt.
- It enters
WP_NAVloiter mode, holding position against wind using the GPS/INS solution. - Heading: The vehicle will face the next waypoint (if one exists) or hold the current heading, unless overridden by a
CONDITION_YAWcommand.
ArduPlane Implementation
In Plane, the logic resides in commands_logic.cpp and verify_loiter_unlim.
- Loiter Radius: The plane uses the
param3radius. Ifparam3is 0, it defaults to the globalWP_LOITER_RADparameter. - Orbit Direction:
- Positive Radius: Clockwise.
- Negative Radius: Counter-Clockwise.
- L1 Controller: The plane maintains the orbit using L1 guidance, adjusting bank angle to compensate for wind drift.
Data Fields (MAVLink)
param1: Empty.param2: Empty.param3(Radius): Radius in meters. Positive = Clockwise, Negative = Counter-Clockwise. If 0, uses default.param4(Yaw/XTrack): Desired Yaw (deg) [Copter] or XTrack location [Plane].x(Latitude): Target latitude.y(Longitude): Target longitude.z(Altitude): Target altitude.
Theory: The L1 Loiter Logic (Plane)
For fixed-wing aircraft, loitering is not static; it is a dynamic energy management state.
- Wind Compensation: To maintain a perfect circle over the ground, the plane must vary its bank angle and ground speed.
- Downwind: Ground speed increases; bank angle must increase to increase centripetal force ($F_c = \frac{mv^2}{r}$).
- Upwind: Ground speed decreases; bank angle must decrease.
$$ ext{Bank Angle} \propto \arctan\left(\frac{v_{ground}^2}{g \cdot r}\right) $$
Practical Use Cases
- Observation Point:
- Scenario: A surveillance drone needs to watch a specific intersection for an unknown duration.
- Action: The operator inserts a
NAV_LOITER_UNLIMcommand. The drone holds station until the operator commands it to "Resume Mission" or "Return to Launch".
- Holding Pattern:
- Scenario: Air traffic control (ATC) requires a delay before landing.
- Action: The aircraft enters a holding pattern at a safe altitude.
Key Codebase Locations
- ArduCopter/mode_auto.cpp:
do_loiter_unlimitedimplementation. - libraries/AP_Mission/AP_Mission.cpp:1085: Parameter packing for storage.
NAV_LOITER_TURNS
Summary
The NAV_LOITER_TURNS command instructs the vehicle to fly to a specified location and orbit it for a specific number of full 360-degree rotations. This is commonly used to ensure a camera has multiple opportunities to capture a target or to allow a vehicle to shed altitude/airspeed before a landing approach.
Status
Supported (All Vehicles)
Directionality
- RX (Receive): The vehicle receives this command as part of a mission upload.
Mission Storage (AP_Mission)
ArduPilot uses complex bit-packing to store the number of turns and the radius within the limited EEPROM space.
- Turns (Param 1):
- Stored in the low byte of
p1. - Supports fractional turns (e.g., 1.5 turns) by multiplying by 256 and setting a "Fractional" bit in storage.
- Stored in the low byte of
- Radius (Param 3):
- Stored in the high byte of
p1. - If the radius is > 255m, it is stored divided by 10, and a "Large Radius" bit is set.
- Stored in the high byte of
Execution (Engineer's View)
ArduCopter Implementation
In Copter, this command utilizes the AC_CircleNav library via ModeAuto::do_circle (mode_auto.cpp).
- Transition: The copter first flies to the edge of the circle (
CIRCLE_MOVE_TO_EDGE). - Tracking: Once on the perimeter, it begins counting the cumulative angle traveled.
- Completion: The command completes when:
$$ \frac{|\text{Total Angle Traveled}|}{2\pi} \ge \text{Target Turns} $$ - Yaw: The vehicle can be configured to face the center, face the direction of travel, or hold a fixed heading via the
CIRCLE_YAW_BEHAVEparameter.
ArduPlane Implementation
In Plane, the logic resides in Plane::verify_loiter_turns.
- L1 Orbit: The plane enters an L1 loiter at the specified radius.
- Cumulative Counting: The autopilot integrates the change in bearing to the center to track rotations.
- Exit Strategy: Unlike Copter, Plane implements a Secondary Heading Goal. Once the turns are completed, the plane does not immediately exit. It continues orbiting until it is pointing toward the next waypoint, ensuring a smooth tangential exit.
Data Fields (MAVLink)
param1(Turns): Number of full orbits to complete.param2: Empty.param3(Radius): Orbit radius in meters. Positive = Clockwise, Negative = Counter-Clockwise.param4(XTrack):- 0: Cross-track from the center of the loiter.
- 1: Cross-track from the tangent exit location (Plane only).
x(Latitude): Center of the orbit.y(Longitude): Center of the orbit.z(Altitude): Target altitude.
Theory: Angular Momentum vs. Ground Track
In the presence of wind, a constant airspeed orbit results in a "drifted" ground track. ArduPilot's L1 controller mathematically solves for the bank angle required to maintain a perfect circle over the ground.
- Wind Speed ($V_w$): Affects the ground speed ($V_g$).
- Maximum Bank Angle: Constrained by
ROLL_LIMIT_DEG. If the wind is too high, the plane may be unable to maintain the radius and will "blow out" of the circle.
Practical Use Cases
- Aerial Cinematography:
- Scenario: A photographer wants a 360-degree reveal of a mountain peak.
- Action: Use
NAV_LOITER_TURNSwithTurns = 1andCIRCLE_YAW_BEHAVE = 1(Face Center). The drone will orbit the peak while the camera stays locked on the target.
- Communications Relay:
- Scenario: A plane acts as a data link between a ground station and a distant rover.
- Action: Loiter for 50 turns over the rover's location to provide persistent coverage.
Key Parameters
CIRCLE_RADIUS: Default radius if mission radius is 0.CIRCLE_RATE: Maximum angular speed (deg/s) for the orbit.WP_LOITER_RAD: (Plane) Default loiter radius.
Key Codebase Locations
- ArduCopter/mode_auto.cpp:2256:
verify_circleimplementation. - ArduPlane/commands_logic.cpp:740:
verify_loiter_turnsimplementation.
NAV_LOITER_TIME
Summary
The NAV_LOITER_TIME command instructs the vehicle to fly to a location and loiter (hover or circle) for a specific duration in seconds. The timer begins only after the vehicle has reached the target coordinate.
Status
Supported (All Vehicles)
Directionality
- RX (Receive): The vehicle receives this command as part of a mission upload.
Mission Storage (AP_Mission)
- Time (Param 1): Stored in the internal
p1field as a 16-bit integer (seconds). - Significance: Since it uses all 16 bits for time, there is no room in the packed mission structure to store a custom radius for this specific command. It will always use the vehicle's default loiter radius.
Execution (Engineer's View)
ArduCopter Implementation
In Copter, the command triggers ModeAuto::do_loiter_time (mode_auto.cpp).
- Waypoint Entry: The copter flies to the target Lat/Lon/Alt using the standard S-Curve path.
- Timer Start: The
loiter_timevariable is initialized to 0. Oncereached_wp_destination()returns true, the current system time is recorded. - Completion: The command completes when:
$$ \text{millis}() - \text{startTime} \ge \text{Param1} \cdot 1000 $$
ArduPlane Implementation
In Plane, the logic resides in Plane::verify_loiter_time.
- Target Radius: Always uses the global
WP_LOITER_RADparameter. - Timer Logic: Similar to Copter, the timer starts only when
reached_loiter_target()is true. - Exit Heading: Once the time expires, Plane transitions to a secondary goal: verify_loiter_heading. It will continue orbiting until it points toward the next mission item, ensuring it exits the circle on a tangent.
Data Fields (MAVLink)
param1(Time): Duration to loiter in seconds.param2: Empty.param3: (Ignored by ArduPilot storage).param4(Yaw): Desired Yaw angle (deg).x(Latitude): Target location.y(Longitude): Target location.z(Altitude): Target altitude.
Theory: Time vs. Turns
While NAV_LOITER_TURNS is distance-dependent, NAV_LOITER_TIME is purely temporal.
- Wind Impact: In a high-wind scenario, a Plane might complete fewer turns in 60 seconds than in a no-wind scenario because it spends more time fighting the headwind.
- Consistency: For a Copter (multirotor),
LOITER_TIMEis the preferred method for creating pauses in a mission (e.g., waiting for a camera buffer to clear).
Practical Use Cases
- Timed Surveillance:
- Scenario: A security drone must orbit a gate for exactly 5 minutes every hour.
- Action: Use
NAV_LOITER_TIMEwithTime = 300.
- Sensor Warm-up:
- Scenario: A specialized gas sensor requires 30 seconds of stable airflow to calibrate.
- Action: Insert a
NAV_LOITER_TIMEat the start of the survey grid to allow the sensor to stabilize.
Key Parameters
WP_LOITER_RAD: (Plane) Controls the circle size.LOITER_REPOSITION: (Copter) Allows the pilot to "nudge" the loiter position with stick inputs without breaking the mission.
Key Codebase Locations
- ArduCopter/mode_auto.cpp:1738:
do_loiter_timeimplementation. - ArduPlane/commands_logic.cpp:710:
verify_loiter_timeimplementation.
NAV_RETURN_TO_LAUNCH
Summary
The NAV_RETURN_TO_LAUNCH (RTL) command instructs the vehicle to return to the home location or a designated rally point. This command is the primary safety mechanism for terminating a mission and returning the aircraft to the operator.
Status
Supported (All Vehicles)
Directionality
- RX (Receive): The vehicle receives this command as part of a mission upload or as a direct command (Failsafe trigger).
Mission Storage (AP_Mission)
- Packing: This command contains no additional parameters (
param1throughparam7are unused in missions). It simply serves as a state-change marker to trigger the vehicle's RTL mode.
Execution (Engineer's View)
ArduCopter Implementation
In Copter, the command triggers ModeAuto::do_RTL() (mode_auto.cpp).
- State Transition: The vehicle switches from
AUTOmode toRTLmode. - Safety Logic:
- Climb: The vehicle first climbs to the
RTL_ALT(or stays at current altitude if already higher, depending onRTL_CLIMB_MIN). - Return: It flies in a straight line towards Home.
- Descent: Once over home, it hovers for the duration of
RTL_LOIT_TIMEbefore initiating the final land.
- Climb: The vehicle first climbs to the
ArduPlane Implementation
In Plane, the logic resides in Plane::verify_RTL (commands_logic.cpp).
- Path Planning: Plane identifies the "best" return location, which could be the Home point or the nearest Rally Point.
- Altitude Management: The aircraft targets the
RTL_ALTITUDE(Plane specific). - Orbit: Upon arrival, the plane enters a loiter (circle) at the return point. Unlike Copter, a standard Plane RTL does not automatically land unless the mission specifically contains a landing sequence or a landing failsafe is triggered.
Data Fields (MAVLink)
param1toparam7: Reserved / Unused.
Theory: The "Cone of Safety"
A critical concept in RTL logic is the Return Cone.
- Problem: If a drone is very far away, returning at a low altitude might hit terrain. If it's very close, climbing to a high "Return Altitude" is a waste of energy.
- Solution: Advanced ArduPilot configurations use a "Safe Return Path" or Rally Points to ensure the vehicle always has a clear line of sight to a safe recovery zone.
Practical Use Cases
- Mission Completion:
- Scenario: A mapping mission has finished its last photo transect.
- Action: The mission list ends with
NAV_RETURN_TO_LAUNCHto bring the drone back to the takeoff area for recovery.
- Radio Failsafe:
- Scenario: The control link between the GCS and the drone is severed.
- Action: The internal failsafe logic injects a
NAV_RETURN_TO_LAUNCHcommand (equivalent) to recover the asset automatically.
Key Parameters
RTL_ALT: (Copter) Altitude to return at.RTL_ALTITUDE: (Plane) Altitude to return at.RTL_RADIUS: (Plane) Radius of the loiter circle over home.
Key Codebase Locations
- ArduCopter/mode_auto.cpp:2184:
verify_RTLimplementation. - ArduPlane/commands_logic.cpp:795:
verify_RTLimplementation.
NAV_LAND
Summary
The NAV_LAND command initiates the final descent and landing sequence. This command transitions the vehicle from flight to a grounded state, typically concluding with the motors disarming once the autopilot detects a successful touchdown.
Status
Supported (All Vehicles)
Directionality
- RX (Receive): The vehicle receives this command as part of a mission upload or as a direct command (Guided Mode).
Mission Storage (AP_Mission)
- Packet Param 1 (Abort Alt):
- Plane: Stored in the internal
p1field as a 16-bit integer (meters). This defines the altitude to climb to if the landing is aborted.
- Plane: Stored in the internal
- Packet Param 4 (Yaw):
- Plane: Stored in the
loiter_ccwfield ifparam4is negative (used for deepstall direction).
- Plane: Stored in the
Execution (Engineer's View)
ArduCopter Implementation
In Copter, the command triggers ModeAuto::do_land (mode_auto.cpp).
- Vertical Descent: The copter descends at the speed specified by
LAND_SPEED. - Touchdown Detection: The flight controller monitors the throttle and vertical velocity. If the throttle is at minimum and the altitude is not changing for a specific duration, it sets the "Landed" flag.
- Disarm: Once "Landed" is confirmed, the motors are automatically disarmed.
- Repositioning: If
LAND_REPOSITIONis enabled, the pilot can "nudge" the copter horizontally during the descent to avoid obstacles.
ArduPlane Implementation
In Plane, the logic resides in the AP_Landing library and Plane::do_land.
- Flare Logic: The plane follows a glideslope until it reaches the
LAND_FLARE_ALT. At this point, it raises the nose and cuts the throttle to "flare" for a smooth touchdown. - Abort Support: If the pilot triggers an abort or the vehicle enters a go-around state, it climbs to the "Abort Altitude" specified in the command's
param1. - Deepstall (Advanced): For airframes without wheels, Plane supports "Deepstall" landing, where the aircraft intentionally stalls its wing at high altitude to fall vertically onto a soft target (like a net or tall grass).
Data Fields (MAVLink)
param1(Abort Alt): Altitude to climb to on abort (Plane only).param2: Empty.param3: Empty.param4(Yaw): Desired yaw heading (Copter only).x(Latitude): Target landing point.y(Longitude): Target landing point.z(Altitude): Target altitude (typically 0).
Theory: The Ground Effect
As a multicopter nears the ground (within ~0.5m), it enters Ground Effect. The downwash from the rotors creates a high-pressure cushion that increases lift efficiency.
- The Hazard: If the autopilot is not tuned correctly, this extra lift can cause the vehicle to "bounce" off the cushion, making it difficult to detect a true touchdown.
- The Code: ArduPilot's landing detector uses a robust statistical filter to distinguish between ground effect bounces and a firm touchdown.
Practical Use Cases
- Standard Mission End:
- Scenario: A mapping mission completes its grid and returns to the takeoff point.
- Action: The last item is
NAV_LANDat the Home coordinates.
- Emergency Forced Landing:
- Scenario: The battery reaches a critical level during a mission.
- Action: The GCS or onboard script sends a
MAV_CMD_NAV_LANDat the vehicle's current location to terminate the flight safely.
Key Parameters
LAND_SPEED: Descent rate in cm/s during final landing.LAND_ALT_LOW: Altitude (cm) below which the land speed is reduced to the "slow" rate.LAND_FLARE_ALT: (Plane) Altitude to begin the flare.
Key Codebase Locations
- ArduCopter/mode_auto.cpp:1651:
do_landimplementation. - ArduPlane/commands_logic.cpp:402:
do_landimplementation.
NAV_TAKEOFF
Summary
The NAV_TAKEOFF command instructs the vehicle to lift off from the ground and climb to a specified altitude. This is typically the first command in an autonomous mission.
Status
Supported (All Vehicles)
Directionality
- RX (Receive): The vehicle receives this command as part of a mission upload or as a direct command (Guided Mode).
Mission Storage (AP_Mission)
- Packet Param 1 (Pitch/Ignored):
- Plane: Minimum pitch angle during takeoff (degrees).
- Copter: Ignored (usually 0).
- Packet Param 7 (Altitude):
- Target altitude in meters.
- Note: The frame of reference depends on the mission command frame (Relative, Absolute, or Terrain).
Execution (Engineer's View)
ArduCopter Implementation
In Copter, the command triggers ModeAuto::do_takeoff, which utilizes the Mode::_TakeOff class logic (takeoff.cpp).
- State Machine:
- The copter verifies it is armed and on the ground.
- It spools up motors to the
THROTTLE_UNLIMITEDstate.
- Climb Logic:
- The vertical position controller is fed a target altitude curve.
- Departure: If the copter is still on the ground, it slews the throttle until it detects a climb (acceleration > threshold) or throttle saturation.
- No Navigation Zone: If
WP_NAVALT_MINis set, the copter climbs straight up without horizontal navigation until it clears the "danger zone" (e.g., fence posts, people).
- Completion: Takeoff is considered complete when the target altitude is reached (within a tolerance).
ArduPlane Implementation
In Plane, the logic resides in Plane::do_takeoff (commands_logic.cpp).
- Pitch Target: The aircraft aims for the pitch angle specified in
param1. If 0, it defaults to a safe minimum (typically 10-15 degrees depending on tuning). - Heading Lock: The plane locks its heading to the ground course projected towards the next waypoint. It uses the rudder (and potentially differential thrust) to fight crosswinds while on the ground.
- Throttle Management: Throttle is clamped to maximum until the
TKOFF_THR_MIN_ACC(acceleration) orTKOFF_THR_MIN_SPD(airspeed) thresholds are met, preventing premature motor spindown.
Data Fields (MAVLink)
param1(Pitch): Minimum pitch angle in degrees (Plane only).param2: Empty.param3: Empty.param4(Yaw): Desired Yaw angle (deg). NaN to use current heading.x(Latitude): Target latitude (optional, used for initial heading alignment).y(Longitude): Target longitude (optional).z(Altitude): Target altitude in meters.
Theory: The "No-Nav" Zone
A critical concept in autonomous takeoff is the "No-Nav" Zone (controlled by WP_NAVALT_MIN).
- Problem: GPS positions drift. If a drone tries to navigate horizontally while still touching the ground, the landing gear might snag on grass or uneven terrain, causing a tip-over (Dynamic Rollover).
- Solution: The autopilot suppresses all horizontal position corrections (Roll/Pitch for Copter) until the vehicle has climbed to a safe altitude (e.g., 2 meters). It effectively shoots straight up like a rocket before engaging the navigation controller.
Practical Use Cases
- Hand Launch (Plane):
- Scenario: Launching a fixed-wing surveyor without a runway.
- Action: The pilot shakes the plane to arm it (Shake-to-Wake). The
NAV_TAKEOFFcommand manages the throttle delay and initial climb out, ensuring the prop doesn't spin up until the plane is thrown.
- Confined Area (Copter):
- Scenario: Taking off from a deep urban canyon or forest clearing.
- Action:
WP_NAVALT_MINis set to 15m. TheNAV_TAKEOFFcommand ensures the drone rises vertically above the treeline before attempting to fly to the first waypoint.
Key Codebase Locations
- ArduCopter/takeoff.cpp: Copter takeoff state machine.
- ArduPlane/commands_logic.cpp:372: Plane takeoff logic.
- libraries/AP_Mission/AP_Mission.cpp: Command unpacking.
NAV_LOITER_TO_ALT
Summary
The NAV_LOITER_TO_ALT command instructions the vehicle to fly to a location and loiter until a target altitude is reached. This is an essential "climb/descend" command for missions where altitude changes must be handled safely before continuing to the next waypoint.
Status
Supported (All Vehicles)
Directionality
- RX (Receive): The vehicle receives this command as part of a mission upload.
Mission Storage (AP_Mission)
- Radius (Param 2): Stored in the internal
p1field as a 16-bit integer (meters). - Significance: This command does support a custom radius in EEPROM storage, unlike
NAV_LOITER_TIME.
Execution (Engineer's View)
ArduCopter Implementation
In Copter, the command triggers ModeAuto::do_loiter_to_alt (mode_auto.cpp).
- Vertical Convergence: The copter holds the XY position while the vertical controller (Z) targets the altitude specified in
param7(packet'szfield). - Completion: The command completes only when:
reached_destination_xyis true (vehicle is over the coordinate).reached_altis true (vertical error is within tolerance).
ArduPlane Implementation
In Plane, the logic resides in Plane::verify_loiter_to_alt.
- Stuck Detection: ArduPilot includes a safety feature for planes. If the plane has been loitering but is unable to achieve the target altitude (e.g., due to low power or extreme downdrafts), it will eventually time out and report "Loiter to alt was stuck" to the GCS, allowing the mission to continue rather than circling until the battery dies.
- Exit Strategy: Once altitude is reached, the plane continues loitering until its heading aligns with the next waypoint (Tangent Exit).
Data Fields (MAVLink)
param1(Heading Required): If 1, the aircraft will not leave the loiter until heading toward the next waypoint (Plane only).param2(Radius): Orbit radius in meters.param3: Empty.param4(XTrack): Exit tangent control (Plane).x(Latitude): Target location.y(Longitude): Target location.z(Altitude): Target altitude.
Theory: Spiral Climbs and Energy Management
For fixed-wing aircraft, LOITER_TO_ALT is safer than a direct waypoint climb.
- Stall Prevention: By climbing in a circle, the aircraft maintains a consistent airspeed and bank angle. A direct climb might result in a high pitch angle and potential stall if the autopilot attempts to climb too aggressively.
- Thermal Hunting: In glider modes (SOAR),
LOITER_TO_ALTis used to stay within a rising thermal until a safe cruise altitude is reached.
Practical Use Cases
- Mountain Clearance:
- Scenario: A drone needs to cross a 2000m ridge from a takeoff point at 500m.
- Action: Place a
NAV_LOITER_TO_ALTat 2100m before the ridge waypoint. This ensures the drone circles and gains the required altitude before attempting the crossing.
- Safe Landing Approach:
- Scenario: A plane is returning at high altitude and needs to descend to 50m for a landing flare.
- Action: Use
NAV_LOITER_TO_ALTto spiral down to 50m over the runway threshold, preventing an overspeed approach.
Key Parameters
WP_LOITER_RAD: Default radius.ALT_HOLD_RTL: (Plane) Minimum altitude for RTL/Loiter safety.
Key Codebase Locations
- ArduCopter/mode_auto.cpp:2175:
verify_loiter_to_altimplementation. - ArduPlane/commands_logic.cpp:766:
verify_loiter_to_altimplementation.
NAV_SPLINE_WAYPOINT
Summary
The NAV_SPLINE_WAYPOINT command defines a 3D coordinate that the vehicle must pass through using a curved, "spline" trajectory. Unlike the standard linear waypoint, which produces sharp corners, the spline waypoint calculates a smooth path that considers the position of the previous and next waypoints to ensure the vehicle never has to come to a complete stop.
Status
Supported (ArduCopter Only)
Directionality
- RX (Receive): The vehicle receives this command as part of a mission upload.
Mission Storage (AP_Mission)
- Packet Param 1 (Delay): Stored in the internal
p1field as a 16-bit integer (seconds). - Packet Param 2-4: Empty.
- x, y, z: Target Latitude, Longitude, and Altitude.
Execution (Engineer's View)
ArduCopter Implementation
In Copter, the command triggers ModeAuto::do_spline_wp (mode_auto.cpp).
- Catmull-Rom Spline: ArduPilot uses a modified Catmull-Rom spline algorithm. To calculate the curve for the current segment (Segment B), the algorithm requires four points:
- $P_0$: The waypoint before the previous one.
- $P_1$: The previous waypoint (start of the curve).
- $P_2$: The current spline waypoint (target).
- $P_3$: The next mission item (used to determine the exit velocity vector).
- Velocity Control: The spline ensures that the velocity vector at $P_2$ is tangent to the curve, allowing for high-speed passes without the "jerk" associated with linear cornering.
- Completion: If
Delay (p1)is 0, the waypoint is considered complete as soon as the vehicle passes through the coordinate, allowing it to transition immediately to the next leg. IfDelay > 0, the vehicle will decelerate to a stop at the coordinate and wait before continuing.
Data Fields (MAVLink)
param1(Delay): Hold time in seconds at the waypoint.x(Latitude): Target latitude.y(Longitude): Target longitude.z(Altitude): Target altitude.
Theory: The Hermite Spline Formulation
The path between waypoints $P_1$ and $P_2$ is defined by a cubic polynomial in terms of time $t \in [0, 1]$:
$$ \mathbf{P}(t) = (2t^3 - 3t^2 + 1)\mathbf{P}_1 + (t^3 - 2t^2 + t)\mathbf{T}_1 + (-2t^3 + 3t^2)\mathbf{P}_2 + (t^3 - t^2)\mathbf{T}_2 $$
Where:
- $\mathbf{P}_1, \mathbf{P}_2$ are the positions.
- $\mathbf{T}_1, \mathbf{T}_2$ are the tangent vectors (velocities) at those points, derived from the surrounding waypoints.
Practical Use Cases
- Cinematic Fly-bys:
- Scenario: A drone needs to fly a smooth arc around a building.
- Action: Use a sequence of
NAV_SPLINE_WAYPOINTitems. The resulting path will be a fluid curve, preventing the "robotic" stop-and-turn behavior of standard waypoints.
- Obstacle Avoidance in Speed Runs:
- Scenario: A racing drone needs to navigate a series of gates at maximum speed.
- Action: Spline waypoints allow the drone to maintain its kinetic energy by "rounding" the corners optimally.
Key Parameters
WPNAV_SPEED: Maximum horizontal speed between waypoints.WPNAV_ACCEL: Maximum acceleration used to define the spline's "tightness."
Key Codebase Locations
- ArduCopter/mode_auto.cpp:1614: Spline waypoint initialization.
- libraries/AC_WPNav/AC_WPNav.cpp: The core spline math implementation.
NAV_ALTITUDE_WAIT
Summary
The NAV_ALTITUDE_WAIT command is a specialized mission item designed for high-altitude balloon launches or gliders. It puts the vehicle into an "Idle" or "Wait" state until it reaches a target altitude or a specific vertical speed, allowing for autonomous activation after a balloon burst or a release from a mother-ship.
Status
Supported (ArduPlane Only)
Directionality
- RX (Receive): The vehicle receives this command as part of a mission upload.
Mission Storage (AP_Mission)
- Altitude (Param 1): Target altitude (meters).
- Descent Rate (Param 2): Vertical speed (m/s) to trigger completion (e.g., detecting a burst).
- Wiggle Time (Param 3): Frequency (seconds) to move control surfaces to prevent freezing in extreme cold.
- Packing: Stored in the
altitude_waitcontent struct.
Execution (Engineer's View)
High Altitude Logic
The command is managed in Plane::do_altitude_wait (commands_logic.cpp).
- Idle State: The autopilot sets
auto_state.idle_mode = true. In this state, servos are held at trim, and the motor is typically disabled. - The "Wiggle": At high altitudes ($>15km$), temperatures drop below $-50^\circ C$. Lubricants in servos can thicken or freeze. ArduPilot uses
Param 3to periodically cycle the servos, using internal friction to generate enough heat to keep the linkages moving. - Burst Detection: The autopilot monitors the vertical velocity ($V_z$). If $V_z$ becomes more negative than
Param 2(indicating the balloon has burst and the vehicle is falling), it completes the command immediately. - Completion: Once the target altitude is reached or a burst is detected, the mission advances to the next item (usually a
NAV_TAKEOFForWAYPOINT), and full flight control is restored.
Data Fields (MAVLink)
param1(Alt): Target altitude (m).param2(Descent): Descent rate (m/s).param3(Wiggle): Time between wiggles (s).param4toparam7: Unused.
Theory: Energy Conservation in Near-Space
In a balloon-launch mission, the vehicle is a passenger for 90% of the ascent.
- Thermal Management: Passive electronics cooling is non-existent in the thin upper atmosphere. By idling the CPU and servos, the vehicle minimizes internal heat generation until the "Real" flight begins.
- Pressure Dynamics: The autopilot uses the EKF's altitude solution, which fuses barometric and GPS data. At very high altitudes, barometric pressure becomes non-linear; ArduPilot's
AP_Barolibrary handles the transition to GPS-dominant altitude sensing safely.
Practical Use Cases
- Weather Balloon Glider:
- Scenario: A glider is carried to 30,000m by a balloon.
- Action:
NAV_ALTITUDE_WAIT (Alt: 30000, Descent: 5m/s, Wiggle: 60s). The drone stays "asleep" during the 2-hour ascent, wiggling every minute to stay limber, and wakes up the moment the balloon pops.
- Drop-Test:
- Scenario: Dropping a test airframe from a larger plane.
- Action: Mission starts with
NAV_ALTITUDE_WAITto detect the rapid descent after release.
Key Parameters
TKOFF_THR_DELAY: Often used after this command to delay motor start until clear of the balloon debris.
Key Codebase Locations
- ArduPlane/commands_logic.cpp:90: Mission command initialization.
- ArduPlane/pullup.cpp: Transition to active flight after wait.
NAV_VTOL_TAKEOFF
Summary
The NAV_VTOL_TAKEOFF command instructs a QuadPlane (or Tilt-Rotor) to lift off vertically using its multicopter motors and then transition to forward, fixed-wing flight. This command is distinct from a standard NAV_TAKEOFF, as it explicitly manages the high-energy state transition between hovering and cruising.
Status
Supported (ArduPlane / QuadPlane Only)
Directionality
- RX (Receive): The vehicle receives this command as part of a mission upload.
Mission Storage (AP_Mission)
- Packing: ArduPilot stores the command in the standard location structure. The altitude is extracted from the
zfield of the MAVLink packet.
Execution (Engineer's View)
ArduPlane (QuadPlane) Implementation
In QuadPlane, the command triggers QuadPlane::do_vtol_takeoff (quadplane.cpp).
-
Vertical Phase:
- The vehicle uses the vertical position controller (
pos_control) to rise to the target altitude. - Time-to-Altitude Estimate: The autopilot calculates the expected duration of the climb using the following kinematic model:
$$ t_{accel} = \frac{V_{max} - V_z}{a} $$
$$ d_{accel} = V_z \cdot t_{accel} + \frac{1}{2} a \cdot t_{accel}^2 $$
$$ t_{total} = \max(t_{accel}, 0) + \max\left(\frac{d_{total} - d_{accel}}{V_{max}}, 0\right) $$ - The vehicle uses the vertical position controller (
-
Transition Phase:
- Once the vertical target is reached, the autopilot begins the Transition to Fixed-Wing.
- It engages the forward motor (pusher) while maintaining multicopter attitude control.
- Once the airspeed reaches the
ARSPD_FBW_MIN, the multicopter motors are phased out, and the vehicle becomes a standard airplane.
Data Fields (MAVLink)
param1: Empty.param2: Empty.param3: Empty.param4(Yaw): Target heading (degrees).x(Latitude): Target latitude.y(Longitude): Target longitude.z(Altitude): Target altitude (meters).
Theory: The "V-Alpha" Transition
The transition from vertical to horizontal flight is the most dangerous phase of flight for a VTOL aircraft.
- Wing Loading: During transition, lift is shared between the vertical rotors and the wing.
- Pitch Control: As forward speed increases, the elevators gain authority, but the multicopter pitch controller is still active. ArduPilot uses a "Blend" logic to ensure smooth control handover.
- Stall Risk: If the transition is too slow, the battery may deplete. If too fast, the aircraft may pitch up violently due to the increased airspeed over the wing.
Practical Use Cases
- Runway-Free Long Endurance:
- Scenario: A fixed-wing plane needs to map 100km of pipeline but must take off from a small jungle clearing.
- Action: Use
NAV_VTOL_TAKEOFFto rise 30m above the trees before accelerating into high-efficiency fixed-wing mode.
- Shipboard Launch:
- Scenario: Launching from a moving vessel.
- Action: VTOL takeoff allows the aircraft to clear the deck and masts vertically before engaging the pusher motor to match the ship's speed and move away safely.
Key Parameters
Q_TAKEOFF_ALT: Default altitude if mission altitude is 0.Q_TRANSITION_MS: Duration of the forward motor ramp-up.Q_TILT_MAX: (Tilt-Rotor only) Maximum tilt angle during transition.
Key Codebase Locations
- ArduPlane/quadplane.cpp:3298: VTOL takeoff initialization.
- ArduPlane/quadplane.cpp:3390: Transition logic handler.
NAV_VTOL_LAND
Summary
The NAV_VTOL_LAND command instructs a hybrid aircraft (QuadPlane) to transition from fixed-wing cruise to multicopter mode and perform a vertical descent to a precise location. This allows long-range fixed-wing assets to land in confined spaces without a runway.
Status
Supported (ArduPlane / QuadPlane Only)
Directionality
- RX (Receive): The vehicle receives this command as part of a mission upload or as a RTL/Failsafe action.
Mission Storage (AP_Mission)
- Packet Param 1 (Options): Stored in the internal
p1field. This bitmask allows for advanced landing behaviors, such as "Descending Loiter" before the final drop.
Execution (Engineer's View)
ArduPlane (QuadPlane) Implementation
In QuadPlane, the command triggers a multi-stage state machine (quadplane.cpp).
- Back-Transition:
- The aircraft approaches the target waypoint in fixed-wing mode.
- It cuts the forward motor and engages the VTOL motors (multicopter) as it decelerates below the stall speed.
- Approach:
- Final Descent:
- The vehicle uses the multicopter vertical controller to descend at
Q_LAND_SPEED. - It uses the
landing_detectlogic to verify touchdown before disarming.
- The vehicle uses the multicopter vertical controller to descend at
Data Fields (MAVLink)
param1(Options): Bitmask for landing behavior.param2: Empty.param3: Empty.param4(Yaw): Desired heading for landing.x(Latitude): Target landing location.y(Longitude): Target landing location.z(Altitude): Final altitude (typically 0).
Theory: The Q-Approach
The "Q-Approach" is a sophisticated landing method designed for high-performance VTOLs.
- Aerodynamic Transition: Unlike multicopters, QuadPlanes have significant wing lift. If they descend too quickly while moving forward, the wing can generate asymmetric lift (if rolling), leading to instability.
- Airbrake Effect: ArduPilot can use the multicopter motors as "airbrakes" by spinning them up at low power while still in forward flight, creating high drag to slow the aircraft down for the final hover.
Practical Use Cases
- Precision Recovery:
- Scenario: A 3-meter wingspan drone returning to a 10m x 10m clearing.
- Action:
NAV_VTOL_LANDensures the aircraft flies the long-distance return at high efficiency, then converts to a hovering drone for a pin-point landing.
- Autonomous Charging Dock:
- Scenario: A drone landing on a robotic charging platform.
- Action: Use
NAV_VTOL_LANDin conjunction with a Precision Landing sensor (IR/Camera) to land within centimeters of the charging pins.
Key Parameters
Q_TRANS_DECEL: Deceleration rate (m/s/s) during back-transition.Q_LAND_FINAL_ALT: Altitude above ground at which the aircraft enters its final, slower descent phase.Q_FWD_THR_USE: Allows the pusher motor to assist with station-keeping in high winds during the vertical descent.
Key Codebase Locations
- ArduPlane/quadplane.cpp: Main VTOL landing handler.
- libraries/AP_Landing/AP_Landing.cpp: Shared landing library.
NAV_DELAY
Summary
The NAV_DELAY command pauses the vehicle's navigation progress for a specified duration or until a specific UTC time. Unlike CONDITION_DELAY (which is a mission-logic gate), NAV_DELAY is a navigation-level command that usually involves the vehicle hovering or loitering at its current location.
Status
Supported (All Vehicles)
Directionality
- RX (Receive): The vehicle receives this command as part of a mission upload.
Mission Storage (AP_Mission)
- Duration (Param 1): Seconds to delay (relative).
- Time (Param 2-4): Hour, Minute, and Second (UTC) for absolute time delay.
- Packing: Stored in the
nav_delaycontent struct.
Execution (Engineer's View)
Delay Logic
Execution is handled by ModeAuto::do_nav_delay (mode_auto.cpp).
- Timer Modes:
- Relative: The timer starts the moment the vehicle reaches the waypoint.
- Absolute (UTC): The mission will not proceed until the onboard GPS clock matches the requested UTC time. This requires a valid GPS lock and PPS (Pulse Per Second) synchronization.
- Vehicle State: While delaying, the vehicle maintains its current coordinates.
- Copter: Position Hold (Loiter).
- Plane: Loiter (Orbit).
- Resumption: Once
millis() - start_time > duration, the mission state machine is released to the next item.
Data Fields (MAVLink)
param1(Delay): Seconds.param2(Hour): UTC Hour [0-23].param3(Min): UTC Minute [0-59].param4(Sec): UTC Second [0-59].
Theory: Synchronized Swarms
The UTC delay is a foundational tool for Multi-Vehicle Synchronization.
- The Problem: GPS signals take different times to reach different drones. Onboard clocks can drift.
- The Solution: By using UTC time (derived from the atomic clocks on GPS satellites), multiple drones can be commanded to "Start Scan" at the exact same microsecond, regardless of when they took off or how far they traveled.
Practical Use Cases
- Golden Hour Photography:
- Scenario: A drone needs to take a photo at exactly sunset.
- Action:
NAV_WAYPOINT->NAV_DELAY (UTC Time of Sunset). The drone flies to the spot and orbits until the lighting is perfect.
- Coordinated Drop:
- Scenario: Two drones dropping a heavy net.
- Action: Both missions use
NAV_DELAYto synchronize the release at the same UTC second.
Key Parameters
GPS_TYPE: Required for UTC time accuracy.WP_LOITER_RAD: (Plane) Orbit size during delay.
Key Codebase Locations
- ArduCopter/mode_auto.cpp:723: Mission command intake.
- ArduCopter/mode_auto.cpp:2186: Relative timer verification.
NAV_PAYLOAD_PLACE
Summary
The NAV_PAYLOAD_PLACE command (often called "Payload Delivery") instructions the vehicle to descend vertically until it detects that a winch-slung or fixed payload has touched the ground. Once touchdown is detected, the vehicle releases the payload (if a gripper is attached) and climbs back to its original altitude.
Status
Supported (ArduCopter and QuadPlane)
Directionality
- RX (Receive): The vehicle receives this command as part of a mission upload.
Mission Storage (AP_Mission)
- Packet Param 1 (Max Descent): Stored in the internal
p1field.- Unit Conversion: ArduPilot converts this value from meters to centimeters ($cm = m \cdot 100$) before storing it in EEPROM.
- x, y, z: The delivery coordinates.
Execution (Engineer's View)
ArduCopter Implementation
In Copter, the command triggers ModeAuto::do_payload_place (mode_auto.cpp).
- Approach: The drone flies to the target Lat/Lon at the current mission altitude.
- Descent: The drone begins a vertical descent at the speed defined by
PLDP_SPEED_DN. - Touchdown Detection: The autopilot does not use simple altitude for detection. Instead, it monitors the Thrust/Weight Ratio.
- As the payload touches the ground, the load on the motors decreases.
- When the thrust required to maintain the descent rate drops below the threshold defined by
PLDP_THRESH, the autopilot considers the payload "Placed".
- Release & Recovery:
- If a gripper or winch is configured, the autopilot triggers the release action.
- The drone waits for
PLDP_DELAYseconds to ensure a clean release. - The drone then climbs back to the initial altitude to continue the mission.
Data Fields (MAVLink)
param1(Max Descent): The maximum distance (meters) the vehicle is allowed to descend. If the ground is not reached within this distance, the command is aborted to prevent a crash.x(Latitude): Target delivery location.y(Longitude): Target delivery location.z(Altitude): Current flight altitude.
Theory: The Load-Sensing Algorithm
Payload delivery in high-wind or turbulent environments is difficult because the vehicle's thrust is constantly fluctuating. ArduPilot uses a filtered approach to detect the "offloading" of weight:
$$ \text{Placed} = \left( \frac{T_{current}}{T_{average\_descent}} \right) < \mathrm{PLDP\_THRESH} $$
Where $T_{current}$ is the instantaneous thrust output and $T_{average\_descent}$ is the learned thrust required to descend at a steady rate with the payload.
Practical Use Cases
- Automated Logistics:
- Scenario: Delivering a medical package to a remote village.
- Action: The drone uses
NAV_PAYLOAD_PLACE. It descends until the box touches the ground, opens the gripper, and climbs away without needing the pilot to see the ground or manage the descent manually.
- Scientific Sensor Deployment:
- Scenario: Placing a seismometer on a steep, inaccessible slope.
- Action: The
PLDP_THRESHlogic ensures the sensor is firmly on the ground before release, even if the terrain altitude is not perfectly known.
Key Parameters
PLDP_THRESH: The fraction of hover thrust that indicates a touchdown (Default 0.9).PLDP_RNG_MAX: Uses a downward-facing rangefinder to prevent "false touchdowns" if the drone is too high.PLDP_SPEED_DN: The vertical velocity during the delivery phase.
Key Codebase Locations
- ArduCopter/mode_auto.cpp:2024: Copter delivery state machine.
- ArduPlane/quadplane.cpp: QuadPlane implementation.
NAV_RALLY_POINT
Summary
The NAV_RALLY_POINT command defines an alternative "Safe Harbor" location for the vehicle. Unlike the Home position (which is usually where the drone took off), Rally Points are used as backup landing or loiter sites that the autopilot can choose from during a failsafe or RTL event based on proximity.
Status
Supported (All Vehicles)
Directionality
- RX (Receive): The vehicle receives these commands during a mission upload (specifically when using the MAVLink Rally Protocol).
Mission Storage (AP_Mission)
- Packing: Rally points are stored in a dedicated region of the EEPROM, separate from the main waypoint mission, allowing the drone to maintain its safety anchors even if the main mission is cleared.
- Quantity: ArduPilot typically supports up to 20-50 individual rally points depending on hardware.
Execution (Engineer's View)
Intelligent RTL
When an RTL (Return to Launch) is triggered:
- Comparison: The autopilot calls
calc_best_rally_or_home_location()(AP_Rally.cpp). - Distance Heuristic: It calculates the 2D distance to Home and all loaded Rally Points.
- Selection: It chooses the Geographically Closest point.
- Action: The vehicle flies to the chosen point and enters a loiter (Plane) or hover (Copter).
Data Fields (MAVLink)
x(Latitude): Rally location.y(Longitude): Rally location.z(Altitude): Rally location.
Theory: Distributed Recovery
Standard recovery is centralized (Home). Rally Points enable Distributed Recovery.
- The Hazard: In long-distance missions (Linear Corridors), the vehicle may be 20km from Home when a battery failsafe occurs. It might not have enough energy to return 20km.
- The Solution: By placing Rally Points every 2km along the path, the autopilot ensures it never has to fly more than 1km to find a safe "Lifeboat."
Practical Use Cases
- Cross-Country FPV:
- Scenario: A plane is flying between two mountain peaks.
- Action: Rally points are placed at known-clear meadows. If the radio link fails, the plane flies to the nearest meadow rather than trying to fly back over the peaks.
- Redundant Landing Pads:
- Scenario: A drone landing at a busy facility.
- Action: Multiple rally points represent different landing pads. The drone chooses the one it can reach most efficiently.
Key Parameters
RALLY_LIMIT_KM: The maximum distance the autopilot will look for a rally point.RALLY_INCL_HOME: Defines if Home should be considered in the proximity calculation.
Key Codebase Locations
- libraries/AP_Rally/AP_Rally.cpp: Proximity comparison logic.
- libraries/GCS_MAVLink/MissionItemProtocol_Rally.cpp: Communication protocol for rally points.
NAV_SCRIPT_TIME
Summary
The NAV_SCRIPT_TIME command is a powerful hybrid command that combines mission flow control with Lua Scripting. Unlike the "Do" version (DO_SEND_SCRIPT_MESSAGE), NAV_SCRIPT_TIME is a Blocking Navigation Command. The mission will not advance to the next item until the Lua script explicitly signals completion or a timeout is reached.
Status
Supported (All Vehicles with Lua Scripting enabled)
Directionality
- RX (Receive): The vehicle receives this command as part of a mission upload.
Mission Storage (AP_Mission)
- Command ID (Param 1): A user-defined ID the script uses to know what to do.
- Timeout (Param 2): Max duration in seconds before the mission auto-advances.
- Arg 1 & 2 (Param 3-4): Floats passed to the script.
- Arg 3 & 4 (x, y): Integers passed to the script.
- Packing: Stored in the
nav_script_timecontent struct.
Execution (Engineer's View)
Handshake Logic
The command creates a tight loop between the Mission Engine and the Lua Virtual Machine (AP_Scripting.cpp).
- Trigger: The mission state machine sets the
nav_scripting.doneflag tofalseand records the start time. - Script Detection: The Lua script polls
mission:get_nav_script_time_id(). - Operation: The script performs its task (e.g., complex pattern flying or sensor analysis).
- Completion Signal: The script calls
mission:nav_script_time_done(id). - Watchdog: If the script fails to call the "done" method before
Param 2seconds pass, the mission engine logs a warning and proceeds to the next item regardless.
Data Fields (MAVLink)
param1(ID): Custom command ID.param2(Timeout): Seconds.param3(Arg1): Float.param4(Arg2): Float.x(Arg3): Int.y(Arg4): Int.
Theory: The Co-Processor Model
NAV_SCRIPT_TIME implements an Asynchronous Co-Processor model for mission logic.
- Decoupling: The "Heavy Lifting" (AI, Image Processing, Path Re-planning) happens in the Lua VM, which is sandboxed and memory-managed.
- Deterministic Safety: The main C++ flight code remains simple and stable. If the script crashes, the mission watchdog (Timeout) ensures the drone doesn't loiter until it crashes.
Practical Use Cases
- AI Search Pattern:
- Scenario: A drone finds a target but needs to perform a "spiral-out" search to find more.
- Action:
NAV_SCRIPT_TIME (ID: 101, Timeout: 60s). The Lua script takes control of the position setpoints, flies the spiral, and signals "Done" once the search is complete.
- External Hardware Sync:
- Scenario: A drone landing on a robotic dock that takes 15 seconds to open.
- Action: The script communicates with the dock, waits for the "Open" signal, and then releases the mission to continue to
NAV_LAND.
Key Parameters
SCR_ENABLE: Enables the scripting engine.SCR_HEAP_SIZE: Important for complex scripts to avoid OOM errors.
Key Codebase Locations
- libraries/AP_Scripting/AP_Scripting.cpp: Implementation of the "Done" signal and binding.
- ArduCopter/mode_auto.cpp:2311: Verification logic.
NAV_ATTITUDE_TIME
Summary
The NAV_ATTITUDE_TIME command instructs the vehicle to maintain a specific attitude (Roll, Pitch, and Yaw) and a constant climb/descent rate for a set duration. This is an advanced "Open Loop" navigation command used for airframe testing, specialized physics research, or high-speed dashes where GPS-based position hold is not required.
Status
Supported (ArduCopter)
Directionality
- RX (Receive): The vehicle receives this command as part of a mission upload.
Mission Storage (AP_Mission)
- Time (Param 1): Duration in seconds.
- Roll (Param 2): Degrees.
- Pitch (Param 3): Degrees.
- Yaw (Param 4): Degrees.
- Climb Rate (x): Meters per second.
- Packing: Stored in the
nav_attitude_timecontent struct.
Execution (Engineer's View)
Direct Attitude Control
The command bypasses the standard "Waypoint-to-Waypoint" navigation and interacts directly with the Attitude Controller (mode_auto.cpp:739).
- Targeting: The autopilot feeds the requested Roll, Pitch, and Yaw angles to the
AC_AttitudeControllibrary. - Vertical Control: The vertical position controller maintains the climb rate specified in the
xfield (Param 5). - Horizontal Behavior: The drone drifts with the wind. Because no Lat/Lon target is provided, the drone behaves as if it were in a manual mode (like AltHold or Stabilize) but with a robotic pilot holding the sticks at fixed angles.
- Completion: The mission advances once the system time exceeds
Param 1seconds from the start of the command.
Data Fields (MAVLink)
param1(Time): s.param2(Roll): deg.param3(Pitch): deg.param4(Yaw): deg.x(Climb Rate): m/s.
Theory: Flight Dynamics Research
NAV_ATTITUDE_TIME is the primary tool for Empirical Aerodynamic Modeling.
- The Problem: GPS navigation masks the "True" physics of the drone by constantly correcting for error.
- The Solution: By flying at a fixed pitch and roll (e.g., 5 degrees pitch forward) for 10 seconds, engineers can measure the resulting airspeed to calculate the airframe's Drag Coefficient ($C_d$) and Thrust Curve.
- Safety: It is critical to ensure enough "Clear Air" is available, as the vehicle will move in the direction of the lean without regard for geofences or waypoints during the execution.
Practical Use Cases
- High-Speed Dash:
- Scenario: A drone needs to cross a field as fast as possible.
- Action:
NAV_ATTITUDE_TIME (Pitch: -45, Time: 5s). The drone tilts aggressively and accelerates until the timer pops, ignoring GPS braking logic.
- Structural Vibration Testing:
- Scenario: Identifying resonant frequencies at specific bank angles.
- Action: A script cycles through various
NAV_ATTITUDE_TIMEcommands while recording IMU data.
Key Parameters
ANGLE_MAX: Still limits the absolute maximum tilt to prevent tip-over.ATC_INPUT_TC: Determines how quickly the drone snaps to the requested attitude.
Key Codebase Locations
- ArduCopter/mode_auto.cpp:739: Command intake.
- ArduCopter/mode_auto.cpp:2327: Timer verification.