ArduPlane: devo telemetry support (RX705/707)

This commit is contained in:
night-ghost 2018-03-04 14:41:06 +05:00 committed by Andrew Tridgell
parent 51a189e906
commit aa53832a70
5 changed files with 23 additions and 1 deletions

View File

@ -84,6 +84,7 @@
#include <AP_BoardConfig/AP_BoardConfig.h>
#include <AP_BoardConfig/AP_BoardConfig_CAN.h>
#include <AP_Frsky_Telem/AP_Frsky_Telem.h>
#include <AP_Devo_Telem/AP_Devo_Telem.h>
#include <AP_ServoRelayEvents/AP_ServoRelayEvents.h>
#include <AP_Rally/AP_Rally.h>
@ -390,6 +391,10 @@ private:
// FrSky telemetry support
AP_Frsky_Telem frsky_telemetry{ahrs, battery, rangefinder};
#endif
#if DEVO_TELEM_ENABLED == ENABLED
// DEVO-M telemetry support
AP_DEVO_Telem devo_telemetry {ahrs};
#endif
// Variables for extended status MAVLink messages
uint32_t control_sensors_present;

View File

@ -365,3 +365,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

View File

@ -60,3 +60,4 @@ LIBRARIES += AP_Beacon
LIBRARIES += PID
LIBRARIES += AP_Soaring
LIBRARIES += AP_Gripper
LIBRARIES += AP_Devo_Telem

View File

@ -119,6 +119,9 @@ void Plane::init_ardupilot()
frsky_telemetry.init(serial_manager, fwver.fw_string,
MAV_TYPE_FIXED_WING);
#endif
#if DEVO_TELEM_ENABLED == ENABLED
devo_telemetry.init(serial_manager);
#endif
#if LOGGING_ENABLED == ENABLED
log_init();
@ -301,6 +304,10 @@ void Plane::set_mode(enum FlightMode 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

View File

@ -32,7 +32,8 @@ def build(bld):
'AP_Beacon',
'PID',
'AP_Soaring',
'AP_Gripper'
'AP_Gripper',
'AP_Devo_Telem',
],
)