mirror of https://github.com/ArduPilot/ardupilot
global: use static method to construct AP_BattMonitor
This commit is contained in:
parent
bd8f0a9e93
commit
b022c02029
|
@ -286,7 +286,7 @@ private:
|
|||
aux_switch_pos aux_ch7;
|
||||
|
||||
// Battery Sensors
|
||||
AP_BattMonitor battery;
|
||||
AP_BattMonitor battery = AP_BattMonitor::create();
|
||||
|
||||
#if FRSKY_TELEM_ENABLED == ENABLED
|
||||
// FrSky telemetry support
|
||||
|
|
|
@ -450,7 +450,7 @@ private:
|
|||
} throw_state = {Throw_Disarmed, Throw_Disarmed, 0, false, 0, 0.0f};
|
||||
|
||||
// Battery Sensors
|
||||
AP_BattMonitor battery;
|
||||
AP_BattMonitor battery = AP_BattMonitor::create();
|
||||
|
||||
// FrSky telemetry support
|
||||
#if FRSKY_TELEM_ENABLED == ENABLED
|
||||
|
|
|
@ -391,7 +391,7 @@ private:
|
|||
int32_t altitude_error_cm;
|
||||
|
||||
// Battery Sensors
|
||||
AP_BattMonitor battery;
|
||||
AP_BattMonitor battery = AP_BattMonitor::create();
|
||||
|
||||
#if FRSKY_TELEM_ENABLED == ENABLED
|
||||
// FrSky telemetry support
|
||||
|
|
|
@ -326,7 +326,7 @@ private:
|
|||
uint32_t nav_delay_time_start;
|
||||
|
||||
// Battery Sensors
|
||||
AP_BattMonitor battery;
|
||||
AP_BattMonitor battery = AP_BattMonitor::create();
|
||||
|
||||
AP_Arming_Sub arming = AP_Arming_Sub::create(ahrs, barometer, compass, battery);
|
||||
|
||||
|
|
|
@ -11,7 +11,7 @@ void loop();
|
|||
|
||||
const AP_HAL::HAL& hal = AP_HAL::get_HAL();
|
||||
|
||||
AP_BattMonitor battery_mon;
|
||||
static AP_BattMonitor battery_mon = AP_BattMonitor::create();
|
||||
uint32_t timer;
|
||||
|
||||
void setup() {
|
||||
|
|
Loading…
Reference in New Issue