FlowHold Mode (Copter)
Executive Summary
FlowHold is a horizontal position-control mode designed for GPS-denied environments. It utilizes an Optical Flow sensor to arrest drift and maintain position. Unlike Loiter, it does not target a specific geographic coordinate but rather continuously minimizes horizontal velocity error derived from visual data.
Theory & Concepts
1. What is Optical Flow?
For those new to ArduPilot, an Optical Flow sensor is essentially a downward-facing camera that tracks the texture of the ground. By analyzing how pixels move from frame to frame, it calculates the "flow rate."
- Analogy: Imagine looking down at the pavement through a straw while walking. The speed at which the cracks in the pavement pass through your view is "Optical Flow."
2. Optical Flow vs. Inertial Prediction
FlowHold is a Velocity Estimator.
- The Problem: IMU sensors (Accelerometers) are very noisy and drift within seconds.
- The Flow Advantage: Optical flow sensors provide a high-rate (50Hz+) measurement of movement over the ground.
- The Fusion: The EKF uses the flow data to constantly correct the "Drift" of the accelerometers. This allows the drone to remain stationary even when the GPS signal is blocked by a roof.
3. The "Fake Motion" Problem (Gyroscopic Compensation)
A raw optical flow sensor cannot distinguish between two very different movements:
- Translation: The drone moves forward. The ground appears to slide backward.
- Rotation: The drone pitches forward (noses down) while hovering in place. The camera tilts, so the ground also appears to slide backward.
If the drone didn't know the difference, pitching forward to accelerate would make it think it was already moving fast, causing it to fight its own inputs.
How ArduPilot Solves It
ArduPilot performs Gyroscopic Compensation. It subtracts the vehicle's angular rotation (measured by the Gyro) from the visual flow rate.
- The Math:
True_Flow = Sensor_Flow - Body_Rotation_Rate - The Code: Validated in
mode_flowhold.cpp:Vector2f raw_flow = copter.optflow.flowRate() - copter.optflow.bodyRate(); - Why this matters for you: If your
FLOW_FXSCALERorFLOW_FYSCALERparameters are incorrect, the units won't match. Pitching the drone will create "ghost" velocity readings, causing instability or "toilet bowling" even if the PID gains are perfect.
Hardware Dependency Matrix
The code explicitly checks for sensor health before entering or maintaining this mode.
| Sensor | Requirement | Code Implementation Notes |
|---|---|---|
| Optical Flow | CRITICAL | copter.optflow.enabled() and healthy() must be true. Failsafe triggers if quality drops below FHLD_QUAL_MIN. |
| GPS | NONE | requires_GPS() returns false. GPS is ignored for navigation. |
| Compass | OPTIONAL | Heading is maintained via the AHRS, but FlowHold itself operates in the body-frame relative to flow. |
| Barometer | REQUIRED | Primary source for Z-axis altitude hold unless a Rangefinder is active. |
| Rangefinder | RECOMMENDED | If absent, the vehicle uses a "Virtual Odometry" estimate which correlates IMU accel with Flow rate to guess height. This is the primary cause of instability. See update_height_estimate(). |
Control Architecture (Engineer's View)
FlowHold operates on a unique control structure distinct from Loiter or PosHold.
- Input Shaper: Pilot Roll/Pitch sticks are mapped directly to Lean Angle (not Velocity).
- Code Path:
get_pilot_desired_lean_anglescalled inrun().
- Code Path:
- Flow-to-Angle Controller:
- The raw flow rate is filtered (
FHLD_FILT_HZ) and constrained (FHLD_FLOW_MAX). - It is fed into a PI Controller (
FHLD_XY_P,FHLD_XY_I). - Output: A correction lean angle that is added to the pilot's input.
- Code Path:
flowhold_flow_to_angle().
- The raw flow rate is filtered (
- Z-Axis Controller:
- Uses standard
PosControlZ-axis logic. - Critical Detail: It calculates altitude error based on the EKF origin. If relying on Barometer (indoor), pressure fluctuations will cause the Z-controller to command throttle changes, leading to "ceiling suction" or floor drops.
- Uses standard
Pilot Interaction
- Active Input: When you move the sticks, you are in Stabilize-like control. You are fighting the flow controller's I-term if you push against the drift.
- Stick Release (Braking): When sticks are centered, the
brakingflag is set.- Logic: The controller applies a "Brake Gain" derived from
FHLD_BRAKE_RATE. - Feel: The vehicle pitches back aggressively to kill momentum, then locks position.
- Logic: The controller applies a "Brake Gain" derived from
Failsafe Logic
The mode_flowhold.cpp run() function contains specific checks:
- Low Flow Quality:
- Trigger: Sensor quality drops below
FHLD_QUAL_MIN(Default: 10). - Behavior: The flow correction term is zeroed out (see
run()loop). - Result: The vehicle silently degrades to AltHold. It will drift with the wind. It does not land or switch modes automatically.
- Trigger: Sensor quality drops below
- Height Estimation Divergence:
- If no rangefinder is present, and the vehicle is static (no velocity change), the height estimator cannot update.
- Result: The flow scaler may be incorrect, leading to oscillation (toilet bowling) or sluggishness.
Key Parameters
Parameter definitions start at line 11.
| Parameter | Default | Description |
|---|---|---|
FHLD_QUAL_MIN |
10 | Minimum flow quality (0-255). Below this, the vehicle stops holding position and acts like AltHold. |
FHLD_FLOW_MAX |
0.6 | The maximum flow rate (approx m/s) the controller will attempt to correct. Lower values make it less aggressive. |
FHLD_XY_P |
3.0 | Proportional gain for the position hold. Increase for tighter hold, decrease if oscillating. |
FHLD_XY_I |
0.05 | Integral gain. Helps correct for steady-state drift (e.g., wind). |
FHLD_BRAKE_RATE |
8 | (deg/s). How aggressively the vehicle pitches back to stop when sticks are released. |
FHLD_FILT_HZ |
5 | Input filter for the flow sensor. Lower values smooth out noisy sensors but add latency. |
FLOW_FXSCALER |
0 | Critical for Theory: Calibrates the sensor's X-axis field of view to match the gyro. If this is wrong, gyroscopic compensation fails. |
FLOW_FYSCALER |
0 | Critical for Theory: Calibrates the sensor's Y-axis field of view to match the gyro. |
Tuning & Troubleshooting
| Symptom | Probable Cause | Corrective Action |
|---|---|---|
| "Toilet Bowling" (Swirling) | Compass interference OR poor height estimate. | If no Rangefinder: perform aggressive maneuvers to help the EKF learn height scale. If Rangefinder: Check alignment. |
| Drifting with Wind | I-Term saturation or too low. | Increase FHLD_XY_I to allow the controller to lean against steady air currents. |
| Oscillation (Jitter) | P-Gain too high for the surface texture. | Reduce FHLD_XY_P. |
| Surging when Pitching | Incorrect Gyro Compensation. | Tune FLOW_FXSCALER / FLOW_FYSCALER. If the drone accelerates when you just tilt it, the sensor thinks rotation is translation. |
| Ceiling Strike | Barometer drift in indoor environment. | Cover the barometer with open-cell foam. Use a Rangefinder (Lidar/Sonar) to override baro. |
Source Code Reference
- Mode Logic:
ardupilot/ArduCopter/mode_flowhold.cpp - Height Estimator:
ModeFlowHold::update_height_estimate() - State Machine:
ModeFlowHold::run()