mirror of https://github.com/ArduPilot/ardupilot
AP_BattMonitor: Fixes the setting of a default parameter for battery instance #2 set in hwdef
This commit is contained in:
parent
5b7004408c
commit
98560d9a17
|
@ -81,7 +81,7 @@ AP_BattMonitor_Analog::AP_BattMonitor_Analog(AP_BattMonitor &mon,
|
|||
_volt_multiplier.set_default(HAL_BATT2_VOLT_SCALE);
|
||||
#endif
|
||||
#ifdef HAL_BATT2_CURR_SCALE
|
||||
_curr_amp_per_volt.set_default(HAL_BATT2_VOLT_SCALE);
|
||||
_curr_amp_per_volt.set_default(HAL_BATT2_CURR_SCALE);
|
||||
#endif
|
||||
}
|
||||
#endif
|
||||
|
|
Loading…
Reference in New Issue