mirror of https://github.com/ArduPilot/ardupilot
global: use static method to construct AP_RPM
This commit is contained in:
parent
aefae9381e
commit
de5e044b02
|
@ -211,7 +211,7 @@ private:
|
||||||
int8_t glitch_count;
|
int8_t glitch_count;
|
||||||
} rangefinder_state = { false, false, 0, 0 };
|
} rangefinder_state = { false, false, 0, 0 };
|
||||||
|
|
||||||
AP_RPM rpm_sensor;
|
AP_RPM rpm_sensor = AP_RPM::create();
|
||||||
|
|
||||||
// Inertial Navigation EKF
|
// Inertial Navigation EKF
|
||||||
NavEKF2 EKF2{&ahrs, barometer, rangefinder};
|
NavEKF2 EKF2{&ahrs, barometer, rangefinder};
|
||||||
|
|
|
@ -209,7 +209,7 @@ private:
|
||||||
|
|
||||||
AP_Vehicle::FixedWing::Rangefinder_State rangefinder_state;
|
AP_Vehicle::FixedWing::Rangefinder_State rangefinder_state;
|
||||||
|
|
||||||
AP_RPM rpm_sensor;
|
AP_RPM rpm_sensor = AP_RPM::create();
|
||||||
|
|
||||||
// Inertial Navigation EKF
|
// Inertial Navigation EKF
|
||||||
#if AP_AHRS_NAVEKF_AVAILABLE
|
#if AP_AHRS_NAVEKF_AVAILABLE
|
||||||
|
|
|
@ -180,7 +180,7 @@ private:
|
||||||
} rangefinder_state = { false, false, 0, 0 };
|
} rangefinder_state = { false, false, 0, 0 };
|
||||||
|
|
||||||
#if RPM_ENABLED == ENABLED
|
#if RPM_ENABLED == ENABLED
|
||||||
AP_RPM rpm_sensor;
|
AP_RPM rpm_sensor = AP_RPM::create();
|
||||||
#endif
|
#endif
|
||||||
|
|
||||||
// Inertial Navigation EKF
|
// Inertial Navigation EKF
|
||||||
|
|
|
@ -26,7 +26,7 @@ void loop();
|
||||||
|
|
||||||
const AP_HAL::HAL& hal = AP_HAL::get_HAL();
|
const AP_HAL::HAL& hal = AP_HAL::get_HAL();
|
||||||
|
|
||||||
static AP_RPM RPM;
|
static AP_RPM RPM = AP_RPM::create();
|
||||||
|
|
||||||
char sensor_state;
|
char sensor_state;
|
||||||
|
|
||||||
|
|
Loading…
Reference in New Issue