From 9ce6019138f60e92f41fe4156900ff7b98bcf120 Mon Sep 17 00:00:00 2001 From: Lucas De Marchi Date: Tue, 29 Aug 2017 10:44:54 -0700 Subject: [PATCH] global: use static method to construct AP_Frsky_Telem --- APMrover2/Rover.cpp | 3 --- APMrover2/Rover.h | 2 +- ArduCopter/Copter.cpp | 3 --- ArduCopter/Copter.h | 6 +++--- ArduPlane/Plane.h | 2 +- 5 files changed, 5 insertions(+), 11 deletions(-) diff --git a/APMrover2/Rover.cpp b/APMrover2/Rover.cpp index fad1c3727b..779b03158b 100644 --- a/APMrover2/Rover.cpp +++ b/APMrover2/Rover.cpp @@ -39,9 +39,6 @@ Rover::Rover(void) : camera_mount(ahrs, current_loc), #endif control_mode(&mode_initializing), -#if FRSKY_TELEM_ENABLED == ENABLED - frsky_telemetry(ahrs, battery, rangefinder), -#endif home(ahrs.get_home()), G_Dt(0.02f) { diff --git a/APMrover2/Rover.h b/APMrover2/Rover.h index 0e039ac457..ebc438930e 100644 --- a/APMrover2/Rover.h +++ b/APMrover2/Rover.h @@ -290,7 +290,7 @@ private: #if FRSKY_TELEM_ENABLED == ENABLED // FrSky telemetry support - AP_Frsky_Telem frsky_telemetry; + AP_Frsky_Telem frsky_telemetry = AP_Frsky_Telem::create(ahrs, battery, rangefinder); #endif uint32_t control_sensors_present; diff --git a/ArduCopter/Copter.cpp b/ArduCopter/Copter.cpp index 6b2708a123..b325830433 100644 --- a/ArduCopter/Copter.cpp +++ b/ArduCopter/Copter.cpp @@ -46,9 +46,6 @@ Copter::Copter(void) initial_armed_bearing(0), loiter_time_max(0), loiter_time(0), -#if FRSKY_TELEM_ENABLED == ENABLED - frsky_telemetry(ahrs, battery, rangefinder), -#endif climb_rate(0), target_rangefinder_alt(0.0f), baro_alt(0), diff --git a/ArduCopter/Copter.h b/ArduCopter/Copter.h index 51ff7d9af2..c1b6e56411 100644 --- a/ArduCopter/Copter.h +++ b/ArduCopter/Copter.h @@ -452,16 +452,16 @@ private: // Battery Sensors AP_BattMonitor battery = AP_BattMonitor::create(); - // FrSky telemetry support #if FRSKY_TELEM_ENABLED == ENABLED - AP_Frsky_Telem frsky_telemetry; + // FrSky telemetry support + AP_Frsky_Telem frsky_telemetry = AP_Frsky_Telem::create(ahrs, battery, rangefinder); #endif // Variables for extended status MAVLink messages uint32_t control_sensors_present; uint32_t control_sensors_enabled; uint32_t control_sensors_health; - + // Altitude // The cm/s we are moving up or down based on filtered data - Positive = UP int16_t climb_rate; diff --git a/ArduPlane/Plane.h b/ArduPlane/Plane.h index bd5bac4012..268dfb06b7 100644 --- a/ArduPlane/Plane.h +++ b/ArduPlane/Plane.h @@ -395,7 +395,7 @@ private: #if FRSKY_TELEM_ENABLED == ENABLED // FrSky telemetry support - AP_Frsky_Telem frsky_telemetry {ahrs, battery, rangefinder}; + AP_Frsky_Telem frsky_telemetry = AP_Frsky_Telem::create(ahrs, battery, rangefinder); #endif // Variables for extended status MAVLink messages