Browse Source

AP_LTM_Telem: add AP_LTM_TELEM_ENABLED

apm_2208
Peter Barker 3 years ago committed by Peter Barker
parent
commit
75862b3e27
  1. 4
      libraries/AP_LTM_Telem/AP_LTM_Telem.cpp
  2. 8
      libraries/AP_LTM_Telem/AP_LTM_Telem.h

4
libraries/AP_LTM_Telem/AP_LTM_Telem.cpp

@ -17,6 +17,8 @@ @@ -17,6 +17,8 @@
#include "AP_LTM_Telem.h"
#if AP_LTM_TELEM_ENABLED
#include <AP_AHRS/AP_AHRS.h>
#include <AP_GPS/AP_GPS.h>
#include <AP_BattMonitor/AP_BattMonitor.h>
@ -216,3 +218,5 @@ void AP_LTM_Telem::tick(void) @@ -216,3 +218,5 @@ void AP_LTM_Telem::tick(void)
generate_LTM();
}
}
#endif // AP_LTM_TELEM_ENABLED

8
libraries/AP_LTM_Telem/AP_LTM_Telem.h

@ -16,6 +16,12 @@ @@ -16,6 +16,12 @@
#include <AP_HAL/AP_HAL.h>
#ifndef AP_LTM_TELEM_ENABLED
#define AP_LTM_TELEM_ENABLED !HAL_MINIMIZE_FEATURES
#endif
#if AP_LTM_TELEM_ENABLED
static const uint8_t LTM_GFRAME_SIZE = 18;
static const uint8_t LTM_AFRAME_SIZE = 10;
static const uint8_t LTM_SFRAME_SIZE = 11;
@ -45,3 +51,5 @@ private: @@ -45,3 +51,5 @@ private:
void send_LTM(uint8_t lt_packet[], uint8_t lt_packet_size);
void tick(void); // tick - main call to send updates to transmitter (called by scheduler at 1kHz)
};
#endif

Loading…
Cancel
Save