AP_RCProtocol: allow FRSky to be compiled out
This commit is contained in:
parent
dd35ca4583
commit
64193542ed
@ -50,10 +50,14 @@ void AP_RCProtocol::init()
|
|||||||
backend[AP_RCProtocol::SBUS_NI] = new AP_RCProtocol_SBUS(*this, false, 100000);
|
backend[AP_RCProtocol::SBUS_NI] = new AP_RCProtocol_SBUS(*this, false, 100000);
|
||||||
backend[AP_RCProtocol::SRXL2] = new AP_RCProtocol_SRXL2(*this);
|
backend[AP_RCProtocol::SRXL2] = new AP_RCProtocol_SRXL2(*this);
|
||||||
backend[AP_RCProtocol::CRSF] = new AP_RCProtocol_CRSF(*this);
|
backend[AP_RCProtocol::CRSF] = new AP_RCProtocol_CRSF(*this);
|
||||||
|
#if AP_RCPROTOCOL_FPORT2_ENABLED
|
||||||
backend[AP_RCProtocol::FPORT2] = new AP_RCProtocol_FPort2(*this, true);
|
backend[AP_RCProtocol::FPORT2] = new AP_RCProtocol_FPort2(*this, true);
|
||||||
|
#endif
|
||||||
#endif
|
#endif
|
||||||
backend[AP_RCProtocol::ST24] = new AP_RCProtocol_ST24(*this);
|
backend[AP_RCProtocol::ST24] = new AP_RCProtocol_ST24(*this);
|
||||||
|
#if AP_RCPROTOCOL_FPORT_ENABLED
|
||||||
backend[AP_RCProtocol::FPORT] = new AP_RCProtocol_FPort(*this, true);
|
backend[AP_RCProtocol::FPORT] = new AP_RCProtocol_FPort(*this, true);
|
||||||
|
#endif
|
||||||
}
|
}
|
||||||
|
|
||||||
AP_RCProtocol::~AP_RCProtocol()
|
AP_RCProtocol::~AP_RCProtocol()
|
||||||
@ -419,10 +423,14 @@ const char *AP_RCProtocol::protocol_name_from_protocol(rcprotocol_t protocol)
|
|||||||
return "CRSF";
|
return "CRSF";
|
||||||
case ST24:
|
case ST24:
|
||||||
return "ST24";
|
return "ST24";
|
||||||
|
#if AP_RCPROTOCOL_FPORT_ENABLED
|
||||||
case FPORT:
|
case FPORT:
|
||||||
return "FPORT";
|
return "FPORT";
|
||||||
|
#endif
|
||||||
|
#if AP_RCPROTOCOL_FPORT2_ENABLED
|
||||||
case FPORT2:
|
case FPORT2:
|
||||||
return "FPORT2";
|
return "FPORT2";
|
||||||
|
#endif
|
||||||
case NONE:
|
case NONE:
|
||||||
break;
|
break;
|
||||||
}
|
}
|
||||||
|
@ -15,6 +15,9 @@
|
|||||||
* Code by Andrew Tridgell and Siddharth Bharat Purohit
|
* Code by Andrew Tridgell and Siddharth Bharat Purohit
|
||||||
*/
|
*/
|
||||||
#pragma once
|
#pragma once
|
||||||
|
|
||||||
|
#include "AP_RCProtocol_config.h"
|
||||||
|
|
||||||
#include <AP_HAL/AP_HAL.h>
|
#include <AP_HAL/AP_HAL.h>
|
||||||
#include <AP_Common/AP_Common.h>
|
#include <AP_Common/AP_Common.h>
|
||||||
|
|
||||||
@ -48,8 +51,12 @@ public:
|
|||||||
SRXL2 = 7,
|
SRXL2 = 7,
|
||||||
CRSF = 8,
|
CRSF = 8,
|
||||||
ST24 = 9,
|
ST24 = 9,
|
||||||
|
#if AP_RCPROTOCOL_FPORT_ENABLED
|
||||||
FPORT = 10,
|
FPORT = 10,
|
||||||
|
#endif
|
||||||
|
#if AP_RCPROTOCOL_FPORT2_ENABLED
|
||||||
FPORT2 = 11,
|
FPORT2 = 11,
|
||||||
|
#endif
|
||||||
#if AP_RCPROTOCOL_FASTSBUS_ENABLED
|
#if AP_RCPROTOCOL_FASTSBUS_ENABLED
|
||||||
FASTSBUS = 12,
|
FASTSBUS = 12,
|
||||||
#endif
|
#endif
|
||||||
@ -88,8 +95,12 @@ public:
|
|||||||
case SBUS:
|
case SBUS:
|
||||||
case SBUS_NI:
|
case SBUS_NI:
|
||||||
case PPM:
|
case PPM:
|
||||||
|
#if AP_RCPROTOCOL_FPORT_ENABLED
|
||||||
case FPORT:
|
case FPORT:
|
||||||
|
#endif
|
||||||
|
#if AP_RCPROTOCOL_FPORT2_ENABLED
|
||||||
case FPORT2:
|
case FPORT2:
|
||||||
|
#endif
|
||||||
return true;
|
return true;
|
||||||
case IBUS:
|
case IBUS:
|
||||||
case SUMD:
|
case SUMD:
|
||||||
|
@ -18,6 +18,9 @@
|
|||||||
*/
|
*/
|
||||||
|
|
||||||
#include "AP_RCProtocol_FPort.h"
|
#include "AP_RCProtocol_FPort.h"
|
||||||
|
|
||||||
|
#if AP_RCPROTOCOL_FPORT_ENABLED
|
||||||
|
|
||||||
#include <AP_Vehicle/AP_Vehicle_Type.h>
|
#include <AP_Vehicle/AP_Vehicle_Type.h>
|
||||||
#include <AP_Frsky_Telem/AP_Frsky_Telem.h>
|
#include <AP_Frsky_Telem/AP_Frsky_Telem.h>
|
||||||
#include <RC_Channel/RC_Channel.h>
|
#include <RC_Channel/RC_Channel.h>
|
||||||
@ -315,3 +318,5 @@ void AP_RCProtocol_FPort::process_byte(uint8_t b, uint32_t baudrate)
|
|||||||
}
|
}
|
||||||
_process_byte(AP_HAL::micros(), b);
|
_process_byte(AP_HAL::micros(), b);
|
||||||
}
|
}
|
||||||
|
|
||||||
|
#endif // AP_RCPROTOCOL_FPORT_ENABLED
|
||||||
|
@ -17,10 +17,13 @@
|
|||||||
|
|
||||||
#pragma once
|
#pragma once
|
||||||
|
|
||||||
#include <AP_Frsky_Telem/AP_Frsky_SPort.h>
|
#include "AP_RCProtocol_config.h"
|
||||||
|
|
||||||
|
#if AP_RCPROTOCOL_FPORT_ENABLED
|
||||||
|
|
||||||
#include "AP_RCProtocol.h"
|
#include "AP_RCProtocol.h"
|
||||||
#include "SoftSerial.h"
|
#include "SoftSerial.h"
|
||||||
|
#include <AP_Frsky_Telem/AP_Frsky_SPort.h>
|
||||||
|
|
||||||
#define FPORT_CONTROL_FRAME_SIZE 29
|
#define FPORT_CONTROL_FRAME_SIZE 29
|
||||||
|
|
||||||
@ -61,3 +64,5 @@ private:
|
|||||||
// if the receiver is not controlling frame rate apply a constraint on consecutive frames
|
// if the receiver is not controlling frame rate apply a constraint on consecutive frames
|
||||||
uint8_t consecutive_telemetry_frame_count;
|
uint8_t consecutive_telemetry_frame_count;
|
||||||
};
|
};
|
||||||
|
|
||||||
|
#endif // AP_RCPROTOCOL_FPORT_ENABLED
|
||||||
|
@ -18,6 +18,9 @@
|
|||||||
*/
|
*/
|
||||||
|
|
||||||
#include "AP_RCProtocol_FPort2.h"
|
#include "AP_RCProtocol_FPort2.h"
|
||||||
|
|
||||||
|
#if AP_RCPROTOCOL_FPORT2_ENABLED
|
||||||
|
|
||||||
#include <AP_Vehicle/AP_Vehicle_Type.h>
|
#include <AP_Vehicle/AP_Vehicle_Type.h>
|
||||||
#include <AP_Frsky_Telem/AP_Frsky_Telem.h>
|
#include <AP_Frsky_Telem/AP_Frsky_Telem.h>
|
||||||
#include <RC_Channel/RC_Channel.h>
|
#include <RC_Channel/RC_Channel.h>
|
||||||
@ -294,3 +297,5 @@ void AP_RCProtocol_FPort2::process_byte(uint8_t b, uint32_t baudrate)
|
|||||||
}
|
}
|
||||||
_process_byte(AP_HAL::micros(), b);
|
_process_byte(AP_HAL::micros(), b);
|
||||||
}
|
}
|
||||||
|
|
||||||
|
#endif // AP_RCPROTOCOL_FPORT2_ENABLED
|
||||||
|
@ -17,10 +17,13 @@
|
|||||||
|
|
||||||
#pragma once
|
#pragma once
|
||||||
|
|
||||||
#include <AP_Frsky_Telem/AP_Frsky_SPort.h>
|
#include "AP_RCProtocol_config.h"
|
||||||
|
|
||||||
|
#if AP_RCPROTOCOL_FPORT2_ENABLED
|
||||||
|
|
||||||
#include "AP_RCProtocol.h"
|
#include "AP_RCProtocol.h"
|
||||||
#include "SoftSerial.h"
|
#include "SoftSerial.h"
|
||||||
|
#include <AP_Frsky_Telem/AP_Frsky_SPort.h>
|
||||||
|
|
||||||
#define FPORT2_CONTROL_FRAME_SIZE 38
|
#define FPORT2_CONTROL_FRAME_SIZE 38
|
||||||
|
|
||||||
@ -58,3 +61,5 @@ private:
|
|||||||
AP_Frsky_SPort::sport_packet_t packet;
|
AP_Frsky_SPort::sport_packet_t packet;
|
||||||
} telem_data;
|
} telem_data;
|
||||||
};
|
};
|
||||||
|
|
||||||
|
#endif // AP_RCPROTOCOL_FPORT2_ENABLED
|
||||||
|
10
libraries/AP_RCProtocol/AP_RCProtocol_config.h
Normal file
10
libraries/AP_RCProtocol/AP_RCProtocol_config.h
Normal file
@ -0,0 +1,10 @@
|
|||||||
|
#pragma once
|
||||||
|
|
||||||
|
#include <AP_Frsky_Telem/AP_Frsky_config.h>
|
||||||
|
|
||||||
|
#ifndef AP_RCPROTOCOL_FPORT_ENABLED
|
||||||
|
#define AP_RCPROTOCOL_FPORT_ENABLED AP_FRSKY_SPORT_TELEM_ENABLED
|
||||||
|
#endif
|
||||||
|
#ifndef AP_RCPROTOCOL_FPORT2_ENABLED
|
||||||
|
#define AP_RCPROTOCOL_FPORT2_ENABLED AP_FRSKY_SPORT_TELEM_ENABLED
|
||||||
|
#endif
|
Loading…
Reference in New Issue
Block a user