mirror of https://github.com/ArduPilot/ardupilot
AP_Devo_Telem: compile out devo telemetry
Devo telemetry is one of the most rarely used features (almost never used since added) we should compile it out from our code
This commit is contained in:
parent
5224468ec6
commit
339a07b8d3
|
@ -60,5 +60,7 @@ void GCS_Tracker::update_vehicle_sensor_status_flags()
|
|||
|
||||
// avoid building/linking LTM:
|
||||
void AP_LTM_Telem::init() {};
|
||||
#if AP_DEVO_TELEM_ENABLED
|
||||
// avoid building/linking Devo:
|
||||
void AP_DEVO_Telem::init() {};
|
||||
#endif
|
||||
|
|
|
@ -98,5 +98,7 @@ void GCS_Sub::update_vehicle_sensor_status_flags()
|
|||
|
||||
// avoid building/linking LTM:
|
||||
void AP_LTM_Telem::init() {};
|
||||
#if AP_DEVO_TELEM_ENABLED
|
||||
// avoid building/linking Devo:
|
||||
void AP_DEVO_Telem::init() {};
|
||||
#endif
|
||||
|
|
|
@ -110,8 +110,10 @@ bool AP_AdvancedFailsafe::gcs_terminate(bool should_terminate, const char *reaso
|
|||
|
||||
// avoid building/linking LTM:
|
||||
void AP_LTM_Telem::init() {};
|
||||
#if AP_DEVO_TELEM_ENABLED
|
||||
// avoid building/linking Devo:
|
||||
void AP_DEVO_Telem::init() {};
|
||||
#endif
|
||||
|
||||
void ReplayVehicle::init_ardupilot(void)
|
||||
{
|
||||
|
|
|
@ -17,20 +17,22 @@
|
|||
DEVO Telemetry library
|
||||
*/
|
||||
|
||||
#define DEVOM_SYNC_BYTE 0xAA
|
||||
|
||||
|
||||
#define AP_SERIALMANAGER_DEVO_TELEM_BAUD 38400
|
||||
#define AP_SERIALMANAGER_DEVO_BUFSIZE_RX 0
|
||||
#define AP_SERIALMANAGER_DEVO_BUFSIZE_TX 32
|
||||
|
||||
#include "AP_Devo_Telem.h"
|
||||
|
||||
#if AP_DEVO_TELEM_ENABLED
|
||||
|
||||
#include <AP_AHRS/AP_AHRS.h>
|
||||
#include <AP_GPS/AP_GPS.h>
|
||||
#include <AP_BattMonitor/AP_BattMonitor.h>
|
||||
#include <GCS_MAVLink/GCS.h>
|
||||
|
||||
#define DEVOM_SYNC_BYTE 0xAA
|
||||
#define AP_SERIALMANAGER_DEVO_TELEM_BAUD 38400
|
||||
#define AP_SERIALMANAGER_DEVO_BUFSIZE_RX 0
|
||||
#define AP_SERIALMANAGER_DEVO_BUFSIZE_TX 32
|
||||
|
||||
extern const AP_HAL::HAL& hal;
|
||||
|
||||
void AP_DEVO_Telem::init()
|
||||
|
@ -133,3 +135,4 @@ void AP_DEVO_Telem::tick(void)
|
|||
send_frames();
|
||||
}
|
||||
}
|
||||
#endif
|
||||
|
|
|
@ -18,6 +18,11 @@
|
|||
#include <AP_HAL/AP_HAL.h>
|
||||
#include <AP_SerialManager/AP_SerialManager.h>
|
||||
|
||||
#ifndef AP_DEVO_TELEM_ENABLED
|
||||
#define AP_DEVO_TELEM_ENABLED 0
|
||||
#endif
|
||||
|
||||
#if AP_DEVO_TELEM_ENABLED
|
||||
class AP_DEVO_Telem {
|
||||
public:
|
||||
//constructor
|
||||
|
@ -43,3 +48,4 @@ private:
|
|||
uint32_t _last_frame_ms;
|
||||
|
||||
};
|
||||
#endif
|
||||
|
|
|
@ -1050,6 +1050,9 @@ public:
|
|||
#if !HAL_MINIMIZE_FEATURES
|
||||
// LTM backend
|
||||
AP_LTM_Telem ltm_telemetry;
|
||||
#endif
|
||||
|
||||
#if AP_DEVO_TELEM_ENABLED
|
||||
// Devo backend
|
||||
AP_DEVO_Telem devo_telemetry;
|
||||
#endif
|
||||
|
|
|
@ -2232,6 +2232,9 @@ void GCS::setup_uarts()
|
|||
}
|
||||
#if !HAL_MINIMIZE_FEATURES
|
||||
ltm_telemetry.init();
|
||||
#endif
|
||||
|
||||
#if AP_DEVO_TELEM_ENABLED
|
||||
devo_telemetry.init();
|
||||
#endif
|
||||
}
|
||||
|
|
Loading…
Reference in New Issue