AP_Frsky_Telem: allow FRSky to be compiled out

This commit is contained in:
Peter Barker 2022-04-17 12:54:07 +10:00 committed by Peter Barker
parent d0ce2ca8f2
commit 6eae090fc8
13 changed files with 87 additions and 9 deletions

View File

@ -1,5 +1,7 @@
#include "AP_Frsky_Backend.h" #include "AP_Frsky_Backend.h"
#if AP_FRSKY_TELEM_ENABLED
#include <AP_Baro/AP_Baro.h> #include <AP_Baro/AP_Baro.h>
#include <AP_AHRS/AP_AHRS.h> #include <AP_AHRS/AP_AHRS.h>
#include <AP_RPM/AP_RPM.h> #include <AP_RPM/AP_RPM.h>
@ -164,3 +166,5 @@ bool AP_Frsky_Backend::calc_rpm(const uint8_t instance, int32_t &value) const
return false; return false;
#endif #endif
} }
#endif // AP_FRSKY_TELEM_ENABLED

View File

@ -1,11 +1,10 @@
#pragma once #pragma once
#include <AP_HAL/AP_HAL.h> #include "AP_Frsky_config.h"
#include <GCS_MAVLink/GCS_MAVLink.h>
#ifndef HAL_WITH_FRSKY_TELEM_BIDIRECTIONAL #if AP_FRSKY_TELEM_ENABLED
#define HAL_WITH_FRSKY_TELEM_BIDIRECTIONAL 1
#endif #include <GCS_MAVLink/GCS_MAVLink.h>
class AP_Frsky_Backend class AP_Frsky_Backend
{ {
@ -148,3 +147,5 @@ private:
void loop(void); void loop(void);
}; };
#endif // AP_FRSKY_TELEM_ENABLED

View File

@ -1,5 +1,7 @@
#include "AP_Frsky_D.h" #include "AP_Frsky_D.h"
#if AP_FRSKY_D_TELEM_ENABLED
#include <AP_AHRS/AP_AHRS.h> #include <AP_AHRS/AP_AHRS.h>
#include <AP_BattMonitor/AP_BattMonitor.h> #include <AP_BattMonitor/AP_BattMonitor.h>
#include <AP_GPS/AP_GPS.h> #include <AP_GPS/AP_GPS.h>
@ -82,3 +84,5 @@ void AP_Frsky_D::send(void)
} }
} }
} }
#endif // AP_FRSKY_D_TELEM_ENABLED

View File

@ -2,6 +2,8 @@
#include "AP_Frsky_Backend.h" #include "AP_Frsky_Backend.h"
#if AP_FRSKY_D_TELEM_ENABLED
class AP_Frsky_D : public AP_Frsky_Backend class AP_Frsky_D : public AP_Frsky_Backend
{ {
@ -29,3 +31,5 @@ private:
} _D; } _D;
}; };
#endif // AP_FRSKY_D_TELEM_ENABLED

View File

@ -1,5 +1,9 @@
#pragma once #pragma once
#include "AP_Frsky_config.h"
#if HAL_WITH_FRSKY_TELEM_BIDIRECTIONAL
#include "AP_Frsky_MAVlite_Message.h" #include "AP_Frsky_MAVlite_Message.h"
#include "AP_Frsky_SPort.h" #include "AP_Frsky_SPort.h"
@ -7,7 +11,6 @@
#include <stdint.h> #include <stdint.h>
#if HAL_WITH_FRSKY_TELEM_BIDIRECTIONAL
/* /*
* An instance of this class encodes a MAVlite message into several * An instance of this class encodes a MAVlite message into several
* SPort packets, and pushes them onto the supplied queue. * SPort packets, and pushes them onto the supplied queue.
@ -51,4 +54,5 @@ private:
int16_t checksum; // sent at end of packet int16_t checksum; // sent at end of packet
void update_checksum(const uint8_t c); void update_checksum(const uint8_t c);
}; };
#endif
#endif // HAL_WITH_FRSKY_TELEM_BIDIRECTIONAL

View File

@ -1,5 +1,7 @@
#include "AP_Frsky_SPort.h" #include "AP_Frsky_SPort.h"
#if AP_FRSKY_SPORT_TELEM_ENABLED
#include <AP_HAL/utility/sparse-endian.h> #include <AP_HAL/utility/sparse-endian.h>
#include <AP_BattMonitor/AP_BattMonitor.h> #include <AP_BattMonitor/AP_BattMonitor.h>
#include <AP_GPS/AP_GPS.h> #include <AP_GPS/AP_GPS.h>
@ -472,3 +474,5 @@ namespace AP {
return AP_Frsky_SPort::get_singleton(); return AP_Frsky_SPort::get_singleton();
} }
}; };
#endif // AP_FRSKY_SPORT_TELEM_ENABLED

View File

@ -2,6 +2,8 @@
#include "AP_Frsky_Backend.h" #include "AP_Frsky_Backend.h"
#if AP_FRSKY_SPORT_TELEM_ENABLED
class AP_Frsky_SPort : public AP_Frsky_Backend class AP_Frsky_SPort : public AP_Frsky_Backend
{ {
@ -64,3 +66,5 @@ private:
namespace AP { namespace AP {
AP_Frsky_SPort *frsky_sport(); AP_Frsky_SPort *frsky_sport();
}; };
#endif // AP_FRSKY_SPORT_TELEM_ENABLED

View File

@ -1,9 +1,9 @@
#pragma once #pragma once
#include <AP_HAL/AP_HAL.h>
#include "AP_Frsky_SPort.h" #include "AP_Frsky_SPort.h"
#if AP_FRSKY_SPORT_TELEM_ENABLED
#include <stdint.h> #include <stdint.h>
// for SPort X protocol // for SPort X protocol
@ -47,3 +47,5 @@ private:
bool should_process_packet(const uint8_t *packet, bool discard_duplicates); bool should_process_packet(const uint8_t *packet, bool discard_duplicates);
bool get_packet(AP_Frsky_SPort::sport_packet_t &sport_packet, bool discard_duplicates); bool get_packet(AP_Frsky_SPort::sport_packet_t &sport_packet, bool discard_duplicates);
}; };
#endif // AP_FRSKY_SPORT_TELEM_ENABLED

View File

@ -1,5 +1,7 @@
#include "AP_Frsky_SPort_Passthrough.h" #include "AP_Frsky_SPort_Passthrough.h"
#if AP_FRSKY_SPORT_PASSTHROUGH_ENABLED
#include <AP_AHRS/AP_AHRS.h> #include <AP_AHRS/AP_AHRS.h>
#include <AP_BattMonitor/AP_BattMonitor.h> #include <AP_BattMonitor/AP_BattMonitor.h>
#include <AP_GPS/AP_GPS.h> #include <AP_GPS/AP_GPS.h>
@ -966,3 +968,5 @@ AP_Frsky_SPort_Passthrough *frsky_passthrough_telem()
return AP_Frsky_SPort_Passthrough::get_singleton(); return AP_Frsky_SPort_Passthrough::get_singleton();
} }
}; };
#endif // AP_FRSKY_SPORT_PASSTHROUGH_ENABLED

View File

@ -1,6 +1,9 @@
#pragma once #pragma once
#include "AP_Frsky_SPort.h" #include "AP_Frsky_SPort.h"
#if AP_FRSKY_SPORT_PASSTHROUGH_ENABLED
#include <AP_RCTelemetry/AP_RCTelemetry.h> #include <AP_RCTelemetry/AP_RCTelemetry.h>
#include "AP_Frsky_SPortParser.h" #include "AP_Frsky_SPortParser.h"
@ -173,3 +176,6 @@ private:
namespace AP { namespace AP {
AP_Frsky_SPort_Passthrough *frsky_passthrough_telem(); AP_Frsky_SPort_Passthrough *frsky_passthrough_telem();
}; };
#endif // AP_FRSKY_SPORT_PASSTHROUGH_ENABLED

View File

@ -22,6 +22,10 @@
FRSKY Telemetry library FRSKY Telemetry library
*/ */
#include "AP_Frsky_config.h"
#if AP_FRSKY_TELEM_ENABLED
#include "AP_Frsky_Telem.h" #include "AP_Frsky_Telem.h"
#include "AP_Frsky_Parameters.h" #include "AP_Frsky_Parameters.h"
@ -61,11 +65,17 @@ bool AP_Frsky_Telem::init(bool use_external_data)
// check for protocol configured for a serial port - only the first serial port with one of these protocols will then run (cannot have FrSky on multiple serial ports) // check for protocol configured for a serial port - only the first serial port with one of these protocols will then run (cannot have FrSky on multiple serial ports)
AP_HAL::UARTDriver *port; AP_HAL::UARTDriver *port;
if ((port = serial_manager.find_serial(AP_SerialManager::SerialProtocol_FrSky_D, 0))) { if ((port = serial_manager.find_serial(AP_SerialManager::SerialProtocol_FrSky_D, 0))) {
#if AP_FRSKY_D_TELEM_ENABLED
_backend = new AP_Frsky_D(port); _backend = new AP_Frsky_D(port);
#endif
} else if ((port = serial_manager.find_serial(AP_SerialManager::SerialProtocol_FrSky_SPort, 0))) { } else if ((port = serial_manager.find_serial(AP_SerialManager::SerialProtocol_FrSky_SPort, 0))) {
#if AP_FRSKY_SPORT_TELEM_ENABLED
_backend = new AP_Frsky_SPort(port); _backend = new AP_Frsky_SPort(port);
#endif
} else if (use_external_data || (port = serial_manager.find_serial(AP_SerialManager::SerialProtocol_FrSky_SPort_Passthrough, 0))) { } else if (use_external_data || (port = serial_manager.find_serial(AP_SerialManager::SerialProtocol_FrSky_SPort_Passthrough, 0))) {
#if AP_FRSKY_SPORT_PASSTHROUGH_ENABLED
_backend = new AP_Frsky_SPort_Passthrough(port, use_external_data, _frsky_parameters); _backend = new AP_Frsky_SPort_Passthrough(port, use_external_data, _frsky_parameters);
#endif
} }
if (_backend == nullptr) { if (_backend == nullptr) {
@ -147,3 +157,5 @@ AP_Frsky_Telem *frsky_telem()
return AP_Frsky_Telem::get_singleton(); return AP_Frsky_Telem::get_singleton();
} }
}; };
#endif // AP_FRSKY_TELEM_ENABLED

View File

@ -14,6 +14,10 @@
*/ */
#pragma once #pragma once
#include "AP_Frsky_config.h"
#if AP_FRSKY_TELEM_ENABLED
#include "AP_Frsky_Backend.h" #include "AP_Frsky_Backend.h"
#include "AP_Frsky_SPort.h" #include "AP_Frsky_SPort.h"
@ -69,3 +73,5 @@ private:
namespace AP { namespace AP {
AP_Frsky_Telem *frsky_telem(); AP_Frsky_Telem *frsky_telem();
}; };
#endif // AP_FRSKY_TELEM_ENABLED

View File

@ -0,0 +1,23 @@
#pragma once
#include <AP_HAL/AP_HAL_Boards.h>
#ifndef AP_FRSKY_TELEM_ENABLED
#define AP_FRSKY_TELEM_ENABLED 1
#endif
#ifndef AP_FRSKY_D_TELEM_ENABLED
#define AP_FRSKY_D_TELEM_ENABLED AP_FRSKY_TELEM_ENABLED
#endif
#ifndef AP_FRSKY_SPORT_TELEM_ENABLED
#define AP_FRSKY_SPORT_TELEM_ENABLED AP_FRSKY_TELEM_ENABLED
#endif
#ifndef AP_FRSKY_SPORT_PASSTHROUGH_ENABLED
#define AP_FRSKY_SPORT_PASSTHROUGH_ENABLED AP_FRSKY_SPORT_TELEM_ENABLED
#endif
#ifndef HAL_WITH_FRSKY_TELEM_BIDIRECTIONAL
#define HAL_WITH_FRSKY_TELEM_BIDIRECTIONAL AP_FRSKY_SPORT_PASSTHROUGH_ENABLED
#endif