Browse Source

Copter: removed frsky_telemetry_send scheduled task

mission-4.1.18
floaledm 9 years ago committed by Andrew Tridgell
parent
commit
f73fa1fc80
  1. 3
      ArduCopter/ArduCopter.cpp
  2. 5
      ArduCopter/Copter.h
  3. 13
      ArduCopter/system.cpp

3
ArduCopter/ArduCopter.cpp

@ -128,9 +128,6 @@ const AP_Scheduler::Task Copter::scheduler_tasks[] = { @@ -128,9 +128,6 @@ const AP_Scheduler::Task Copter::scheduler_tasks[] = {
SCHED_TASK(accel_cal_update, 10, 100),
#if ADSB_ENABLED == ENABLED
SCHED_TASK(avoidance_adsb_update, 10, 100),
#endif
#if FRSKY_TELEM_ENABLED == ENABLED
SCHED_TASK(frsky_telemetry_send, 5, 75),
#endif
SCHED_TASK(terrain_update, 10, 100),
#if EPM_ENABLED == ENABLED

5
ArduCopter/Copter.h

@ -81,7 +81,6 @@ @@ -81,7 +81,6 @@
#include <AP_Notify/AP_Notify.h> // Notify library
#include <AP_BattMonitor/AP_BattMonitor.h> // Battery monitor library
#include <AP_BoardConfig/AP_BoardConfig.h> // board configuration library
#include <AP_Frsky_Telem/AP_Frsky_Telem.h>
#include <AP_LandingGear/AP_LandingGear.h> // Landing Gear library
#include <AP_Terrain/AP_Terrain.h>
#include <AP_ADSB/AP_ADSB.h>
@ -111,6 +110,9 @@ @@ -111,6 +110,9 @@
#include <AC_PrecLand/AC_PrecLand.h>
#include <AP_IRLock/AP_IRLock.h>
#endif
#if FRSKY_TELEM_ENABLED == ENABLED
#include <AP_Frsky_Telem/AP_Frsky_Telem.h>
#endif
// Local modules
#include "Parameters.h"
@ -1034,7 +1036,6 @@ private: @@ -1034,7 +1036,6 @@ private:
bool optflow_position_ok();
void update_auto_armed();
void check_usb_mux(void);
void frsky_telemetry_send(void);
bool should_log(uint32_t mask);
bool current_mode_has_user_takeoff(bool must_navigate);
bool do_user_takeoff(float takeoff_alt_cm, bool must_navigate);

13
ArduCopter/system.cpp

@ -152,8 +152,8 @@ void Copter::init_ardupilot() @@ -152,8 +152,8 @@ void Copter::init_ardupilot()
}
#if FRSKY_TELEM_ENABLED == ENABLED
// setup frsky
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
// identify ourselves correctly with the ground station
@ -426,15 +426,6 @@ void Copter::check_usb_mux(void) @@ -426,15 +426,6 @@ void Copter::check_usb_mux(void)
ap.usb_connected = usb_check;
}
// frsky_telemetry_send - sends telemetry data using frsky telemetry
// should be called at 5Hz by scheduler
#if FRSKY_TELEM_ENABLED == ENABLED
void Copter::frsky_telemetry_send(void)
{
frsky_telemetry.send_frames((uint8_t)control_mode);
}
#endif
/*
should we log a message type now?
*/

Loading…
Cancel
Save