Rover: removed frsky_telemetry_send scheduled task

This commit is contained in:
floaledm 2016-05-03 10:07:14 -05:00 committed by Andrew Tridgell
parent f09277a0ed
commit 4030851207
3 changed files with 2 additions and 16 deletions

View File

@ -75,9 +75,6 @@ const AP_Scheduler::Task Rover::scheduler_tasks[] = {
SCHED_TASK(one_second_loop, 1, 3000),
SCHED_TASK(compass_cal_update, 50, 100),
SCHED_TASK(accel_cal_update, 10, 100),
#if FRSKY_TELEM_ENABLED == ENABLED
SCHED_TASK(frsky_telemetry_send, 5, 100),
#endif
SCHED_TASK(dataflash_periodic, 50, 300),
SCHED_TASK(button_update, 5, 100),
};

View File

@ -286,8 +286,8 @@ private:
// Battery Sensors
AP_BattMonitor battery;
// Battery Sensors
#if FRSKY_TELEM_ENABLED == ENABLED
// FrSky telemetry support
AP_Frsky_Telem frsky_telemetry;
#endif
@ -496,7 +496,6 @@ private:
void check_usb_mux(void);
uint8_t check_digital_pin(uint8_t pin);
bool should_log(uint32_t mask);
void frsky_telemetry_send(void);
void print_hit_enter();
void gcs_send_text_fmt(MAV_SEVERITY severity, const char *fmt, ...);
void print_mode(AP_HAL::BetterStream *port, uint8_t mode);

View File

@ -129,7 +129,7 @@ void Rover::init_ardupilot()
// setup frsky telemetry
#if FRSKY_TELEM_ENABLED == ENABLED
frsky_telemetry.init(serial_manager);
frsky_telemetry.init(serial_manager, (uint8_t *)&control_mode);
#endif
mavlink_system.sysid = g.sysid_this_mav;
@ -487,16 +487,6 @@ bool Rover::should_log(uint32_t mask)
return ret;
}
/*
send FrSky telemetry. Should be called at 5Hz by scheduler
*/
#if FRSKY_TELEM_ENABLED == ENABLED
void Rover::frsky_telemetry_send(void)
{
frsky_telemetry.send_frames((uint8_t)control_mode);
}
#endif
/*
update AHRS soft arm state and log as needed
*/