mirror of https://github.com/ArduPilot/ardupilot
APMrover2: devo telemetry support (RX705/707)
This commit is contained in:
parent
33a26ac0a8
commit
2aee8d1018
|
@ -40,6 +40,7 @@
|
|||
#include <AP_Compass/AP_Compass.h> // ArduPilot Mega Magnetometer Library
|
||||
#include <AP_Declination/AP_Declination.h> // Compass declination library
|
||||
#include <AP_Frsky_Telem/AP_Frsky_Telem.h>
|
||||
#include <AP_Devo_Telem/AP_Devo_Telem.h>
|
||||
#include <AP_GPS/AP_GPS.h> // ArduPilot GPS library
|
||||
#include <AP_InertialSensor/AP_InertialSensor.h> // Inertial Sensor (uncalibated IMU) Library
|
||||
#include <AP_L1_Control/AP_L1_Control.h>
|
||||
|
@ -296,6 +297,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
|
||||
|
||||
uint32_t control_sensors_present;
|
||||
uint32_t control_sensors_enabled;
|
||||
|
|
|
@ -177,3 +177,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
|
||||
|
|
|
@ -51,3 +51,4 @@ LIBRARIES += AC_Fence
|
|||
LIBRARIES += AP_SmartRTL
|
||||
LIBRARIES += AC_Avoidance
|
||||
LIBRARIES += AC_AttitudeControl
|
||||
LIBRARIES += AP_Devo_Telem
|
||||
|
|
|
@ -82,6 +82,9 @@ void Rover::init_ardupilot()
|
|||
#if FRSKY_TELEM_ENABLED == ENABLED
|
||||
frsky_telemetry.init(serial_manager, fwver.fw_string, (is_boat() ? MAV_TYPE_SURFACE_BOAT : MAV_TYPE_GROUND_ROVER));
|
||||
#endif
|
||||
#if DEVO_TELEM_ENABLED == ENABLED
|
||||
devo_telemetry.init(serial_manager);
|
||||
#endif
|
||||
|
||||
#if LOGGING_ENABLED == ENABLED
|
||||
log_init();
|
||||
|
@ -235,6 +238,10 @@ bool Rover::set_mode(Mode &new_mode, mode_reason_t reason)
|
|||
#if FRSKY_TELEM_ENABLED == ENABLED
|
||||
frsky_telemetry.update_control_mode(control_mode->mode_number());
|
||||
#endif
|
||||
#if DEVO_TELEM_ENABLED == ENABLED
|
||||
devo_telemetry.update_control_mode(control_mode->mode_number());
|
||||
#endif
|
||||
|
||||
#if CAMERA == ENABLED
|
||||
camera.set_is_auto_mode(control_mode->mode_number() == AUTO);
|
||||
#endif
|
||||
|
|
|
@ -25,6 +25,7 @@ def build(bld):
|
|||
'AP_Proximity',
|
||||
'AC_Avoidance',
|
||||
'AC_AttitudeControl',
|
||||
'AP_Devo_Telem',
|
||||
],
|
||||
)
|
||||
|
||||
|
|
Loading…
Reference in New Issue