mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-03 06:28:27 -04:00
HAL_Linux: fixed build
This commit is contained in:
parent
8019d45200
commit
a8946a5f31
@ -1,3 +1,6 @@
|
|||||||
|
#include <AP_HAL.h>
|
||||||
|
|
||||||
|
#if CONFIG_HAL_BOARD == HAL_BOARD_LINUX
|
||||||
#include "AnalogIn.h"
|
#include "AnalogIn.h"
|
||||||
|
|
||||||
using namespace Linux;
|
using namespace Linux;
|
||||||
@ -41,4 +44,4 @@ AP_HAL::AnalogSource* LinuxAnalogIn::channel(int16_t n) {
|
|||||||
return new LinuxAnalogSource(1.11);
|
return new LinuxAnalogSource(1.11);
|
||||||
}
|
}
|
||||||
|
|
||||||
|
#endif // CONFIG_HAL_BOARD
|
||||||
|
@ -1,3 +1,6 @@
|
|||||||
|
#include <AP_HAL.h>
|
||||||
|
|
||||||
|
#if CONFIG_HAL_BOARD == HAL_BOARD_LINUX
|
||||||
|
|
||||||
#include "GPIO.h"
|
#include "GPIO.h"
|
||||||
|
|
||||||
@ -62,3 +65,5 @@ void LinuxDigitalSource::write(uint8_t value) {
|
|||||||
void LinuxDigitalSource::toggle() {
|
void LinuxDigitalSource::toggle() {
|
||||||
_v = !_v;
|
_v = !_v;
|
||||||
}
|
}
|
||||||
|
|
||||||
|
#endif // CONFIG_HAL_BOARD
|
||||||
|
@ -1,3 +1,6 @@
|
|||||||
|
#include <AP_HAL.h>
|
||||||
|
|
||||||
|
#if CONFIG_HAL_BOARD == HAL_BOARD_LINUX
|
||||||
|
|
||||||
#include "RCInput.h"
|
#include "RCInput.h"
|
||||||
|
|
||||||
@ -36,3 +39,4 @@ bool LinuxRCInput::set_override(uint8_t channel, int16_t override) {
|
|||||||
void LinuxRCInput::clear_overrides()
|
void LinuxRCInput::clear_overrides()
|
||||||
{}
|
{}
|
||||||
|
|
||||||
|
#endif // CONFIG_HAL_BOARD
|
||||||
|
@ -1,3 +1,6 @@
|
|||||||
|
#include <AP_HAL.h>
|
||||||
|
|
||||||
|
#if CONFIG_HAL_BOARD == HAL_BOARD_LINUX
|
||||||
|
|
||||||
#include "RCOutput.h"
|
#include "RCOutput.h"
|
||||||
|
|
||||||
@ -36,3 +39,4 @@ uint16_t LinuxRCOutput::read(uint8_t ch) {
|
|||||||
void LinuxRCOutput::read(uint16_t* period_us, uint8_t len)
|
void LinuxRCOutput::read(uint16_t* period_us, uint8_t len)
|
||||||
{}
|
{}
|
||||||
|
|
||||||
|
#endif // CONFIG_HAL_BOARD
|
||||||
|
Loading…
Reference in New Issue
Block a user