Copter: move devo telemetry handling to GCS
This commit is contained in:
parent
9c36887a90
commit
451f5f17ce
@ -140,10 +140,6 @@
|
||||
# include <AP_Camera/AP_Camera.h>
|
||||
#endif
|
||||
|
||||
#if DEVO_TELEM_ENABLED == ENABLED
|
||||
#include <AP_Devo_Telem/AP_Devo_Telem.h>
|
||||
#endif
|
||||
|
||||
#if OSD_ENABLED == ENABLED
|
||||
#include <AP_OSD/AP_OSD.h>
|
||||
#endif
|
||||
@ -401,10 +397,6 @@ private:
|
||||
FUNCTOR_BIND_MEMBER(&Copter::handle_battery_failsafe, void, const char*, const int8_t),
|
||||
_failsafe_priorities};
|
||||
|
||||
#if DEVO_TELEM_ENABLED == ENABLED
|
||||
AP_DEVO_Telem devo_telemetry;
|
||||
#endif
|
||||
|
||||
#if OSD_ENABLED == ENABLED
|
||||
AP_OSD osd;
|
||||
#endif
|
||||
|
@ -234,10 +234,6 @@ bool Copter::set_mode(control_mode_t mode, mode_reason_t reason)
|
||||
fence.manual_recovery_start();
|
||||
#endif
|
||||
|
||||
#if DEVO_TELEM_ENABLED == ENABLED
|
||||
devo_telemetry.update_control_mode(control_mode);
|
||||
#endif
|
||||
|
||||
#if CAMERA == ENABLED
|
||||
camera.set_is_auto_mode(control_mode == AUTO);
|
||||
#endif
|
||||
|
@ -87,11 +87,6 @@ void Copter::init_ardupilot()
|
||||
// setup telem slots with serial ports
|
||||
gcs().setup_uarts(serial_manager);
|
||||
|
||||
#if DEVO_TELEM_ENABLED == ENABLED
|
||||
// setup devo
|
||||
devo_telemetry.init();
|
||||
#endif
|
||||
|
||||
#if OSD_ENABLED == ENABLED
|
||||
osd.init();
|
||||
#endif
|
||||
|
Loading…
Reference in New Issue
Block a user