Browse Source

ArduCopter: devo telemetry support (RX705/707)

master
night-ghost 7 years ago committed by Andrew Tridgell
parent
commit
51a189e906
  1. 1
      ArduCopter/APM_Config.h
  2. 8
      ArduCopter/Copter.h
  3. 8
      ArduCopter/config.h
  4. 1
      ArduCopter/make.inc
  5. 4
      ArduCopter/mode.cpp
  6. 5
      ArduCopter/system.cpp
  7. 1
      ArduCopter/wscript

1
ArduCopter/APM_Config.h

@ -42,6 +42,7 @@ @@ -42,6 +42,7 @@
//#define MODE_SMARTRTL_ENABLED DISABLED // disable smartrtl mode support
//#define MODE_SPORT_ENABLED DISABLED // disable sport mode support
//#define MODE_THROW_ENABLED DISABLED // disable throw mode support
//#define DEVO_TELEM_ENABLED DISABLED // disable DEVO telemetry, if you don't use Walkera RX-707 (or newer) receivers
// features below are disabled by default on all boards

8
ArduCopter/Copter.h

@ -147,6 +147,11 @@ @@ -147,6 +147,11 @@
#if CAMERA == ENABLED
# include <AP_Camera/AP_Camera.h>
#endif
#if DEVO_TELEM_ENABLED == ENABLED
#include <AP_Devo_Telem/AP_Devo_Telem.h>
#endif
#if ADVANCED_FAILSAFE == ENABLED
# include "afs_copter.h"
#endif
@ -441,6 +446,9 @@ private: @@ -441,6 +446,9 @@ private:
// FrSky telemetry support
AP_Frsky_Telem frsky_telemetry{ahrs, battery, rangefinder};
#endif
#if DEVO_TELEM_ENABLED == ENABLED
AP_DEVO_Telem devo_telemetry{ahrs};
#endif
// Variables for extended status MAVLink messages
uint32_t control_sensors_present;

8
ArduCopter/config.h

@ -716,3 +716,11 @@ @@ -716,3 +716,11 @@
#ifndef STATS_ENABLED
# define STATS_ENABLED ENABLED
#endif
#ifndef DEVO_TELEM_ENABLED
#if HAL_MINIMIZE_FEATURES
#define DEVO_TELEM_ENABLED DISABLED
#else
#define DEVO_TELEM_ENABLED ENABLED
#endif
#endif

1
ArduCopter/make.inc

@ -67,3 +67,4 @@ LIBRARIES += AP_SmartRTL @@ -67,3 +67,4 @@ LIBRARIES += AP_SmartRTL
LIBRARIES += AP_Winch
LIBRARIES += AP_WheelEncoder
LIBRARIES += AP_Follow
LIBRARIES += AP_Devo_Telem

4
ArduCopter/mode.cpp

@ -225,6 +225,10 @@ bool Copter::set_mode(control_mode_t mode, mode_reason_t reason) @@ -225,6 +225,10 @@ bool Copter::set_mode(control_mode_t mode, mode_reason_t reason)
#if FRSKY_TELEM_ENABLED == ENABLED
frsky_telemetry.update_control_mode(control_mode);
#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

5
ArduCopter/system.cpp

@ -106,6 +106,11 @@ void Copter::init_ardupilot() @@ -106,6 +106,11 @@ void Copter::init_ardupilot()
&ap.value);
#endif
#if DEVO_TELEM_ENABLED == ENABLED
// setup devo
devo_telemetry.init(serial_manager);
#endif
#if LOGGING_ENABLED == ENABLED
log_init();
#endif

1
ArduCopter/wscript

@ -35,6 +35,7 @@ def build(bld): @@ -35,6 +35,7 @@ def build(bld):
'AP_WheelEncoder',
'AP_Winch',
'AP_Follow',
'AP_Devo_Telem',
],
)

Loading…
Cancel
Save