mirror of https://github.com/ArduPilot/ardupilot
AP_HAL_ChibiOS: default to 0 battery capacity on periph
This commit is contained in:
parent
73c77d0757
commit
2fbc27584b
|
@ -247,6 +247,11 @@
|
|||
#define AP_BATT_MONITOR_MAX_INSTANCES 1
|
||||
#endif
|
||||
|
||||
// Capacity tracking off
|
||||
#ifndef AP_BATT_MONITOR_BATTERY_CAPACITY
|
||||
#define AP_BATT_MONITOR_BATTERY_CAPACITY 0
|
||||
#endif
|
||||
|
||||
#ifndef RANGEFINDER_MAX_INSTANCES
|
||||
#define RANGEFINDER_MAX_INSTANCES 1
|
||||
#endif
|
||||
|
|
Loading…
Reference in New Issue