Skip to content
Merged
Show file tree
Hide file tree
Changes from all commits
Commits
File filter

Filter by extension

Filter by extension

Conversations
Failed to load comments.
Loading
Jump to
Jump to file
Failed to load files.
Loading
Diff view
Diff view
149 changes: 149 additions & 0 deletions docs/Battery.md
Original file line number Diff line number Diff line change
Expand Up @@ -169,6 +169,155 @@ current_meter_scale = (reported_draw_mAh / charging_data_mAh) * old_current_mete
= 435
```

## Power and Current Limiting

INAV includes an advanced power and current limiting system to protect your battery and ESCs from excessive discharge rates. This feature automatically reduces throttle output when current or power draw exceeds configured limits.

### Why Use Power Limiting?

Power and current limiting helps:
- **Protect batteries** from exceeding their C-rating and getting damaged
- **Prevent voltage sag** and brown-outs during high-throttle maneuvers
- **Extend battery lifespan** by avoiding excessive discharge rates
- **Improve safety** by preventing ESC or battery overheating
- **Comply with regulations** that may limit power output

### How It Works

The power limiter uses a PI (Proportional-Integral) controller to smoothly reduce throttle when current or power exceeds limits. It supports two operating modes:

1. **Continuous Limit**: The sustained current/power that can be drawn indefinitely
2. **Burst Limit**: A higher current/power allowed for a short duration before falling back to the continuous limit

This burst mode allows brief high-power maneuvers (like punch-outs or quick climbs) while protecting the battery during sustained high-throttle flight.

### Configuration

Power limiting requires a current sensor (`CURRENT_METER` feature). Power-based limiting additionally requires voltage measurement (`VBAT` feature).

#### Basic Settings (per battery profile)

| Setting | Description | Unit | Range |
|---------|-------------|------|-------|
| `limit_cont_current` | Continuous current limit | dA (deci-amps) | 0-2000 (0-200A) |
| `limit_burst_current` | Burst current limit | dA | 0-2000 (0-200A) |
| `limit_burst_current_time` | Duration burst is allowed | ds (deci-seconds) | 0-600 (0-60s) |
| `limit_burst_current_falldown_time` | Ramp-down duration from burst to continuous | ds | 0-600 (0-60s) |
| `limit_cont_power` | Continuous power limit | dW (deci-watts) | 0-20000 (0-2000W) |
| `limit_burst_power` | Burst power limit | dW | 0-20000 (0-2000W) |
| `limit_burst_power_time` | Duration burst power is allowed | ds | 0-600 (0-60s) |
| `limit_burst_power_falldown_time` | Ramp-down duration for power | ds | 0-600 (0-60s) |

**Note**: Set any limit to `0` to disable that specific limiter.

#### Advanced Tuning Settings

| Setting | Description | Default | Range |
|---------|-------------|---------|-------|
| `limit_pi_p` | Proportional gain for PI controller | 100 | 10-500 |
| `limit_pi_i` | Integral gain for PI controller | 15 | 10-200 |
| `limit_attn_filter_cutoff` | Low-pass filter cutoff frequency | 50 Hz | 10-200 |

### Example Configurations

#### Example 1: Simple Current Limiting (50A continuous)

Protect a 1500mAh 4S 50C battery (75A max burst, 50A continuous safe):

```
battery_profile 1

set limit_cont_current = 500 # 50A continuous
set limit_burst_current = 750 # 75A burst
set limit_burst_current_time = 100 # 10 seconds
set limit_burst_current_falldown_time = 20 # 2 second ramp-down
```

#### Example 2: Power Limiting for Racing (500W limit)

Limit total system power for racing class restrictions:

```
battery_profile 1

set limit_cont_power = 4500 # 450W continuous
set limit_burst_power = 5000 # 500W burst
set limit_burst_power_time = 50 # 5 seconds
set limit_burst_power_falldown_time = 10 # 1 second ramp-down
```

#### Example 3: Combined Current and Power Limiting

Protect both battery (current) and ESCs (power):

```
battery_profile 1

# Current limits (battery protection)
set limit_cont_current = 600 # 60A continuous
set limit_burst_current = 800 # 80A burst
set limit_burst_current_time = 100 # 10 seconds

# Power limits (ESC protection)
set limit_cont_power = 8000 # 800W continuous
set limit_burst_power = 10000 # 1000W burst
set limit_burst_power_time = 100 # 10 seconds
```

### Understanding Burst Mode

When you exceed the continuous limit, the system uses "burst reserve" (like a capacitor):
- **Burst reserve** starts full and depletes when current/power exceeds the continuous limit
- When reserve is empty, the limit drops to the continuous value
- The `falldown_time` setting creates a smooth ramp-down instead of an abrupt drop
- Reserve recharges when current/power drops below the continuous limit

**Example timeline** (60A continuous, 80A burst, 10s burst time, 2s falldown):
```
Time Limit Reason
---- ----- ------
0s 80A Full burst reserve
5s 80A Still have reserve (using 5s of 10s)
10s 80A Reserve depleted
10-12s 80→60A Ramping down over 2 seconds
12s+ 60A Continuous limit active
```

### OSD Elements

Three OSD elements display power limiting status:

- **`OSD_PLIMIT_REMAINING_BURST_TIME`**: Shows remaining burst time in seconds
- **`OSD_PLIMIT_ACTIVE_CURRENT_LIMIT`**: Shows current limit being enforced (blinks when limiting)
- **`OSD_PLIMIT_ACTIVE_POWER_LIMIT`**: Shows power limit being enforced (blinks when limiting)

Enable these in the OSD tab to monitor limiting during flight.

### Calibration Tips

1. **Find your battery's limits**: Check manufacturer specifications for continuous and burst C-ratings
- Continuous limit = `battery_capacity_mAh × continuous_C_rating / 100` (in dA)
- Burst limit = `battery_capacity_mAh × burst_C_rating / 100` (in dA)

2. **Test incrementally**: Start with conservative limits and increase gradually

3. **Monitor in flight**: Use OSD elements to see when limiting activates

4. **Calibrate current sensor**: Accurate current readings are critical - see "Current Monitoring" section above

5. **Tune PI controller**: If limiting feels abrupt or causes oscillation, adjust `limit_pi_p` and `limit_pi_i`:
- Increase P for faster response (may cause oscillation)
- Increase I for better steady-state accuracy
- Decrease if throttle oscillates during limiting

### Notes

- Power limiting is part of the battery profile system - each profile can have different limits
- Both current and power limiting can be active simultaneously - the most restrictive applies
- Limiting is applied smoothly via PI controller to avoid abrupt throttle cuts
- The system uses instantaneous current/power readings for responsive limiting
- Set limits to `0` to disable a specific limiter while keeping others active

## Battery capacity monitoring

For the capacity monitoring to work you need a current sensor (`CURRENT_METER` feature). For monitoring energy in milliWatt hour you also need voltage measurement (`VBAT` feature). For best results the current and voltage readings have to be calibrated.
Expand Down
9 changes: 7 additions & 2 deletions src/main/flight/power_limits.c
Original file line number Diff line number Diff line change
Expand Up @@ -73,7 +73,10 @@ static bool wasLimitingPower = false;
#endif

void powerLimiterInit(void) {
if (currentBatteryProfile->powerLimits.burstCurrent < currentBatteryProfile->powerLimits.continuousCurrent) {
// Only enforce burst >= continuous if burst is enabled (non-zero)
// A value of 0 means "disabled/unlimited", not "zero amps allowed"
if (currentBatteryProfile->powerLimits.burstCurrent > 0 &&
currentBatteryProfile->powerLimits.burstCurrent < currentBatteryProfile->powerLimits.continuousCurrent) {
currentBatteryProfileMutable->powerLimits.burstCurrent = currentBatteryProfile->powerLimits.continuousCurrent;
}

Expand All @@ -87,7 +90,9 @@ void powerLimiterInit(void) {
pt1FilterInitRC(&currentThrLimitingBaseFilter, LIMITING_THR_FILTER_TCONST, 0);

#ifdef USE_ADC
if (currentBatteryProfile->powerLimits.burstPower < currentBatteryProfile->powerLimits.continuousPower) {
// Only enforce burst >= continuous if burst is enabled (non-zero)
if (currentBatteryProfile->powerLimits.burstPower > 0 &&
currentBatteryProfile->powerLimits.burstPower < currentBatteryProfile->powerLimits.continuousPower) {
currentBatteryProfileMutable->powerLimits.burstPower = currentBatteryProfile->powerLimits.continuousPower;
}

Expand Down