From de5e044b02a329b6e9879680322955b59576d087 Mon Sep 17 00:00:00 2001 From: Lucas De Marchi Date: Fri, 25 Aug 2017 11:49:57 -0700 Subject: [PATCH] global: use static method to construct AP_RPM --- ArduCopter/Copter.h | 2 +- ArduPlane/Plane.h | 2 +- ArduSub/Sub.h | 2 +- libraries/AP_RPM/examples/RPM_generic/RPM_generic.cpp | 2 +- 4 files changed, 4 insertions(+), 4 deletions(-) diff --git a/ArduCopter/Copter.h b/ArduCopter/Copter.h index c068e8f415..6c5934bcd1 100644 --- a/ArduCopter/Copter.h +++ b/ArduCopter/Copter.h @@ -211,7 +211,7 @@ private: int8_t glitch_count; } rangefinder_state = { false, false, 0, 0 }; - AP_RPM rpm_sensor; + AP_RPM rpm_sensor = AP_RPM::create(); // Inertial Navigation EKF NavEKF2 EKF2{&ahrs, barometer, rangefinder}; diff --git a/ArduPlane/Plane.h b/ArduPlane/Plane.h index 1b65d5fa06..cf895a72b8 100644 --- a/ArduPlane/Plane.h +++ b/ArduPlane/Plane.h @@ -209,7 +209,7 @@ private: AP_Vehicle::FixedWing::Rangefinder_State rangefinder_state; - AP_RPM rpm_sensor; + AP_RPM rpm_sensor = AP_RPM::create(); // Inertial Navigation EKF #if AP_AHRS_NAVEKF_AVAILABLE diff --git a/ArduSub/Sub.h b/ArduSub/Sub.h index 85dca5f9e4..2521d13ed0 100644 --- a/ArduSub/Sub.h +++ b/ArduSub/Sub.h @@ -180,7 +180,7 @@ private: } rangefinder_state = { false, false, 0, 0 }; #if RPM_ENABLED == ENABLED - AP_RPM rpm_sensor; + AP_RPM rpm_sensor = AP_RPM::create(); #endif // Inertial Navigation EKF diff --git a/libraries/AP_RPM/examples/RPM_generic/RPM_generic.cpp b/libraries/AP_RPM/examples/RPM_generic/RPM_generic.cpp index 283ad99687..9d84d7e242 100644 --- a/libraries/AP_RPM/examples/RPM_generic/RPM_generic.cpp +++ b/libraries/AP_RPM/examples/RPM_generic/RPM_generic.cpp @@ -26,7 +26,7 @@ void loop(); const AP_HAL::HAL& hal = AP_HAL::get_HAL(); -static AP_RPM RPM; +static AP_RPM RPM = AP_RPM::create(); char sensor_state;