Browse Source

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
gps-1.3.1
Shiv Tyagi 3 years ago committed by Andrew Tridgell
parent
commit
339a07b8d3
  1. 2
      AntennaTracker/GCS_Tracker.cpp
  2. 2
      ArduSub/GCS_Sub.cpp
  3. 2
      Tools/Replay/Replay.cpp
  4. 13
      libraries/AP_Devo_Telem/AP_Devo_Telem.cpp
  5. 6
      libraries/AP_Devo_Telem/AP_Devo_Telem.h
  6. 3
      libraries/GCS_MAVLink/GCS.h
  7. 3
      libraries/GCS_MAVLink/GCS_Common.cpp

2
AntennaTracker/GCS_Tracker.cpp

@ -60,5 +60,7 @@ void GCS_Tracker::update_vehicle_sensor_status_flags() @@ -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

2
ArduSub/GCS_Sub.cpp

@ -98,5 +98,7 @@ void GCS_Sub::update_vehicle_sensor_status_flags() @@ -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

2
Tools/Replay/Replay.cpp

@ -110,8 +110,10 @@ bool AP_AdvancedFailsafe::gcs_terminate(bool should_terminate, const char *reaso @@ -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)
{

13
libraries/AP_Devo_Telem/AP_Devo_Telem.cpp

@ -17,20 +17,22 @@ @@ -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) @@ -133,3 +135,4 @@ void AP_DEVO_Telem::tick(void)
send_frames();
}
}
#endif

6
libraries/AP_Devo_Telem/AP_Devo_Telem.h

@ -18,6 +18,11 @@ @@ -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: @@ -43,3 +48,4 @@ private:
uint32_t _last_frame_ms;
};
#endif

3
libraries/GCS_MAVLink/GCS.h

@ -1050,6 +1050,9 @@ public: @@ -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

3
libraries/GCS_MAVLink/GCS_Common.cpp

@ -2232,6 +2232,9 @@ void GCS::setup_uarts() @@ -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…
Cancel
Save