Plane: removed frsky_telemetry_send scheduled task

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

View File

@ -79,9 +79,6 @@ const AP_Scheduler::Task Plane::scheduler_tasks[] = {
SCHED_TASK(update_logging1, 10, 300),
SCHED_TASK(update_logging2, 10, 300),
SCHED_TASK(parachute_check, 10, 200),
#if FRSKY_TELEM_ENABLED == ENABLED
SCHED_TASK(frsky_telemetry_send, 5, 100),
#endif
SCHED_TASK(terrain_update, 10, 200),
SCHED_TASK(update_is_flying_5Hz, 5, 100),
SCHED_TASK(dataflash_periodic, 50, 400),

View File

@ -1003,7 +1003,6 @@ private:
void print_comma(void);
void servo_write(uint8_t ch, uint16_t pwm);
bool should_log(uint32_t mask);
void frsky_telemetry_send(void);
int8_t throttle_percentage(void);
void change_arm_state(void);
bool disarm_motors(void);

View File

@ -159,7 +159,8 @@ void Plane::init_ardupilot()
// setup frsky
#if FRSKY_TELEM_ENABLED == ENABLED
frsky_telemetry.init(serial_manager);
// setup frsky, and pass a number of parameters to the library
frsky_telemetry.init(serial_manager, (uint8_t *)&control_mode);
#endif
mavlink_system.sysid = g.sysid_this_mav;
@ -782,17 +783,6 @@ bool Plane::should_log(uint32_t mask)
#endif
}
/*
send FrSky telemetry. Should be called at 5Hz by scheduler
*/
#if FRSKY_TELEM_ENABLED == ENABLED
void Plane::frsky_telemetry_send(void)
{
frsky_telemetry.send_frames((uint8_t)control_mode);
}
#endif
/*
return throttle percentage from 0 to 100 for normal use and -100 to 100 when using reverse thrust
*/