mirror of https://github.com/ArduPilot/ardupilot
AP_SBusOut: add and use AP_SBUSOUTPUT_ENABLED
.... which will allow periphs to instantiate this if they really feel like it, and for it to be removed on smaller boards on the custom build server (and potentially on lower-specced boards.
This commit is contained in:
parent
3869c4c0e9
commit
f99f9741fb
|
@ -37,6 +37,11 @@
|
||||||
* POSSIBILITY OF SUCH DAMAGE.
|
* POSSIBILITY OF SUCH DAMAGE.
|
||||||
*
|
*
|
||||||
*/
|
*/
|
||||||
|
|
||||||
|
#include "AP_SBusOut_config.h"
|
||||||
|
|
||||||
|
#if AP_SBUSOUTPUT_ENABLED
|
||||||
|
|
||||||
#include "AP_SBusOut.h"
|
#include "AP_SBusOut.h"
|
||||||
#include <AP_Math/AP_Math.h>
|
#include <AP_Math/AP_Math.h>
|
||||||
#include <AP_SerialManager/AP_SerialManager.h>
|
#include <AP_SerialManager/AP_SerialManager.h>
|
||||||
|
@ -189,3 +194,4 @@ void AP_SBusOut::init() {
|
||||||
sbus1_uart = serial_manager->find_serial(AP_SerialManager::SerialProtocol_Sbus1,0);
|
sbus1_uart = serial_manager->find_serial(AP_SerialManager::SerialProtocol_Sbus1,0);
|
||||||
}
|
}
|
||||||
|
|
||||||
|
#endif // AP_SBUSOUTPUT_ENABLED
|
||||||
|
|
|
@ -7,6 +7,10 @@
|
||||||
|
|
||||||
#pragma once
|
#pragma once
|
||||||
|
|
||||||
|
#include "AP_SBusOut_config.h"
|
||||||
|
|
||||||
|
#if AP_SBUSOUTPUT_ENABLED
|
||||||
|
|
||||||
#include <AP_HAL/AP_HAL.h>
|
#include <AP_HAL/AP_HAL.h>
|
||||||
#include <AP_Param/AP_Param.h>
|
#include <AP_Param/AP_Param.h>
|
||||||
|
|
||||||
|
@ -35,3 +39,5 @@ private:
|
||||||
AP_Int16 sbus_rate;
|
AP_Int16 sbus_rate;
|
||||||
bool initialised;
|
bool initialised;
|
||||||
};
|
};
|
||||||
|
|
||||||
|
#endif // AP_SBUSOUTPUT_ENABLED
|
||||||
|
|
|
@ -0,0 +1,7 @@
|
||||||
|
#pragma once
|
||||||
|
|
||||||
|
#include <AP_HAL/AP_HAL_Boards.h>
|
||||||
|
|
||||||
|
#ifndef AP_SBUSOUTPUT_ENABLED
|
||||||
|
#define AP_SBUSOUTPUT_ENABLED 1
|
||||||
|
#endif
|
Loading…
Reference in New Issue