global: use static method to construct AP_Frsky_Telem

This commit is contained in:
Lucas De Marchi 2017-08-29 10:44:54 -07:00 committed by Francisco Ferreira
parent 8b5d799885
commit 9ce6019138
5 changed files with 5 additions and 11 deletions

View File

@ -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)
{

View File

@ -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;

View File

@ -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),

View File

@ -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;

View File

@ -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