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:
Shiv Tyagi 2021-11-19 09:04:22 +05:30 committed by Andrew Tridgell
parent 5224468ec6
commit 339a07b8d3
7 changed files with 26 additions and 5 deletions

View File

@ -60,5 +60,7 @@ void GCS_Tracker::update_vehicle_sensor_status_flags()
// avoid building/linking LTM: // avoid building/linking LTM:
void AP_LTM_Telem::init() {}; void AP_LTM_Telem::init() {};
#if AP_DEVO_TELEM_ENABLED
// avoid building/linking Devo: // avoid building/linking Devo:
void AP_DEVO_Telem::init() {}; void AP_DEVO_Telem::init() {};
#endif

View File

@ -98,5 +98,7 @@ void GCS_Sub::update_vehicle_sensor_status_flags()
// avoid building/linking LTM: // avoid building/linking LTM:
void AP_LTM_Telem::init() {}; void AP_LTM_Telem::init() {};
#if AP_DEVO_TELEM_ENABLED
// avoid building/linking Devo: // avoid building/linking Devo:
void AP_DEVO_Telem::init() {}; void AP_DEVO_Telem::init() {};
#endif

View File

@ -110,8 +110,10 @@ bool AP_AdvancedFailsafe::gcs_terminate(bool should_terminate, const char *reaso
// avoid building/linking LTM: // avoid building/linking LTM:
void AP_LTM_Telem::init() {}; void AP_LTM_Telem::init() {};
#if AP_DEVO_TELEM_ENABLED
// avoid building/linking Devo: // avoid building/linking Devo:
void AP_DEVO_Telem::init() {}; void AP_DEVO_Telem::init() {};
#endif
void ReplayVehicle::init_ardupilot(void) void ReplayVehicle::init_ardupilot(void)
{ {

View File

@ -17,20 +17,22 @@
DEVO Telemetry library 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" #include "AP_Devo_Telem.h"
#if AP_DEVO_TELEM_ENABLED
#include <AP_AHRS/AP_AHRS.h> #include <AP_AHRS/AP_AHRS.h>
#include <AP_GPS/AP_GPS.h> #include <AP_GPS/AP_GPS.h>
#include <AP_BattMonitor/AP_BattMonitor.h> #include <AP_BattMonitor/AP_BattMonitor.h>
#include <GCS_MAVLink/GCS.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; extern const AP_HAL::HAL& hal;
void AP_DEVO_Telem::init() void AP_DEVO_Telem::init()
@ -133,3 +135,4 @@ void AP_DEVO_Telem::tick(void)
send_frames(); send_frames();
} }
} }
#endif

View File

@ -18,6 +18,11 @@
#include <AP_HAL/AP_HAL.h> #include <AP_HAL/AP_HAL.h>
#include <AP_SerialManager/AP_SerialManager.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 { class AP_DEVO_Telem {
public: public:
//constructor //constructor
@ -43,3 +48,4 @@ private:
uint32_t _last_frame_ms; uint32_t _last_frame_ms;
}; };
#endif

View File

@ -1050,6 +1050,9 @@ public:
#if !HAL_MINIMIZE_FEATURES #if !HAL_MINIMIZE_FEATURES
// LTM backend // LTM backend
AP_LTM_Telem ltm_telemetry; AP_LTM_Telem ltm_telemetry;
#endif
#if AP_DEVO_TELEM_ENABLED
// Devo backend // Devo backend
AP_DEVO_Telem devo_telemetry; AP_DEVO_Telem devo_telemetry;
#endif #endif

View File

@ -2232,6 +2232,9 @@ void GCS::setup_uarts()
} }
#if !HAL_MINIMIZE_FEATURES #if !HAL_MINIMIZE_FEATURES
ltm_telemetry.init(); ltm_telemetry.init();
#endif
#if AP_DEVO_TELEM_ENABLED
devo_telemetry.init(); devo_telemetry.init();
#endif #endif
} }