DO_JUMP
Summary
The DO_JUMP command provides procedural flow control within a mission. It allows the autopilot to jump back (or forward) to a specific mission item number and repeat that sequence a set number of times. This is the primary mechanism for creating loops (e.g., repeating a survey grid or a loiter-and-check sequence).
Status
Supported (All Vehicles)
Directionality
- RX (Receive): The vehicle receives this command as part of a mission upload.
Mission Storage (AP_Mission)
- Target (Param 1): The sequence number of the mission item to jump to.
- Repeat Count (Param 2): The number of times to perform the jump.
- Mechanism: ArduPilot maintains an internal
jump_trackingarray (AP_Mission.cpp) to persist the state of each jump command across reboots or mode changes.
Execution (Engineer's View)
Logic Flow
When the mission engine encounters a DO_JUMP:
- Check Counter: It retrieves the current
num_times_runfor this specific command index from thejump_trackingRAM. - Comparison:
- If
num_times_run<Repeat Count, it increments the counter and sets the current mission index to the Target. - If
num_times_run==Repeat Count, it ignores the jump and proceeds to the next mission item (breaking the loop).
- If
- Unlimited Loops: If the
Repeat Countis set to a high value (like 255 or 65535, depending on the GCS), ArduPilot can be configured to loop indefinitely.
Jump Tracking Constraints
- Max Jumps: ArduPilot typically supports tracking up to 15-20 individual
DO_JUMPcommands in a single mission (defined byAP_MISSION_MAX_NUM_DO_JUMP_COMMANDS). - Nested Loops: While technically possible, nesting jumps can lead to complex state behavior. ArduPilot's tracker is indexed by the index of the jump command itself, which prevents collisions between different loops.
Data Fields (MAVLink)
param1(Item #): Mission sequence number to jump to.param2(Repeat): Total number of times to perform the jump.param3toparam7: Unused.
Theory: Finite State Machines and Halting
A mission is essentially a Linear Finite State Machine. DO_JUMP introduces Cycles into the graph.
- Determinism: Because ArduPilot tracks the repeat count in non-volatile-ready RAM, the mission remains deterministic. If the vehicle loses power and reboots, the mission can resume and "remember" how many loops it has already completed.
- The Halting Problem: Infinite loops are dangerous in autonomous flight. Always ensure a
DO_JUMPhas a finite repeat count unless the vehicle is in a monitored "holding pattern" state.
Practical Use Cases
- Survey Re-runs:
- Scenario: A drone is scanning for a lost hiker. The search grid needs to be flown 3 times to ensure coverage.
- Action:
WP 1...WP 10->DO_JUMP (Target: 1, Repeat: 3).
- Delayed Entry:
- Scenario: A plane must loiter at a waypoint until a specific time, but ArduPilot's clock isn't synchronized yet.
- Action: Use a
DO_JUMPto a loiter point with a small repeat count to "wait" for GCS synchronization.
Key Parameters
MIS_RESTART: Controls whether the jump counters are reset when the mission is restarted.
Key Codebase Locations
- libraries/AP_Mission/AP_Mission.cpp:2311:
increment_jump_times_runimplementation. - libraries/AP_Mission/AP_Mission.h: Definition of the jump tracking structure.
DO_CHANGE_SPEED
Summary
The DO_CHANGE_SPEED command allows the autopilot to dynamically adjust the vehicle's speed and throttle limits during a mission. This is essential for missions that require high-speed transit between work areas but slow, precise flight during data collection.
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)
- Speed Type (Param 1): 0 = Airspeed, 1 = Ground Speed.
- Target Speed (Param 2): Target speed in m/s.
- Throttle (Param 3): Desired throttle percentage (0-100).
- Mechanism: Stored in the internal
speedcontent struct.
Execution (Engineer's View)
ArduCopter Implementation
In Copter, the command triggers ModeAuto::do_change_speed (mode_auto.cpp).
- WPNav Update: The command updates the
AC_WPNavlibrary's internal speed variables. - Overrides:
- Horizontal: Sets
set_speed_xy(cm/s). - Vertical: If the type is set to climb or descent (ArduPilot extension), it updates
set_speed_uporset_speed_down.
- Horizontal: Sets
- Persistence: The new speed remains in effect until the end of the mission or until another
DO_CHANGE_SPEEDcommand is encountered.
ArduPlane Implementation
In Plane, the command updates the navigation controller's target velocity.
- Airspeed vs. Groundspeed:
- If Airspeed is selected: The plane adjusts pitch and throttle to maintain the target airspeed (IAS/EAS).
- If Groundspeed is selected: The plane uses its "Min Groundspeed" logic (
MIN_GNDSPD_CM) to ensure it maintains progress against headwinds.
- Safety Limits: The autopilot will always clamp the requested speed between
ARSPD_FBW_MINandARSPD_FBW_MAX.
Data Fields (MAVLink)
param1(Type): 0:Airspeed, 1:Groundspeed, 2:Climb speed, 3:Descent speed.param2(Speed): Target speed in m/s.param3(Throttle): Throttle setpoint (0-100). -1 to ignore.param4(Relative): 0: Absolute speed, 1: Offset from default.
Theory: Groundspeed vs. Airspeed
Understanding the difference is critical for safety:
- Fixed-Wing: Airspeed is what keeps you in the air (lift). Changing airspeed affects your stall margin.
DO_CHANGE_SPEEDin a plane is often used to fly slowly for photography or fast for "dash" legs. - Multicopter: Multicopters primarily care about Groundspeed. Airspeed is only relevant in high-wind scenarios where "Lean Angle" limits (e.g.,
ANGLE_MAX) might prevent the drone from achieving the requested groundspeed.
Practical Use Cases
- Long Range Transit:
- Scenario: A delivery drone needs to fly 10km to a destination.
- Action:
TAKEOFF->DO_CHANGE_SPEED (25 m/s)->WAYPOINT (Destination).
- Precision Mapping:
- Scenario: A high-resolution camera requires a slow ground speed to prevent motion blur.
- Action:
DO_CHANGE_SPEED (5 m/s)->WAYPOINT (Start of Grid).
Key Parameters
WPNAV_SPEED: (Copter) Default mission speed.TRIM_ARSPD_CM: (Plane) Default cruise airspeed.ARSPD_FBW_MIN: Absolute minimum airspeed safety limit.
Key Codebase Locations
- ArduCopter/mode_auto.cpp:1936: Copter implementation.
- ArduPlane/commands_logic.cpp: Plane implementation.
DO_SET_HOME
Summary
The DO_SET_HOME command redefines the vehicle's "Home" position. The Home position is used as the reference point for RTL (Return to Launch), altitude-above-home calculations, and distance-from-home failsafes.
Status
Supported (All Vehicles)
Directionality
- RX (Receive): The vehicle receives this command as part of a mission upload or as a direct command (Guided/Command Mode).
Mission Storage (AP_Mission)
- Use Current (Param 1):
- 1: Use the vehicle's current location as home.
- 0: Use the Lat/Lon/Alt provided in the command's x/y/z fields.
- Packing: Stored in the standard location struct.
Execution (Engineer's View)
Logic
The command calls AP_Vehicle::set_home() (or vehicle-specific wrappers like ModeAuto::do_set_home).
- Safety Check: ArduPilot generally allows setting Home while disarmed. If the vehicle is armed, setting home is typically restricted to the current location to prevent the vehicle from performing an RTL to a dangerously distant or unreachable coordinate.
- Coordinate Update: The EKF (Extended Kalman Filter) uses the new Home as the origin for its local NE (North-East) coordinate system if the "Absolute Altitude" is updated.
- GCS Notification: Upon successful update, the vehicle broadcasts a new
HOME_POSITION(242) MAVLink message to all connected Ground Control Stations.
Data Fields (MAVLink)
param1(Flag): 1: Current Location, 0: Specified Location.x(Latitude): New home latitude.y(Longitude): New home longitude.z(Altitude): New home altitude.
Theory: The EKF Origin vs. Home
It is important to distinguish between the EKF Origin and the Home Position.
- EKF Origin: The absolute GPS coordinate where the Kalman Filter initialized. It never changes during a flight.
- Home Position: A user-defined coordinate used for navigation. It can be changed multiple times.
- Math: Internal navigation is done in meters relative to the EKF Origin. When you "Set Home," ArduPilot calculates the meter-offset from the Origin and stores that as the new Home reference.
Practical Use Cases
- Mobile Landing Platform:
- Scenario: A drone takes off from a moving boat.
- Action: As the boat moves, the GCS periodically sends
DO_SET_HOME (Current Location: 1)to ensure the drone's RTL point stays near the boat.
- Long Corridor Missions:
- Scenario: A drone is inspecting 50km of power lines.
- Action: The mission can include
DO_SET_HOMEcommands at safe landing clearings along the route, so if a failsafe occurs, the drone flies to the nearest safe point rather than all the way back to the start.
Key Parameters
FS_GCS_ENABL: GCS failsafe.RTL_ALT: Altitude used when returning to the (potentially new) home.
Key Codebase Locations
- ArduCopter/mode_auto.cpp:1954:
do_set_homeimplementation. - libraries/AP_Vehicle/AP_Vehicle.cpp: Core Home management logic.
Summary
The DO_SET_RELAY and DO_REPEAT_RELAY commands provide simple digital control over the vehicle's GPIO pins. Relays are typically used to trigger non-MAVLink hardware like power switches, smoke generators, water pumps, or simple camera shutters.
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)
- Relay Number (Param 1): The index of the relay to control (typically 0-5).
- State / Repeat (Param 2):
- 181: 0: Off, 1: On.
- 182: The number of times to toggle the relay.
- Cycle Time (Param 3): (182 only) The duration of each on/off cycle in seconds.
- Packing: Stored in the
relayorrepeat_relaycontent struct withinAP_Mission.
Execution (Engineer's View)
Logic Implementation
The commands utilize the AP_ServoRelayEvents library (AP_ServoRelayEvents.cpp).
- Pin Mapping: ArduPilot maps "Relay 0" to a physical GPIO pin on the flight controller via the
RELAY_PINparameter. - Toggle Logic (Repeat):
- The
delay_msis calculated asParam3 * 500(half of the cycle time). - The relay state is flipped every
delay_msuntil the repeat count is exhausted.
- The
- Conflict Handling: If a new relay command is received for a pin currently running a "Repeat" sequence, the existing sequence is immediately cancelled in favor of the new state.
Data Fields (MAVLink)
DO_SET_RELAY (181)
param1(Index): Relay instance number.param2(State): 0: OFF, 1: ON.
DO_REPEAT_RELAY (182)
param1(Index): Relay instance number.param2(Count): Number of toggle cycles.param3(Time): Cycle time in seconds.
Theory: PWM vs. GPIO
Most flight controller pins are configured for PWM (Pulse Width Modulation) by default to drive servos.
- Relay Transformation: When a pin is assigned to a Relay, the autopilot reconfigures the hardware timer/DMA for that pin into Digital I/O Mode.
- Voltage: The output is typically 3.3V (standard microcontrollers) or 5V (level-shifted boards), which is used to trigger a transistor or a physical mechanical relay module.
Practical Use Cases
- Water Sprayer (Agri-Drone):
- Scenario: A crop-dusting drone needs to spray only while over a specific field.
- Action:
WAYPOINT (Start of Field)->DO_SET_RELAY (On)...WAYPOINT (End of Field)->DO_SET_RELAY (Off).
- Emergency Strobe:
- Scenario: A drone needs to flash its high-intensity lights during an RTL.
- Action: Mission starts with
DO_REPEAT_RELAY (Count: 999, Time: 1s)to create a persistent blink.
Key Parameters
RELAY_PIN: Defines which physical pin is assigned to which relay instance.RELAY_DEFAULT: The state (On/Off) the relay enters upon autopilot boot.
Key Codebase Locations
- libraries/AP_ServoRelayEvents/AP_ServoRelayEvents.cpp: Main execution handler.
- libraries/AP_Relay/AP_Relay.cpp: Low-level GPIO driver.
Summary
The DO_SET_SERVO and DO_REPEAT_SERVO commands allow the mission script to directly override the PWM (Pulse Width Modulation) output of specific flight controller pins. This is used to control auxiliary hardware like mechanical grippers, gimbal pitches (non-stabilized), or robotic arms.
Status
Supported (All Vehicles)
Directionality
- RX (Receive): The vehicle receives this command as part of a mission upload or as a direct command.
Mission Storage (AP_Mission)
- Channel (Param 1): The Servo/Output number to control (typically 1-16).
- PWM Value / Repeat (Param 2):
- 183: The target PWM value (typically 1000 to 2000 microseconds).
- 184: The target PWM value for the "pulsed" state.
- Repeat Count (Param 3): (184 only) The number of times to pulse.
- Cycle Time (Param 4): (184 only) The duration of each pulse cycle in seconds.
- Packing: Stored in the
servoorrepeat_servocontent struct.
Execution (Engineer's View)
Handling Logic
Execution is managed by AP_ServoRelayEvents::do_set_servo (AP_ServoRelayEvents.cpp).
- Safety Check: ArduPilot checks the "Servo Function" (
SERVOX_FUNCTION) of the requested pin.- If the pin is assigned to a critical flight function (e.g.,
Motor 1orAileron), the mission command is rejected and an info message is sent to the GCS: "ServoRelayEvent: Channel %d is already in use". - The pin must be set to
0(Disabled),1(RCPassThru), or another non-critical auxiliary function.
- If the pin is assigned to a critical flight function (e.g.,
- Output: The autopilot writes the target PWM value directly to the hardware timer registry for that pin.
- Repeat Pattern (184): The autopilot toggles between the target PWM Value and the pin's Trim Value at the requested frequency.
Data Fields (MAVLink)
DO_SET_SERVO (183)
param1(Index): Output channel number.param2(PWM): PWM value [1000-2000].
DO_REPEAT_SERVO (184)
param1(Index): Output channel number.param2(PWM): PWM value for the pulse.param3(Count): Number of cycles.param4(Time): Cycle time (seconds).
Theory: The Duty Cycle
Servos are controlled by the width of a pulse sent at a specific frequency (typically 50Hz).
- Pulse Width ($ au$): 1000$ au$s is typically "Full Left/Closed," 1500$ au$s is "Center," and 2000$ au$s is "Full Right/Open."
- Timing: ArduPilot's main loop handles the logic, but the actual high-precision pulse generation is offloaded to the SoC's hardware timers (DMA/PWM) to ensure jitter-free control.
Practical Use Cases
- Cargo Hook:
- Scenario: A drone needs to drop a package at a specific waypoint.
- Action:
DO_SET_SERVO (Channel: 9, PWM: 2000)triggers the hook to open.
- Bait Dropper (Fishing Drone):
- Scenario: Releasing a fishing line into the surf.
- Action:
DO_REPEAT_SERVO (Channel: 10, PWM: 2000, Count: 2, Time: 1s)ensures the release mechanism triggers twice to prevent a snag.
Key Parameters
SERVOX_FUNCTION: Must be configured asDisabledorScriptingfor mission commands to work on that channel.SERVOX_MIN/MAX: Bounds for the PWM output.
Key Codebase Locations
- libraries/AP_ServoRelayEvents/AP_ServoRelayEvents.cpp:30: Command verification and safety logic.
- libraries/SRV_Channel/SRV_Channels.cpp: Low-level servo output manager.
DO_RETURN_PATH_START
Summary
The DO_RETURN_PATH_START command defines the beginning of a safe return segment in a mission. This is an advanced "failsafe-aware" mission marker that allows a vehicle to rejoin a pre-defined safe corridor if an RTL is triggered, rather than flying a direct (and potentially dangerous) line back to Home.
Status
Supported (ArduPlane / All Vehicles using Mission re-entry)
Directionality
- RX (Receive): The vehicle receives this command as part of a mission upload.
Mission Storage (AP_Mission)
- Segment Boundary: This command marks the start of the safe segment. The segment ends at the next encountered
DO_LAND_STARTor mission end. - Coordinates: Optional. If provided, they define the geometric start of the segment.
Execution (Engineer's View)
Corridor Logic
When a vehicle using missions for return-to-launch triggers a failsafe:
- Search: The autopilot calls
get_return_path_start()(AP_Mission.cpp). - Closest re-entry: It identifies the segment between
DO_RETURN_PATH_STARTandDO_LAND_START. - Orthogonal Projection: The autopilot calculates the closest point on that line segment to the vehicle's current position.
- Action: The vehicle flies to that "Re-entry Point" and then follows the mission forward towards the landing sequence.
Data Fields (MAVLink)
param1toparam4: Unused.x(Latitude): Optional coordinate.y(Longitude): Optional coordinate.z(Altitude): Optional coordinate.
Theory: Corridor Missions
Standard RTL logic is "Point A to Home." Corridor Logic is "Point A to the nearest safe pipe, then through the pipe to Home."
- Geofence Integration: If a mission is flown through a narrow canyon or a corridor bounded by Inclusion Fences, a direct RTL would immediately trigger a fence breach.
- Geometric Join: ArduPilot mathematically treats the mission between these markers as a vector. The vehicle joins the vector tangentially to ensure it never exits the "safe zone" during the recovery.
Practical Use Cases
- Canyon Mapping:
- Scenario: A drone is mapping a deep canyon. It is flying at 50m, but the canyon walls rise to 200m on either side.
- Action: Place
DO_RETURN_PATH_STARTat the canyon entrance. If the drone loses link deep in the canyon, it will not attempt to climb and fly over the walls; it will fly back along the canyon floor until it exits the marked segment.
- Urban BVLOS:
- Scenario: Flying along a pre-approved corridor between skyscrapers.
- Action: The markers define the safe air-road. Recovery always follows the approved path.
Key Parameters
MIS_OPTIONS: Must be configured to allow Mission-based RTL.
Key Codebase Locations
- libraries/AP_Mission/AP_Mission.cpp:2467:
get_return_path_startlogic.
DO_LAND_START
Summary
The DO_LAND_START command acts as a marker or "entry point" for the landing sequence in a mission. It is not an active flight command itself, but rather a metadata tag that tells the autopilot where the landing-specific mission items begin.
Status
Supported (All Vehicles)
Directionality
- RX (Receive): The vehicle receives this command as part of a mission upload or as a direct command (to trigger an immediate mission landing).
Mission Storage (AP_Mission)
- Latitude/Longitude/Altitude: Optional. If provided, they help the autopilot find the closest landing sequence if multiple exist in a single mission.
- Packing: Stored as a standard location-based mission item.
Execution (Engineer's View)
Autopilot Logic
ArduPilot uses DO_LAND_START in several critical scenarios:
- Mission Landing Trigger: When the vehicle enters RTL or a Battery Failsafe, and the mission contains a
DO_LAND_STARTmarker, the autopilot will skip all intermediate waypoints and jump directly to the item following the marker to begin a structured approach and landing. - Closest Sequence Discovery: If a mission contains multiple landing sequences (e.g., for different wind directions), ArduPilot's
get_landing_sequence_start()function (AP_Mission.cpp) will calculate whichDO_LAND_STARTis geographically closest to the vehicle's current position and use that sequence. - Arming Check: ArduPilot can be configured to require a
DO_LAND_STARTin the mission as a pre-arm safety check for certain high-value autonomous operations.
Data Fields (MAVLink)
param1toparam4: Unused.x(Latitude): Optional coordinate for proximity matching.y(Longitude): Optional coordinate for proximity matching.z(Altitude): Optional coordinate for proximity matching.
Theory: The Non-Destructive Jump
Standard missions are sequential. Failsafes usually involve returning home (RTL). DO_LAND_START enables a Mission-Aware Failsafe.
- The Problem: RTL is often a direct line that might cross restricted airspace or terrain.
- The Solution: By marking a landing sequence, the pilot defines a known-safe approach path (e.g., spiral down -> align with runway -> land).
DO_LAND_STARTensures the autopilot uses this "known-good" procedure instead of a "naive" RTL.
Practical Use Cases
- Runway Alignment (Plane):
- Scenario: A plane needs to land on a narrow runway.
- Action:
DO_LAND_START->WAYPOINT (Approach)->WAYPOINT (Final)->NAV_LAND. If a failsafe occurs, the plane jumps to "Approach" instead of flying directly to the runway.
- Emergency Rally Landing (Copter):
- Scenario: Mapping a large forest.
- Action: Include multiple
DO_LAND_STARTmarkers at various clearings. The drone will choose the closest one during a low-battery event.
Key Parameters
MIS_OPTIONS: Controls how the mission engine handles the landing sequence.
Key Codebase Locations
- libraries/AP_Mission/AP_Mission.cpp:2395:
get_landing_sequence_startimplementation. - ArduPlane/commands_logic.cpp: Plane-specific landing sequence handling.
DO_GO_AROUND
Summary
The DO_GO_AROUND command is an safety override used during an autonomous landing. It instructs the vehicle to immediately abort the landing sequence, climb to a safe altitude, and typically enter a loiter or wait for further instructions.
Status
Supported (ArduPlane and QuadPlane Only)
Directionality
- RX (Receive): The vehicle receives this command as a direct override from the GCS or as an automatic response to a landing sensor failure.
Mission Storage (AP_Mission)
- Packet Param 1 (Altitude): Altitude to climb to (meters).
- Mechanism: Stored as an immediate execution marker in the landing state machine.
Execution (Engineer's View)
ArduPlane Implementation
When a Go-Around is triggered:
- State Reset: The landing state machine (Flare/Touchdown detection) is immediately terminated.
- Climb-out: The plane applies full throttle and targets the "Abort Altitude" specified in the command (or the last takeoff altitude).
- Navigation: The plane typically returns to the
DO_LAND_STARTwaypoint or the waypoint immediately preceding the landing sequence to re-attempt the approach.
QuadPlane Implementation
For hybrid VTOLs, the Go-Around behavior depends on the current stage:
- Fixed-Wing Approach: Performs a standard fixed-wing abort climb.
- VTOL Descent: The vehicle transitions to a multicopter climb, rising vertically to a safe height before either loitering or transitioning back to fixed-wing flight.
Data Fields (MAVLink)
param1(Altitude): Target altitude for the abort climb.param2toparam7: Unused.
Theory: Energy vs. Safety
A Go-Around is a trade-off between Impact Risk and Stall Risk.
- The Hazard: During landing, a plane is at its lowest energy state (low speed, low altitude).
- The Reaction: ArduPilot prioritized Airspeed first. It will prioritize gaining speed over gaining altitude to ensure the aircraft remains controllable during the high-stress transition away from the ground.
Practical Use Cases
- Runway Incursion:
- Scenario: A vehicle or person enters the runway while a drone is on final approach.
- Action: The GCS operator clicks "Abort Landing," sending a
MAV_CMD_DO_GO_AROUND. The drone climbs away and circles until the runway is clear.
- Lidar/Rangefinder Glitch:
- Scenario: The landing Lidar fails 5 meters above the ground.
- Action: ArduPilot's internal safety logic triggers an automatic Go-Around to prevent a blind landing.
Key Parameters
TECS_LAND_SINK: Controls the sink rate that might trigger an automatic abort if exceeded.LAND_ABORT_THR: (Plane) Throttle level used during the abort climb.
Key Codebase Locations
- ArduPlane/commands_logic.cpp: Landing logic handler.
- libraries/AP_Landing/AP_Landing.cpp: Shared landing abort state machine.
DO_PAUSE_CONTINUE
Summary
The DO_PAUSE_CONTINUE command provides a mechanism to suspend or resume the mission's horizontal movement without changing the flight mode. It is primarily used to "Pause" the vehicle at its current location during a mission.
Status
Supported (ArduCopter and Rover)
Directionality
- RX (Receive): The vehicle receives this command as a direct override from the GCS.
Mission Storage (AP_Mission)
- Packing: This command is typically sent as an immediate command (
COMMAND_LONG), not stored in a mission. If encountered in a mission, ArduPilot treats it as a state change.
Execution (Engineer's View)
ArduCopter Implementation
In Copter, the command calls ModeAuto::pause() or ModeAuto::resume() (mode_auto.cpp).
- WPNav Interaction: The autopilot tells the
AC_WPNavlibrary to freeze the current trajectory. - Position Hold: The drone enters a "GPS Position Hold" at its current coordinates.
- Vertical Behavior: The drone maintains its current mission altitude.
- Resumption: When
Continue (1)is sent, theWPNavresumes following the path from where it was paused.
Data Fields (MAVLink)
param1(State): 0: Pause, 1: Continue.param2toparam7: Unused.
Theory: Suspending the Vector
Most flight modes are "State-based." AUTO mode is "Vector-based."
- The Pause:
DO_PAUSE_CONTINUEzero-scales the mission's velocity vector while keeping the PID loops active. - Benefit: This is safer than switching to
LOITERand back toAUTO, as the mission state machine (sequence number, jump counters, timers) remains exactly where it was.
Practical Use Cases
- Bird Incursion:
- Scenario: A pilot sees a hawk approaching the drone during a mapping grid.
- Action: The pilot clicks "Pause." The drone stops moving immediately. Once the bird leaves, the pilot clicks "Continue."
- Visual Inspection:
- Scenario: During an autonomous tower inspection, the inspector needs more time to look at a specific bracket.
- Action: Send
Pause, inspect, thenContinue.
Key Parameters
WPNAV_ACCEL: Determines how quickly the drone stops when paused.
Key Codebase Locations
- ArduCopter/mode_auto.cpp:2339: Implementation of pause/resume methods.
DO_SET_REVERSE
Summary
The DO_SET_REVERSE command tells the autopilot to change its primary direction of travel. This is used by Rovers and Boats to backup, and by Planes equipped with reversible ESCs to perform steep descents or reverse-thrust landings.
Status
Supported (ArduPlane, Rover, and Boat)
Directionality
- RX (Receive): The vehicle receives this command as part of a mission upload or as a direct command.
Mission Storage (AP_Mission)
- Reverse (Param 1):
- 0: Forward.
- 1: Reverse.
- Packing: Stored in the internal
p1field.
Execution (Engineer's View)
ArduPlane Implementation
In Plane, the command enables the use of Negative Thrust (reverse_thrust.cpp).
- ESC Configuration: Requires a bi-directional ESC (DShot or specialized PWM).
- Navigation: The autopilot maintains its orientation but reverses the throttle output.
- Use Case: Typically used for "Beta Range" aerodynamic braking during a steep approach to clear obstacles on short runways.
Rover/Sub/Boat Implementation
In Rover, this command is used to navigate "Tail First."
- Ackermann Logic: For cars, the steering logic is inverted when in reverse.
- Pivot Turns: Skid-steer rovers use this to back out of dead ends.
Data Fields (MAVLink)
param1(State): 1: Reverse, 0: Forward.param2toparam7: Unused.
Theory: Thrust Vectoring and Polarity
In standard propulsion, thrust is a scalar value $T \in [0, 1]$. DO_SET_REVERSE redefines the propulsion model as a signed value $T \in [-1, 1]$.
- The Transition: Transitioning from forward to reverse requires the motor to come to a complete stop (to prevent back-EMF spikes) before spinning in the opposite direction. ArduPilot's motor library manages this "Zero-Crossing" safely.
Practical Use Cases
- Boat Docking:
- Scenario: An autonomous boat needs to back into a slip.
- Action:
WAYPOINT (Front of Slip)->DO_SET_REVERSE (1)->WAYPOINT (Back of Slip).
- STOL (Short Takeoff and Landing):
- Scenario: A plane landing on a very short mountain strip.
- Action: After
NAV_LANDflare, the mission triggersDO_SET_REVERSE (1)to use the prop as an airbrake.
Key Parameters
USE_REV_THRUST: (Plane) Global enable for reverse thrust logic.SERVOX_REVERSED: (Rover) Hardware-level motor direction.
Key Codebase Locations
- ArduPlane/reverse_thrust.cpp: Plane-specific reverse logic.
- libraries/AP_Motors/AP_Motors_Class.cpp: Low-level bidirectional motor control.
Summary
The "Region of Interest" (ROI) commands instruction the vehicle to point its camera (and potentially its entire airframe) at a specific coordinate or object. This is a critical command for surveillance, cinematography, and inspection missions where the sensor's target is independent of the vehicle's flight path.
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)
- Mode (Param 1):
- 0: No ROI (Cancels current ROI).
- 1: ROI at next waypoint.
- 2: ROI at specific mission item.
- 3: ROI at fixed Lat/Lon location.
- Location (x, y, z): The GPS coordinates of the target (used for 195 and Mode 3).
- Mechanism: Stored as a standard location item or a mode-switch item.
Execution (Engineer's View)
Gimbal and Airframe Integration
ArduPilot handles ROI via the AP_Mount and AutoYaw libraries (mode_auto.cpp).
- 3D Geometry: The autopilot calculates the vector between the vehicle's current 3D position (GPS/INS) and the target 3D coordinate.
- Point of Aim:
- Gimbal: If a stabilized gimbal is present, ArduPilot sends Pitch and Yaw angles to the mount controller.
- Airframe: If no gimbal is present, or if the gimbal lacks a pan (yaw) axis, the multicopter will rotate its entire body (Yaw) to face the target while keeping the camera centered.
- Persistence: An ROI command is "sticky." Once set, the vehicle will continue to track that coordinate even as it flies through subsequent waypoints, until a
DO_SET_ROI_NONEcommand is encountered or a new ROI is defined.
Data Fields (MAVLink)
param1(Mode): Selection between location, waypoint, or cancel.param2(Item #): Mission index if mode=2.x(Latitude): Target latitude.y(Longitude): Target longitude.z(Altitude): Target altitude.
Theory: Trigonometry of Tracking
To point the camera, the autopilot solves for the Azimuth ($\psi$) and Elevation ($\\theta$) angles relative to North:
$$ \psi = \operatorname{atan2}( \Delta \text{East}, \Delta \text{North} ) $$
$$ \theta = \operatorname{atan2}( \Delta \text{Alt}, \sqrt{\Delta \text{North}^2 + \Delta \text{East}^2} ) $$
The EKF solution provides high-frequency updates to these angles to ensure the camera remains locked even during aggressive vehicle maneuvering.
Practical Use Cases
- POI (Point of Interest) Orbit:
- Scenario: Filming a lighthouse from a circling drone.
- Action:
DO_SET_ROI (Lighthouse)->NAV_LOITER_TURNS. The drone circles while the gimbal automatically tilts and pans to keep the lighthouse in the center of the frame.
- Static Security Watch:
- Scenario: A plane is patrolling a perimeter but needs to keep its camera locked on a specific gate.
- Action:
DO_SET_ROI (Gate)followed by a patrol mission.
Key Parameters
MNT1_TYPE: Defines the type of gimbal hardware.WP_YAW_BEHAVE: Must be aware that ROI will override the default "Face Next Waypoint" behavior.
Key Codebase Locations
- ArduCopter/mode_auto.cpp:1975:
do_roiimplementation. - libraries/AP_Mount/AP_Mount.cpp: Core tracking mathematics.
Summary
The DO_DIGICAM_CONFIGURE and DO_DIGICAM_CONTROL commands are the legacy interface for interacting with onboard digital cameras. While modern systems prefer the MAVLink Camera Protocol (v2), these commands remain vital for supporting a vast array of existing hardware, including CHDK-enabled Canon cameras, Sony NEX series via IR/Multi-port, and simple PWM-triggered DSLRs.
Status
Legacy / Supported (All Vehicles with AP_Camera enabled)
Directionality
- RX (Receive): The vehicle receives this command as part of a mission upload or as a direct command.
Mission Storage (AP_Mission)
ArduPilot uses a highly efficient packing strategy to store these complex commands:
- 202 (Configure): Stored in the
digicam_configurestruct. Includes Shutter Speed, Aperture, and ISO. - 203 (Control): Stored in the
digicam_controlstruct. Includes Zoom absolute, Zoom step, and Focus locking. - Packing: Both utilize the standard 15-byte mission storage limit by bit-packing smaller values where possible.
Execution (Engineer's View)
Triggering and Handshaking
The commands are routed through the AP_Camera library (AP_Camera.cpp).
- Direct Shutter: If
Shooting Command (Param 5)is set to 1, the autopilot triggers the shutter. - Focus Lock: ArduPilot supports a "Half-press" logic for cameras that require focusing before the final capture.
- Engine Cut-off: A unique feature of
DO_DIGICAM_CONFIGUREis the Engine Cut-off Time (Param 7). For gas-powered vehicles with extreme vibration, the autopilot can momentarily kill the engine or reduce throttle during the capture to ensure a blur-free image.
Data Fields (MAVLink)
DO_DIGICAM_CONTROL (203)
param1(Session): 0:Ignore, 1:Show Lens, 2:Hide Lens.param2(Zoom): Absolute position.param3(Step): Zoom step (offset).param4(Focus): 0:Ignore, 1:Lock, 2:Unlock.param5(Shot): 1:Take picture.
Theory: The Latency of Mechanical Shutters
Unlike digital sensors, mechanical shutters have Trigger Latency ($\Delta t_{shutter}$).
- The Drift: If a drone is flying at 20 m/s and the shutter has a 200ms lag, the photo will be taken 4 meters past the intended coordinate.
- ArduPilot Compensation: High-end configurations use the
CAM_FEEDBACK_PIN(Hot Shoe). When the shutter actually fires, the camera sends a signal back to the flight controller, which then captures the exact GPS/IMU state for that microsecond, ensuring sub-centimeter mapping accuracy.
Practical Use Cases
- Vibration-Sensitive Long Exposure:
- Scenario: A high-altitude plane taking photos in low light.
- Action:
DO_DIGICAM_CONFIGURE (Engine Cut-off: 0.5s). The motor stops for half a second, the photo is taken in still air, and the motor restarts automatically.
- Canon CHDK Integration:
- Scenario: Using a cheap Canon Point-and-Shoot for mapping.
- Action:
DO_DIGICAM_CONTROLsends the PWM pulse required by the CHDK script to trigger the capture.
Key Parameters
CAM_TRIGG_TYPE: Must be set toRelayorPWM.CAM_DURATION: The length of the shutter pulse.
Key Codebase Locations
- libraries/AP_Mission/AP_Mission_Commands.cpp:115: Command parsing.
- libraries/AP_Camera/AP_Camera.cpp: Core execution logic.
DO_MOUNT_CONTROL
Summary
The DO_MOUNT_CONTROL command allows the mission script to set specific Pitch, Roll, and Yaw angles for a camera mount or antenna gimbal. Unlike ROI (which targets a coordinate), MOUNT_CONTROL targets specific body-relative or Earth-relative angles.
Status
Supported (All Vehicles)
Directionality
- RX (Receive): The vehicle receives this command as part of a mission upload or as a direct command.
Mission Storage (AP_Mission)
- Pitch (Param 1): Angle in degrees.
- Roll (Param 2): Angle in degrees.
- Yaw (Param 3): Angle in degrees.
- Mechanism: Stored in the
mount_controlcontent struct.
Execution (Engineer's View)
Controlling the Mount
ArduPilot directs these commands to the AP_Mount library (AP_Mount.cpp).
- Angle Mapping: The command defines the target orientation.
- Mount Mode: Encountering this command typically switches the mount to
MAVLINK_TARGETINGmode. - Airframe Yaw Integration: A critical feature in ArduCopter: If the vehicle has a camera mount that does not support a pan (Yaw) axis (e.g., a 2-axis gimbal), ArduPilot will rotate the entire vehicle airframe to achieve the requested Yaw angle (mode_auto.cpp).
Data Fields (MAVLink)
param1(Pitch): Target pitch angle (deg).param2(Roll): Target roll angle (deg).param3(Yaw): Target yaw angle (deg).param7(Mode): Selection between angle and rate control (if supported).
Theory: Body-Relative vs. Earth-Relative
- Body-Relative: The angles are relative to the drone's nose. If the drone turns 90 degrees, the camera turns 90 degrees.
- Earth-Relative (North-Up): The camera locks onto a compass heading. If the drone turns, the gimbal compensates to stay pointed North.
- ArduPilot Default:
MAV_CMD_DO_MOUNT_CONTROLis typically interpreted as Earth-Relative for Pitch (tilt) and Yaw (pan), but Body-Relative for Roll.
Practical Use Cases
- Vertical Mapping (Nadir):
- Scenario: A surveyor needs the camera to point straight down for the entire flight.
- Action:
DO_MOUNT_CONTROL (Pitch: -90, Roll: 0, Yaw: 0).
- Forward Scouting:
- Scenario: A search and rescue drone needs to look 15 degrees below the horizon and 45 degrees to the right to scan a coastline.
- Action:
DO_MOUNT_CONTROL (Pitch: -15, Yaw: 45).
Key Parameters
MNT1_TYPE: Enables the gimbal driver.MNT1_PITCH_MIN/MAX: Defines the mechanical limits to prevent servo damage.
Key Codebase Locations
- libraries/AP_Mount/AP_Mount.cpp:555: Command intake.
- ArduCopter/mode_auto.cpp:1987: Yaw-override logic for 2-axis gimbals.
DO_SET_CAM_TRIGG_DIST
Summary
The DO_SET_CAM_TRIGG_DIST command enables automatic camera triggering based on the 2D distance traveled by the vehicle. This is the primary mechanism for aerial mapping (photogrammetry), ensuring consistent image overlap regardless of groundspeed fluctuations caused by wind.
Status
Supported (All Vehicles)
Directionality
- RX (Receive): The vehicle receives this command as part of a mission upload or as a direct command.
Mission Storage (AP_Mission)
- Distance (Param 1): The distance in meters between triggers.
- Shutter (Param 2): Shutter integration time (typically unused by ArduPilot, which relies on hardware-specific drivers).
- Trigger Once (Param 3): If set to 1, the camera triggers immediately upon receiving the command.
- Mechanism: Stored in the
cam_trigg_distcontent struct withinAP_Mission.
Execution (Engineer's View)
Triggering Logic
The command utilizes the AP_Camera library (AP_Camera.cpp).
- Distance Threshold: The autopilot records the GPS position of the last trigger.
- Continuous Check: Every loop, it calculates the 2D horizontal distance ($d$) from the last trigger point.
- Firing: When $d \ge \text{TriggDist}$, the autopilot sends a signal to the camera shutter (via Relay, PWM, MAVLink, or DroneCAN) and updates the last-trigger position.
- Disabling: Sending this command with
Param 1 = 0disables automatic triggering.
Data Fields (MAVLink)
param1(Distance): Meters between shots. 0 to disable.param2(Shutter): Integration time (ms).param3(Trigger): 1 to trigger one shot immediately.param4toparam7: Unused.
Theory: Photogrammetry Overlap
Mapping accuracy depends on Frontal Overlap ($O_f$). For a camera with sensor height $H_s$ and focal length $f$, flying at altitude $A$ with a groundspeed $V_g$:
- Ground Sample Distance (GSD): The real-world size of one pixel.
- Trigger Distance ($D$):
$$ D = \text{Footprint}_{height} \cdot (1 - O_f) $$
UsingDO_SET_CAM_TRIGG_DISTensures that even if the drone slows down when flying into a headwind, the images are still taken at the mathematically correct spatial intervals to maintain the required $O_f$ for 3D reconstruction.
Practical Use Cases
- Ortho-Mosaic Mapping:
- Scenario: Mapping a farm at 80% overlap.
- Action: Mission starts with
DO_SET_CAM_TRIGG_DIST (20m). The drone flies the survey grid, and the camera fires every 20 meters.
- Corridor Inspection:
- Scenario: Inspecting a pipeline.
- Action:
DO_SET_CAM_TRIGG_DIST (50m)ensures high-resolution coverage without filling the SD card with redundant images.
Key Parameters
CAM_TRIGG_TYPE: Defines if the trigger is via Relay, PWM, or MAVLink.CAM_DURATION: How long the shutter signal is held high.
Key Codebase Locations
- libraries/AP_Camera/AP_Camera.cpp:291: Implementation of distance-based triggering.
- ArduCopter/mode_auto.cpp: Integration with the mission engine.
DO_FENCE_ENABLE
Summary
The DO_FENCE_ENABLE command allows the mission script to dynamically enable or disable the vehicle's Geofence system. This is particularly useful for missions where a drone must transition from a restricted "test area" into an open flight corridor, or vice-versa.
Status
Supported (All Vehicles)
Directionality
- RX (Receive): The vehicle receives this command as part of a mission upload or as a direct command from the GCS.
Mission Storage (AP_Mission)
- Enable (Param 1):
- 0: Disable all fences.
- 1: Enable all fences.
- 2: Disable "Floor" only (Altitude minimum).
- Packing: Stored in the internal
p1field.
Execution (Engineer's View)
Dynamic Fencing Logic
Execution is handled by the AC_Fence library (AC_Fence.cpp).
- State Change: The command updates the internal fence enable bitmask.
- Safety Verification: If enabling the fence, the autopilot immediately checks the current vehicle position against the fence boundaries.
- Breech Handling: If the vehicle is already outside the boundary when the fence is enabled via mission command, the autopilot will immediately trigger a Fence Failsafe (typically RTL or Land).
Data Fields (MAVLink)
param1(State): 0: Disable, 1: Enable, 2: Disable Floor.param2toparam7: Unused.
Theory: Adaptive Airspace
Dynamic fencing enables Adaptive Airspace management.
- Corridors: A mission can be "fenced" into a narrow pipe for a BVLOS transit. Once it reaches a designated high-altitude workspace, the
DO_FENCE_ENABLE (Disable)command can be used to allow for freer movement during manual inspection tasks. - Payload Protection: A drone carrying hazardous material might enable a very tight fence only during the transport phase, then disable it for recovery once the payload is released.
Practical Use Cases
- Transitioning to Open Sea:
- Scenario: A search-and-rescue drone launches from a crowded beach.
- Action: Mission starts with Geofence Enabled. Once the drone is 500m offshore,
DO_FENCE_ENABLE (Disable)is triggered to allow it to scan a wide area without nuisance alerts.
- Autonomous Testing:
- Scenario: Testing a new Lua script.
- Action: The script is only allowed to run while the drone is inside a "Safety Box." The mission enables the box before starting the script and disables it upon completion.
Key Parameters
FENCE_ENABLE: Global master switch for fencing.FENCE_ACTION: Determines what happens when a fence is breached (RTL, Land, etc.).
Key Codebase Locations
- libraries/AC_Fence/AC_Fence.cpp: Core fence logic.
- ArduCopter/mode_auto.cpp:1008: Mission command intake.
DO_PARACHUTE
Summary
The MAV_CMD_DO_PARACHUTE command triggers or manages the vehicle's emergency recovery parachute. In a mission context, this is rarely used for standard recovery (which is usually an RTL) but is vital for "Total Safety" missions or testing environments where a soft impact must be guaranteed at a specific stage.
Status
Supported (All Vehicles)
Directionality
- RX (Receive): The vehicle receives this command as part of a mission upload or as a direct "PANIC" command from the GCS.
Mission Storage (AP_Mission)
- Action (Param 1):
- 0: Disable parachute release.
- 1: Enable parachute (Armed).
- 2: Release parachute (Fire immediately).
- Packing: Stored in the internal
p1field.
Execution (Engineer's View)
Emergency Logic
The command utilizes the AP_Parachute library (AP_Parachute.cpp).
- Safety Interlocks: If
Release (2)is commanded, the autopilot instantly stops all flight motors (ArduCopter/GCS_Mavlink.cpp:978). This prevents the parachute lines from tangling in the props. - Deployment: A high signal is sent to the assigned parachute relay or servo.
- Logging: A "PARACHUTE" event is recorded in the DataFlash log.
Data Fields (MAVLink)
param1(Action): 0: Disable, 1: Enable, 2: Release.param2toparam7: Unused.
Theory: The Point of No Return
Parachute deployment is a Terminating Event.
- Motor Inhibition: Once a parachute is fired, ArduPilot will not allow the motors to restart until the vehicle has been disarmed and rebooted.
- Altitude Constraint: Parachutes require a minimum altitude to inflate. ArduPilot uses the
CHUTE_ALT_MINparameter to prevent deployment if the vehicle is too low (which could lead to a prop-entanglement before inflation).
Practical Use Cases
- Sensitive Equipment Recovery:
- Scenario: A drone is carrying a $100k prototype sensor.
- Action: At the end of the mission, instead of a standard landing, the mission triggers
DO_PARACHUTE (Release)over a designated soft-target area to ensure the sensor is never subjected to a landing impact.
- Safety Drills:
- Scenario: Testing a new airframe.
- Action: The GCS "Kill Switch" is mapped to
DO_PARACHUTE (Release).
Key Parameters
CHUTE_ENABLED: Global master switch.CHUTE_TYPE: Defines if the trigger is a Relay or Servo.CHUTE_SERVO_ON: The PWM value used to fire the chute.
Key Codebase Locations
- libraries/AP_Parachute/AP_Parachute.cpp: Core deployment logic.
- ArduCopter/GCS_Mavlink.cpp:978: Critical motor-kill logic.
DO_INVERTED_FLIGHT
Summary
The DO_INVERTED_FLIGHT command instructions the autopilot to fly the aircraft upside-down. This is primarily used in ArduPlane for aerobatics or specialized flight maneuvers.
Status
Supported (ArduPlane Only)
Directionality
- RX (Receive): The vehicle receives this command as part of a mission upload or as a direct command from the GCS.
Mission Storage (AP_Mission)
- Inverted (Param 1):
- 0: Normal flight (Upright).
- 1: Inverted flight (Upside-down).
- Packing: Stored in the internal
p1field.
Execution (Engineer's View)
ArduPlane Implementation
In Plane, the command updates the auto_state.inverted_flight flag (commands_logic.cpp).
- Attitude Target: When inverted flight is enabled, the AHRS (Attitude and Heading Reference System) redefines the Roll target as 180 degrees.
- Controller Inversion: The PID controllers for Aileron and Elevator must account for the inverted state.
- Pitch: Pulling "Up" on the stick while inverted will cause the aircraft to move towards the ground.
- Self-Leveling: The autopilot automatically handles the inversion of these vectors to ensure that standard "Fly-By-Wire" (FBW) controls remain intuitive for the pilot (if in a semi-autonomous mode) or consistent for the mission engine.
- Oil/Fuel Handling: This command is only recommended for airframes with inverted-flight capable propulsion systems (e.g., fuel-injected engines with header tanks or electric systems).
Data Fields (MAVLink)
param1(State): 0: Normal, 1: Inverted.param2toparam7: Unused.
Theory: The Lift Vector Inversion
In normal flight, lift ($L$) acts upwards to oppose gravity ($W$).
$$ L = W $$
In inverted flight, the aircraft must maintain a negative angle of attack ($\alpha$) to generate lift "upwards" relative to the Earth, even though the wing is upside down.
$$ L_{inverted} = \frac{1}{2} \rho v^2 S C_{L, inverted} $$
ArduPilot's navigation controller (L1) calculates the required bank angle to maintain the ground track while accounting for the reduced lift efficiency of most non-symmetrical airfoils when flying inverted.
Practical Use Cases
- Aerobatic Display:
- Scenario: An autonomous drone show involving complex maneuvers.
- Action:
WAYPOINT (A)->DO_INVERTED_FLIGHT (1)->WAYPOINT (B). The plane rolls 180 degrees and flies the segment between A and B upside-down.
- Sensor Calibration:
- Scenario: Calibrating an IMU or magnetometer by exposing it to symmetrical forces.
- Action: Flying a specific leg upright, then repeating it inverted to cancel out bias.
Key Parameters
ROLL_LIMIT_DEG: Still applies while inverted.
Key Codebase Locations
- ArduPlane/commands_logic.cpp:134: Mission command intake.
- ArduPlane/attitude.cpp: High-level attitude control logic for inversion.
DO_GRIPPER
Summary
The DO_GRIPPER command manages the state of a mechanical cargo gripper (claw, magnetic latch, or drop-hook). This is a dedicated actuator command that is safer and more descriptive than a raw DO_SET_SERVO because it integrates with the autopilot's landing and failsafe logic.
Status
Supported (All Vehicles)
Directionality
- RX (Receive): The vehicle receives this command as part of a mission upload or as a direct command.
Mission Storage (AP_Mission)
- Instance (Param 1): The gripper ID (ArduPilot typically supports 1 primary gripper).
- Action (Param 2):
- 0: Release (Open).
- 1: Grab (Close).
- Packing: Stored in the internal
grippercontent struct.
Execution (Engineer's View)
Gripper Logic
Execution is handled by the AP_Gripper library (AP_Gripper.cpp).
- Safety Interlocks: ArduPilot can be configured to prevent a "Release" action if the vehicle is not within a safe altitude range or if a "Touchdown" has not been detected.
- Actuator Type:
AP_Grippersupports multiple hardware backends:- Servo: Moves a servo to a specific PWM (Open/Closed).
- EPM (Electro-Permanent Magnet): Sends a pulse to flip the magnetic polarity (no power required to hold).
- Completion: The mission script advances immediately after the command is sent to the actuator; it does not wait for a "sensor confirmed closed" signal unless combined with a
CONDITION_DELAY.
Data Fields (MAVLink)
param1(ID): Gripper instance number.param2(Action): 0: Release, 1: Grab.param3toparam7: Unused.
Theory: Energy States of Actuators
- Standard Servos: Require continuous power to maintain a "Grab" state against a heavy load. This causes heat and battery drain.
- EPMs: Use a high-current pulse to re-align the magnetic domains of an Alnico core. Once "Grabbed," the payload is held by a permanent magnetic field with zero power consumption. This is the preferred gripper type for long-endurance ArduPilot missions.
Practical Use Cases
- Automated Package Delivery:
- Scenario: A drone delivering a box to a backyard.
- Action:
NAV_WAYPOINT->NAV_PAYLOAD_PLACE->DO_GRIPPER (Release).
- Sample Collection:
- Scenario: A rover picking up a rock.
- Action:
DO_GRIPPER (Grab)once the rover is over the target.
Key Parameters
GRIP_ENABLE: Global switch.GRIP_TYPE: Selection between Servo and EPM.GRIP_CAN_ON_PWM: The PWM value used to Close the gripper.
Key Codebase Locations
- libraries/AP_Gripper/AP_Gripper.cpp: Core hardware interface.
- ArduCopter/mode_auto.cpp: Mission integration.
DO_AUTOTUNE_ENABLE
Summary
The DO_AUTOTUNE_ENABLE command triggers ArduPilot's automated PID tuning process during a mission. This allows the vehicle to optimize its control gains in real-time while flying a specific leg of a mission, which is useful for airframes whose dynamics change significantly with different payloads.
Status
Supported (ArduPlane Only)
Directionality
- RX (Receive): The vehicle receives this command as part of a mission upload or as a direct command from the GCS.
Mission Storage (AP_Mission)
- Enable (Param 1):
- 0: Disable Autotune.
- 1: Enable Autotune.
- Packing: Stored in the internal
p1field.
Execution (Engineer's View)
Tuning Logic
The command utilizes the AP_AutoTune library (GCS_Mavlink.cpp:1207).
- Safety Verification: The aircraft must be in a stable flight state (typically FBWA or Cruise) for Autotune to be effective.
- Perturbation: When enabled, the autopilot injects small, controlled step-inputs into the Roll and Pitch axes.
- Analysis: It monitors the vehicle's response (Rate and Acceleration) to calculate the ideal P, I, and D gains.
- Completion: The mission advances immediately. The Autotune process runs in the background. It is common to follow this command with a long, straight
WAYPOINTto give the tuner enough time to converge.
Data Fields (MAVLink)
param1(State): 0: Disable, 1: Enable.param2toparam7: Unused.
Theory: System Identification
AutoTune is a form of Online System Identification.
- Excitation: The step-inputs "excite" the airframe's natural frequencies.
- Damping Ratio: The algorithm looks for the "Overshoot" and "Settling Time" to ensure the resulting PID gains provide a damping ratio ($\zeta$) near 0.707 (Critically Damped).
- Risk: If Autotune is enabled on a poorly balanced or structurally weak airframe, the perturbations can trigger oscillations. ArduPilot's tuner includes "divergence protection" to automatically abort if the aircraft's attitude becomes unstable.
Practical Use Cases
- Post-Payload Calibration:
- Scenario: A plane drops a heavy 2kg sensor mid-flight.
- Action: The mission triggers
DO_AUTOTUNE_ENABLE (1)on the return leg to re-calibrate the PIDs for the now much lighter (and potentially differently balanced) airframe.
- Maiden Flight Script:
- Scenario: Automating the first flight of a new aircraft.
- Action: Mission includes a 5km straight leg with Autotune enabled to ensure a perfect tune before the first landing.
Key Parameters
AUTOTUNE_LEVEL: Defines how "aggressive" the resulting tune should be.AUTOTUNE_AXES: Selection of which axes to tune (Roll, Pitch, Yaw).
Key Codebase Locations
- ArduPlane/GCS_Mavlink.cpp:1207: Autotune trigger logic.
- libraries/AP_AutoTune/AP_AutoTune.cpp: The core gain-calculation engine.
DO_SET_RESUME_REPEAT_DIST
Summary
The DO_SET_RESUME_REPEAT_DIST command defines a "Rewind Distance" for mission resumption. If a mission is interrupted (e.g., due to a mode change or a battery failsafe), and then resumed, the autopilot will not simply fly to the next waypoint. Instead, it will backtrack along the mission path by the specified distance before continuing forward.
Status
Supported (All Vehicles)
Directionality
- RX (Receive): The vehicle receives this command as part of a mission upload.
Mission Storage (AP_Mission)
- Distance (Param 1): The backtrack distance in meters.
- Packing: Stored in the internal
_repeat_distvariable in theAP_Missionlibrary.
Execution (Engineer's View)
Resumption Logic
ArduPilot handles this command within the AP_Mission::resume() function (AP_Mission.cpp).
- Interrupt Discovery: The autopilot tracks the last successful waypoint passed (
LAST_WP_PASSED). - Rewind Calculation: If
_repeat_dist > 0, the autopilot callscalc_rewind_pos().- It looks at the segment between the last WP and the current WP.
- It calculates a 3D coordinate that is
Param1meters backwards along that segment.
- Path Re-entry: The vehicle first flies to this calculated rewind point and then resumes the original mission track.
Data Fields (MAVLink)
param1(Distance): Rewind distance in meters.param2toparam7: Unused.
Theory: The Overlap Requirement
In mapping and sensor missions, an interrupt usually results in a "data gap."
- The Hazard: Most autopilots resume at the next waypoint, leaving a section of the mission un-scanned.
- The Solution: By setting a repeat distance (e.g., 50 meters), the pilot ensures that the drone "re-scans" the last section of the previous leg, providing a overlap buffer that guarantees data continuity for photogrammetry or LiDAR processing.
Practical Use Cases
- Battery Swap Recovery:
- Scenario: A mapping drone triggers a low-battery RTL in the middle of a 1km leg.
- Action: The mission includes
DO_SET_RESUME_REPEAT_DIST (100m). After the pilot swaps the battery and clicks "Resume," the drone flies back to the point 100m before it left the track, ensuring the map has no holes.
- Loss of Signal (LOS) Buffer:
- Scenario: A drone is inspecting a long bridge and loses telemetry.
- Action: Backtracking ensures that any missed photos are re-taken upon reconnection.
Key Parameters
MIS_RESTART: Affects whether the mission resets entirely or supports this resume logic.
Key Codebase Locations
- libraries/AP_Mission/AP_Mission.cpp:158:
resumelogic and rewind calculation.
DO_SPRAYER
Summary
The DO_SPRAYER command provides mission-level control for agricultural liquid sprayers. It is used to enable or disable the pump and manage the flow rate based on the vehicle's ground speed to ensure even chemical application.
Status
Supported (ArduCopter and ArduPlane with AC_Sprayer enabled)
Directionality
- RX (Receive): The vehicle receives this command as part of a mission upload or as a direct command.
Mission Storage (AP_Mission)
- Enable (Param 1):
- 0: Disable Sprayer (Pump Off).
- 1: Enable Sprayer (Pump On).
- Packing: Stored in the internal
p1field.
Execution (Engineer's View)
Sprayer Control Logic
Execution is handled by the AC_Sprayer library (AC_Sprayer.cpp).
-
Velocity Compensation: One of the most advanced features of
AC_Sprayeris speed-scaling. The pump's PWM output is modulated based on groundspeed ($V_g$).$$ \text{PWM}_{out} = \text{BaseFlow} \cdot \left( \frac{V_{ground}}{V_{nominal}} \right) $$
-
Spin-up/down: The controller manages the ramp-up time for the pump to prevent motor surges.
-
Automatic Cutoff: ArduPilot automatically disables the sprayer if the vehicle comes to a stop or enters a failsafe state, preventing chemical pooling.
Data Fields (MAVLink)
param1(State): 0: Disable, 1: Enable.param2toparam7: Unused.
Theory: Linear Application Rate
In precision agriculture, the goal is to apply a specific volume of liquid per unit of area ($L/Ha$).
- The Challenge: Drones decelerate at waypoints. If the pump stayed at a constant speed, the area near the waypoint would receive a massive overdose of chemicals.
- The Solution: The
AC_Sprayerlibrary integrates with the navigation controller to vary the pump speed in real-time, maintaining a constant Linear Application Rate regardless of flight dynamics.
Practical Use Cases
- Crop Mapping & Spraying:
- Scenario: Spraying a rectangular field.
- Action:
WAYPOINT (A)->DO_SPRAYER (1)->WAYPOINT (B). The drone flies the transect, spraying only between A and B, and adjusting the flow as it accelerates out of A and decelerates into B.
- Mosquito Abatement:
- Scenario: Targeting a specific swampy area.
- Action: Mission uses ROI to circle the swamp while
DO_SPRAYERmanages the payload.
Key Parameters
SPRAY_ENABLE: Global switch.SPRAY_PUMP_RATE: Nominal pump speed (%).SPRAY_SPEED_MIN: Groundspeed below which the pump is shut off.
Key Codebase Locations
- libraries/AC_Sprayer/AC_Sprayer.cpp: Flow-scaling and pump control.
DO_SEND_SCRIPT_MESSAGE
Summary
The DO_SEND_SCRIPT_MESSAGE command provides a bridge between the static Mission Engine and ArduPilot's dynamic Lua Scripting environment. It allows a mission to pass numeric data to a running script, which can then perform complex logic, such as changing flight parameters, interacting with custom hardware, or modifying the mission on-the-fly.
Status
Supported (All Vehicles with AP_Scripting enabled)
Directionality
- RX (Receive): The vehicle receives this command as part of a mission upload.
Mission Storage (AP_Mission)
- Target (Param 1): An ID used by the Lua script to identify the specific message.
- Values (Param 2-4): Three numeric values (p1, p2, p3) passed to the script.
- Packing: Stored in the
scriptingcontent struct.
Execution (Engineer's View)
Scripting Bridge
The command utilizes the AP_Scripting library (AP_Scripting.cpp).
- Event Generation: When the mission reaches this item, the autopilot generates a
MISSION_ITEM_REACHEDevent internally. - Script Polling: A Lua script running on the flight controller uses the
mission:get_last_script_message()binding to retrieve the data. - Action: The script parses the
Param 1ID and executes the corresponding custom code. - Completion: The mission advances immediately. The "wait" for the script to finish must be handled manually via a
CONDITION_DELAYor a script-controlled mission override.
Data Fields (MAVLink)
param1(ID): Message identifier.param2(p1): First numeric parameter.param3(p2): Second numeric parameter.param4(p3): Third numeric parameter.param5toparam7: Unused.
Theory: Extending the State Machine
Missions are typically limited to the commands defined in the MAVLink spec. DO_SEND_SCRIPT_MESSAGE transforms the Mission Engine into a Programmable Logic Controller (PLC).
- Custom Payloads: A drone carrying a non-standard sensor (e.g., a spectral scanner) can use this command to tell a Lua script to start a specific calibration routine.
- External Comms: A script can listen for this message and then send a custom HTTP/UDP packet to an onboard companion computer or a cloud server.
Practical Use Cases
- Dynamic Parameter Tuning:
- Scenario: A plane needs different PID gains for a low-altitude "nap-of-the-earth" segment.
- Action:
DO_SEND_SCRIPT_MESSAGE (ID: 10, p1: 1)triggers a Lua script to callparam:set('ATC_RAT_RLL_P', 0.15).
- Robotic Integration:
- Scenario: A drone landing on a moving rover needs to "Handshake" with the rover's local network.
- Action: Mission triggers the message, and the script handles the custom socket communication.
Key Parameters
SCR_ENABLE: Enables the Lua scripting engine.SCR_VM_I_COUNT: Instruction count (performance) for scripts.
Key Codebase Locations
- libraries/AP_Scripting/AP_Scripting.cpp: Lua binding implementation.
- ArduCopter/mode_auto.cpp: Command-to-script event routing.
DO_AUX_FUNCTION
Summary
The DO_AUX_FUNCTION command allows a mission to trigger any of ArduPilot's numerous "Auxiliary Functions." These are the same functions typically assigned to physical switches on a radio transmitter (e.g., "Save Waypoint," "Camera Trigger," "Arm/Disarm"). This command effectively allows the mission to "flick a virtual switch."
Status
Supported (All Vehicles)
Directionality
- RX (Receive): The vehicle receives this command as part of a mission upload or as a direct command.
Mission Storage (AP_Mission)
- Function (Param 1): The ID of the auxiliary function (e.g., 7 = Save Waypoint).
- Switch Position (Param 2):
- 0: Low (Off).
- 1: Middle.
- 2: High (On).
- Packing: Stored in the
auxfunctioncontent struct.
Execution (Engineer's View)
Universal Switch Logic
Execution is handled by the RC_Channel library's auxiliary function dispatcher.
- Virtual Input: ArduPilot treats the mission command as a virtual RC channel.
- Mapping: The
Param 1value is matched against the list of internal functions (e.g.,AUXSW_MOTOR_INTERLOCK,AUXSW_GRIPPER). - Action: The autopilot executes the code associated with that switch transition (e.g., if set to
High, it runs theon_switch_high()method for that function).
Data Fields (MAVLink)
param1(Function): Auxiliary function ID.param2(Position): 0: Low, 1: Mid, 2: High.param3toparam7: Unused.
Theory: Abstracted Logic
DO_AUX_FUNCTION represents the ultimate in Logic Abstraction.
- The Power: ArduPilot has over 100 aux functions. Instead of creating 100 individual mission commands, this one command provides access to all of them.
- Unified Control: It ensures that whether an action is triggered by a human on a radio, a GCS button, or an autonomous mission, it always calls the same verified block of C++ code.
Practical Use Cases
- Waypoint Saving:
- Scenario: A pilot is flying a survey and wants the mission to automatically record its own progress.
- Action:
DO_AUX_FUNCTION (Function: 7, Position: 2).
- Emergency Stop (Motor Interlock):
- Scenario: A high-risk mission segment (e.g., flying through a tunnel).
- Action: A script can inject
DO_AUX_FUNCTION (Function: 32, Position: 0)to instantly kill the motors if a failure is detected.
Key Parameters
RCx_OPTION: Used to identify the ID of specific functions.
Key Codebase Locations
- libraries/RC_Channel/RC_Channel.cpp: Auxiliary function dispatcher.
- libraries/AP_Mission/AP_Mission.cpp: Command-to-RC-logic routing.
DO_GUIDED_LIMITS
Summary
The DO_GUIDED_LIMITS command sets safety constraints for Guided Mode. It defines the maximum time and distance an external controller (e.g., an onboard companion computer or an GCS script) is allowed to control the vehicle before the autopilot automatically intervenes and terminates the command.
Status
Supported (All Vehicles)
Directionality
- RX (Receive): The vehicle receives this command as part of a mission upload or as a direct setup command.
Mission Storage (AP_Mission)
- Time Limit (Param 1): Max time in seconds for external control.
- Alt Min (Param 2): Minimum altitude (meters).
- Alt Max (Param 3): Maximum altitude (meters).
- Horiz Max (Param 4): Maximum horizontal distance from the command start point (meters).
- Packing: Stored in the
guided_limitscontent struct.
Execution (Engineer's View)
Safety Buffer Logic
ArduPilot handles this in the Guided flight mode logic (mode_auto.cpp).
- Handover: When the mission reaches
NAV_GUIDED_ENABLE(or enters Guided mode via MAVLink), these limits are activated. - Continuous Monitoring: Every loop, the autopilot checks:
- Time:
millis() - start_time > Param1. - Altitude:
current_alt < Param2ORcurrent_alt > Param3. - Radius:
2D_Distance(start_pos, current_pos) > Param4.
- Time:
- Failsafe: If any limit is breached, the autopilot instantly terminates Guided mode and typically returns to the mission or enters a failsafe state (RTL).
Data Fields (MAVLink)
param1(Time): Max execution time (s).param2(Alt Min): Min altitude (m).param3(Alt Max): Max altitude (m).param4(Radius): Max horizontal distance (m).
Theory: The Sandbox Principal
DO_GUIDED_LIMITS implements a Sandbox for external intelligence.
- The Problem: Companion computer scripts (running ROS or Python) can crash or "go rogue" due to bugs.
- The Solution: The flight controller (which is the ultimate arbiter of safety) creates a "Virtual Box" and a "Watchdog Timer." The companion computer is free to experiment inside the box, but the flight controller will "reel it back in" the moment it tries to exit the safe boundaries.
Practical Use Cases
- AI Landing Research:
- Scenario: Testing a new vision-based landing algorithm on a Raspberry Pi.
- Action:
DO_GUIDED_LIMITS (Time: 30s, Alt Min: 2m). If the AI fails to land within 30 seconds or drops below 2 meters unexpectedly, the flight controller takes over.
- GCS "Follow-Me":
- Scenario: A tablet app is commanding the drone to follow a cyclist.
- Action: Use horizontal limits to ensure the drone never wanders too far from the cyclist if the app loses the tracking lock.
Key Parameters
GUID_OPTIONS: Can affect how Guided mode behaves when limits are hit.
Key Codebase Locations
- ArduCopter/mode_auto.cpp:785: Mission command intake.
- ArduCopter/mode_guided.cpp: Limit enforcement logic.
DO_ENGINE_CONTROL
Summary
The DO_ENGINE_CONTROL command provides a mission-level interface for Internal Combustion Engines (ICE). It is used to start or stop the engine, manage "Cold Start" procedures, and control height-based delays for engine engagement. This is critical for high-endurance large-scale drones and hybrid power systems.
Status
Supported (ArduPlane and ArduCopter with ICE enabled)
Directionality
- RX (Receive): The vehicle receives this command as part of a mission upload or as a direct command.
Mission Storage (AP_Mission)
- Start/Stop (Param 1): 1: Start Engine, 0: Stop Engine.
- Cold Start (Param 2): 1: Cold Start (enables extended cranking/glow plug time), 0: Warm Start.
- Height Delay (Param 3): Height in meters to wait before attempting a start (unit converted to cm in storage).
- Options (Param 4): Bitmask for start behavior (e.g., Allow start while disarmed).
- Mechanism: Stored in the internal
do_engine_controlcontent struct.
Execution (Engineer's View)
ICE State Machine
The command is handled by the AP_ICEngine library.
- Cranking Logic: When
Start (1)is commanded, the autopilot manages the Starter Motor (via a Relay or ESC) and Ignition system. - Telemetry Check: ArduPilot monitors the engine RPM via an onboard sensor. The "Start" is only considered successful when the RPM exceeds the
ICE_START_RPM. - Kill Switch: The
Stop (0)command instantly terminates the ignition/fuel relay, ensuring a rapid shutdown for safety or post-mission power-down. - VTOL Integration: In hybrid QuadPlanes, this command can be used to start the generator engine once the aircraft is clear of the ground and transitioning to fixed-wing flight.
Data Fields (MAVLink)
param1(Start): 1: Start, 0: Stop.param2(Cold): 1: Cold Start, 0: Warm.param3(Height): Delay start until this height (meters).param4(Options): Bit 0: Allow start while disarmed.param5toparam7: Unused.
Theory: Combustion Safety
Starting a combustion engine autonomously is a significant safety risk.
- Vibration: Engines produce high-frequency vibration that can saturate the EKF. ArduPilot's engine controller includes logic to check the "Health" of the IMUs during the cranking phase.
- Height Delays: The
Height Delay (Param 3)is a critical safety feature. It prevents a hot, powerful engine from starting on the ground where it could injure people. The engine is only engaged once the vehicle is safely "In the Air."
Practical Use Cases
- Hybrid Range Extension:
- Scenario: A VTOL drone launches using battery power for noise abatement.
- Action: Mission includes
DO_ENGINE_CONTROL (Start, Height Delay: 20m). The engine starts only after the drone is high enough to minimize ground noise.
- Autonomous Landing Shutdown:
- Scenario: A gas-powered drone completes its mission.
- Action:
NAV_LAND->[CONDITION_DELAY](/mission-planning/condition-commands.html#CONDITION_DELAY) (5s)->DO_ENGINE_CONTROL (Stop). Ensures the engine is cool and stopped before humans approach the airframe.
Key Parameters
ICE_START_RPM: RPM threshold to consider the engine "Running."ICE_PIN: Relay pin used for the Starter.ICE_PWM_IGN: PWM value to enable ignition.
Key Codebase Locations
- libraries/AP_ICEngine/AP_ICEngine.cpp: The core ICE driver and state machine.
- ArduPlane/commands_logic.cpp:183: Plane mission integration.
DO_GIMBAL_MANAGER_PITCHYAW
Summary
The DO_GIMBAL_MANAGER_PITCHYAW command provides advanced, high-level control for modern MAVLink gimbals. It allows for simultaneous control of both angles and rates, and includes flags for specifying the frame of reference (Body vs. Earth). This is the "Modern" version of the legacy DO_MOUNT_CONTROL.
Status
Supported (All Vehicles with Gimbal Manager backends)
Directionality
- RX (Receive): The vehicle receives this command as part of a mission upload or as a direct command.
Mission Storage (AP_Mission)
- Pitch (Param 1): Angle in degrees.
- Yaw (Param 2): Angle in degrees.
- Pitch Rate (Param 3): Deg/s.
- Yaw Rate (Param 4): Deg/s.
- Flags (Param 5): Bitmask for coordinate frames and modes.
- Gimbal ID (Param 7): Target instance.
- Packing: Stored in the
gimbal_manager_pitchyawcontent struct.
Execution (Engineer's View)
Gimbal Manager Protocol
Unlike simple servo gimbals, modern gimbals (like the DJI H20T or specialized Gremsy units) handle their own stabilization. ArduPilot acts as a "Manager."
- Setpoints: ArduPilot extracts the 5D setpoint (Angle P, Angle Y, Rate P, Rate Y, Frame).
- Targeting: The command is forwarded to the specific Gimbal ID via the MAVLink Gimbal Protocol v2.
- Frame Switching:
- Body Frame: The camera follows the drone's nose.
- Earth Frame: The camera stays locked to a compass heading.
- Rate Overlays: The inclusion of "Rate" parameters allows for smooth "Cinematic Pans" where the gimbal moves at a constant speed to a target angle, rather than jumping instantly.
Data Fields (MAVLink)
param1(Pitch): deg.param2(Yaw): deg.param3(PRate): deg/s.param4(YRate): deg/s.param5(Flags): See GIMBAL_MANAGER_FLAGS.
Theory: Rate vs. Position Control
In control systems, Position Control ($P$) is prone to "jerk" ($J = \frac{da}{dt}$).
- The Improvement: By specifying a Rate Limit ($\omega$), the gimbal manager implements a Velocity-Limited Position Controller.
- Mathematics: The target angle $\theta(t)$ follows a ramp:
$$ \theta(t) = \theta_0 + \omega \cdot t $$
until $\theta(t) = \theta_{target}$. This results in the smooth, professional camera movements seen in high-end cinema drones.
Practical Use Cases
- Survey Pivot:
- Scenario: A triple-lens camera needs to pan from visual to thermal while maintaining a steady rate to avoid motion blur.
- Action:
DO_GIMBAL_MANAGER_PITCHYAW (Yaw: 90, YawRate: 5). The camera slowly turns to the right over 18 seconds.
- Tracking a Moving Target:
- Scenario: The GCS is streaming a target velocity.
- Action: The command uses the Rate parameters to "Lead" the target.
Key Parameters
MNT1_TYPE: Must be set toMAVLinkV2.
Key Codebase Locations
- libraries/GCS_MAVLink/GCS_Common.cpp:5519: Command forwarding logic.
- libraries/AP_Mount/AP_Mount.cpp: High-level mount coordination.
DO_WINCH
Summary
The DO_WINCH command provides advanced control for robotic winches slung beneath a vehicle. It supports releasing a specific length of cable, controlling the cable's rate of descent, or "relaxing" the motor. This is the primary command for air-to-ground delivery systems where the drone must remain high while the payload descends.
Status
Supported (ArduCopter)
Directionality
- RX (Receive): The vehicle receives this command as part of a mission upload or as a direct command.
Mission Storage (AP_Mission)
- Action (Param 2):
- 0: Relax (Motor powered off).
- 1: Position (Release length).
- 2: Rate (Descent speed).
- Length (Param 3): Distance in meters (Negative to reel in).
- Rate (Param 4): Speed in m/s.
- Packing: Stored in the
winchcontent struct.
Execution (Engineer's View)
Winch Control State Machine
The command is handled by the AP_Winch library (AP_Winch.cpp).
- Safety Verification: ArduPilot checks the
WINCH_TYPE. It supports PWM winches (servos), DroneCAN winches, and Daedalus-protocol winches. - Position Control: If
Action: 1is selected, the autopilot uses a PID loop to move the cable to the absolute length requested. This typically requires an encoder on the winch motor. - Rate Control: If
Action: 2is selected, the autopilot maintains a steady cable velocity. This is safer for heavy payloads to prevent "yanking" the drone out of the air if the cable snags. - Completion: The mission advances immediately. The winch continues to work in the background. It is highly recommended to follow a winch command with a
CONDITION_DELAYif the next mission leg requires the payload to be fully deployed or retracted.
Data Fields (MAVLink)
param1(Instance): Winch number (typically 0).param2(Action): 0:Relax, 1:Length, 2:Rate.param3(Length): m.param4(Rate): m/s.
Theory: Tension and Pendulums
Slung loads introduce Pendulum Dynamics into the drone's flight model.
- Oscillation: A long cable ($L$) has a natural frequency $f = \frac{1}{2\pi}\sqrt{\frac{g}{L}}$.
- Damping: ArduPilot's position controller is aware of the cable length if
DO_WINCHis used, allowing the EKF to potentially compensate for the shifting center of gravity. - Safety: The
Relax (0)action is critical for emergencies. If the payload snags on a tree, relaxing the winch allows the drone to fly away rather than being pulled into the ground.
Practical Use Cases
- Cable-Drop Delivery:
- Scenario: Delivering a parcel to a balcony.
- Action: Drone hovers 10m above the balcony.
DO_WINCH (Action: 1, Length: 10m)lowers the parcel.[DO_GRIPPER](/mission-planning/do-commands.html#DO_GRIPPER) (Release)drops it.DO_WINCH (Action: 1, Length: -10m)reels the hook back in.
- Water Sampling:
- Scenario: Lowering a sensor into a lake.
- Action:
DO_WINCH (Action: 2, Rate: 0.5m/s)ensures a smooth entry for the sensor.
Key Parameters
WINCH_TYPE: Hardware selection.WINCH_MAX_LENGTH: Safety limit to prevent the motor from unspooling the entire drum.
Key Codebase Locations
- libraries/AP_Winch/AP_Winch.cpp: Main driver logic.
- ArduCopter/mode_auto.cpp:1997: Mission command intake.