mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-03 06:28:27 -04:00
AP_HAL_Linux: remove ifdef checks for HAL_BOARD_LINUX
Everything inside libraries/AP_HAL_Linux is for Linux boards, there's not need to add the ifdefs.
This commit is contained in:
parent
c4306de122
commit
45c6b750f2
@ -1,6 +1,5 @@
|
|||||||
#include <AP_HAL/AP_HAL.h>
|
#include <AP_HAL/AP_HAL.h>
|
||||||
|
|
||||||
#if CONFIG_HAL_BOARD == HAL_BOARD_LINUX
|
|
||||||
#include "AnalogIn.h"
|
#include "AnalogIn.h"
|
||||||
|
|
||||||
using namespace Linux;
|
using namespace Linux;
|
||||||
@ -43,5 +42,3 @@ void AnalogIn::init()
|
|||||||
AP_HAL::AnalogSource* AnalogIn::channel(int16_t n) {
|
AP_HAL::AnalogSource* AnalogIn::channel(int16_t n) {
|
||||||
return new AnalogSource(1.11);
|
return new AnalogSource(1.11);
|
||||||
}
|
}
|
||||||
|
|
||||||
#endif // CONFIG_HAL_BOARD
|
|
||||||
|
@ -1,7 +1,5 @@
|
|||||||
#include <AP_HAL/AP_HAL.h>
|
#include <AP_HAL/AP_HAL.h>
|
||||||
|
|
||||||
#if CONFIG_HAL_BOARD == HAL_BOARD_LINUX
|
|
||||||
|
|
||||||
#include "AnalogIn_ADS1115.h"
|
#include "AnalogIn_ADS1115.h"
|
||||||
|
|
||||||
AnalogSource_ADS1115::AnalogSource_ADS1115(int16_t pin):
|
AnalogSource_ADS1115::AnalogSource_ADS1115(int16_t pin):
|
||||||
@ -95,5 +93,3 @@ void AnalogIn_ADS1115::_update()
|
|||||||
|
|
||||||
_last_update_timestamp = AP_HAL::micros();
|
_last_update_timestamp = AP_HAL::micros();
|
||||||
}
|
}
|
||||||
|
|
||||||
#endif
|
|
||||||
|
@ -1,7 +1,6 @@
|
|||||||
/// -*- tab-width: 4; Mode: C++; c-basic-offset: 4; indent-tabs-mode: nil -*-
|
/// -*- tab-width: 4; Mode: C++; c-basic-offset: 4; indent-tabs-mode: nil -*-
|
||||||
#include <AP_HAL/AP_HAL.h>
|
#include <AP_HAL/AP_HAL.h>
|
||||||
|
|
||||||
#if CONFIG_HAL_BOARD == HAL_BOARD_LINUX
|
|
||||||
#include "AnalogIn_IIO.h"
|
#include "AnalogIn_IIO.h"
|
||||||
|
|
||||||
extern const AP_HAL::HAL& hal;
|
extern const AP_HAL::HAL& hal;
|
||||||
@ -125,5 +124,3 @@ void AnalogIn_IIO::init()
|
|||||||
AP_HAL::AnalogSource* AnalogIn_IIO::channel(int16_t pin) {
|
AP_HAL::AnalogSource* AnalogIn_IIO::channel(int16_t pin) {
|
||||||
return new AnalogSource_IIO(pin, 0.0f, IIO_VOLTAGE_SCALING);
|
return new AnalogSource_IIO(pin, 0.0f, IIO_VOLTAGE_SCALING);
|
||||||
}
|
}
|
||||||
|
|
||||||
#endif // CONFIG_HAL_BOARD
|
|
||||||
|
@ -1,7 +1,5 @@
|
|||||||
#include <AP_HAL/AP_HAL.h>
|
#include <AP_HAL/AP_HAL.h>
|
||||||
|
|
||||||
#if CONFIG_HAL_BOARD == HAL_BOARD_LINUX
|
|
||||||
|
|
||||||
#include "AnalogIn_Navio2.h"
|
#include "AnalogIn_Navio2.h"
|
||||||
|
|
||||||
#include <cstdio>
|
#include <cstdio>
|
||||||
@ -124,5 +122,3 @@ void AnalogIn_Navio2::init()
|
|||||||
_board_voltage_pin = channel(0);
|
_board_voltage_pin = channel(0);
|
||||||
_servorail_pin = channel(1);
|
_servorail_pin = channel(1);
|
||||||
}
|
}
|
||||||
|
|
||||||
#endif
|
|
||||||
|
@ -1,7 +1,5 @@
|
|||||||
#include <AP_HAL/AP_HAL.h>
|
#include <AP_HAL/AP_HAL.h>
|
||||||
|
|
||||||
#if CONFIG_HAL_BOARD == HAL_BOARD_LINUX
|
|
||||||
|
|
||||||
#include "AnalogIn_Raspilot.h"
|
#include "AnalogIn_Raspilot.h"
|
||||||
#include "px4io_protocol.h"
|
#include "px4io_protocol.h"
|
||||||
|
|
||||||
@ -135,5 +133,3 @@ void AnalogIn_Raspilot::_update()
|
|||||||
|
|
||||||
_last_update_timestamp = AP_HAL::micros();
|
_last_update_timestamp = AP_HAL::micros();
|
||||||
}
|
}
|
||||||
|
|
||||||
#endif
|
|
||||||
|
@ -1,6 +1,5 @@
|
|||||||
#include <AP_HAL/AP_HAL.h>
|
#include <AP_HAL/AP_HAL.h>
|
||||||
|
|
||||||
#if CONFIG_HAL_BOARD == HAL_BOARD_LINUX
|
|
||||||
#include "ConsoleDevice.h"
|
#include "ConsoleDevice.h"
|
||||||
|
|
||||||
#include <stdio.h>
|
#include <stdio.h>
|
||||||
@ -80,5 +79,3 @@ void ConsoleDevice::set_blocking(bool blocking)
|
|||||||
void ConsoleDevice::set_speed(uint32_t baudrate)
|
void ConsoleDevice::set_speed(uint32_t baudrate)
|
||||||
{
|
{
|
||||||
}
|
}
|
||||||
|
|
||||||
#endif
|
|
||||||
|
@ -1,8 +1,6 @@
|
|||||||
#include <AP_HAL/AP_HAL.h>
|
#include <AP_HAL/AP_HAL.h>
|
||||||
#include "GPIO.h"
|
#include "GPIO.h"
|
||||||
|
|
||||||
#if CONFIG_HAL_BOARD == HAL_BOARD_LINUX
|
|
||||||
|
|
||||||
using namespace Linux;
|
using namespace Linux;
|
||||||
|
|
||||||
static const AP_HAL::HAL& hal = AP_HAL::get_HAL();
|
static const AP_HAL::HAL& hal = AP_HAL::get_HAL();
|
||||||
@ -32,5 +30,3 @@ void DigitalSource::toggle()
|
|||||||
{
|
{
|
||||||
write(!read());
|
write(!read());
|
||||||
}
|
}
|
||||||
|
|
||||||
#endif
|
|
||||||
|
@ -2,8 +2,6 @@
|
|||||||
|
|
||||||
#include "AP_HAL_Linux.h"
|
#include "AP_HAL_Linux.h"
|
||||||
|
|
||||||
#if CONFIG_HAL_BOARD == HAL_BOARD_LINUX
|
|
||||||
|
|
||||||
class Linux::DigitalSource : public AP_HAL::DigitalSource {
|
class Linux::DigitalSource : public AP_HAL::DigitalSource {
|
||||||
public:
|
public:
|
||||||
DigitalSource(uint8_t v);
|
DigitalSource(uint8_t v);
|
||||||
@ -30,5 +28,3 @@ private:
|
|||||||
#elif CONFIG_HAL_BOARD_SUBTYPE == HAL_BOARD_SUBTYPE_LINUX_BEBOP
|
#elif CONFIG_HAL_BOARD_SUBTYPE == HAL_BOARD_SUBTYPE_LINUX_BEBOP
|
||||||
#include "GPIO_Bebop.h"
|
#include "GPIO_Bebop.h"
|
||||||
#endif
|
#endif
|
||||||
|
|
||||||
#endif // CONFIG_HAL_BOARD == HAL_BOARD_LINUX
|
|
||||||
|
@ -2,7 +2,7 @@
|
|||||||
|
|
||||||
#include <AP_HAL/AP_HAL.h>
|
#include <AP_HAL/AP_HAL.h>
|
||||||
|
|
||||||
#if CONFIG_HAL_BOARD == HAL_BOARD_LINUX && CONFIG_HAL_BOARD_SUBTYPE != HAL_BOARD_SUBTYPE_LINUX_QFLIGHT
|
#if CONFIG_HAL_BOARD_SUBTYPE != HAL_BOARD_SUBTYPE_LINUX_QFLIGHT
|
||||||
|
|
||||||
#include <fcntl.h>
|
#include <fcntl.h>
|
||||||
#include <stdio.h>
|
#include <stdio.h>
|
||||||
|
@ -2,8 +2,6 @@
|
|||||||
|
|
||||||
#include <AP_HAL/AP_HAL.h>
|
#include <AP_HAL/AP_HAL.h>
|
||||||
|
|
||||||
#if CONFIG_HAL_BOARD == HAL_BOARD_LINUX
|
|
||||||
|
|
||||||
#include "AP_HAL_Linux.h"
|
#include "AP_HAL_Linux.h"
|
||||||
#include "GPIO.h"
|
#include "GPIO.h"
|
||||||
|
|
||||||
@ -78,5 +76,3 @@ protected:
|
|||||||
*/
|
*/
|
||||||
static bool _export_pin(uint8_t vpin);
|
static bool _export_pin(uint8_t vpin);
|
||||||
};
|
};
|
||||||
|
|
||||||
#endif
|
|
||||||
|
@ -1,11 +1,9 @@
|
|||||||
#include <AP_HAL/AP_HAL.h>
|
|
||||||
#if CONFIG_HAL_BOARD == HAL_BOARD_LINUX
|
|
||||||
|
|
||||||
#include <assert.h>
|
#include <assert.h>
|
||||||
|
|
||||||
#include "HAL_Linux_Class.h"
|
#include "HAL_Linux_Class.h"
|
||||||
#include "AP_HAL_Linux_Private.h"
|
#include "AP_HAL_Linux_Private.h"
|
||||||
|
|
||||||
|
#include <AP_HAL/AP_HAL.h>
|
||||||
#include <AP_HAL/utility/getopt_cpp.h>
|
#include <AP_HAL/utility/getopt_cpp.h>
|
||||||
#include <stdio.h>
|
#include <stdio.h>
|
||||||
#include <unistd.h>
|
#include <unistd.h>
|
||||||
@ -351,5 +349,3 @@ const AP_HAL::HAL& AP_HAL::get_HAL() {
|
|||||||
static const HAL_Linux hal;
|
static const HAL_Linux hal;
|
||||||
return hal;
|
return hal;
|
||||||
}
|
}
|
||||||
|
|
||||||
#endif
|
|
||||||
|
@ -1,6 +1,5 @@
|
|||||||
#include <AP_HAL/AP_HAL.h>
|
#include <AP_HAL/AP_HAL.h>
|
||||||
|
|
||||||
#if CONFIG_HAL_BOARD == HAL_BOARD_LINUX
|
|
||||||
#include "I2CDriver.h"
|
#include "I2CDriver.h"
|
||||||
#include "Util.h"
|
#include "Util.h"
|
||||||
|
|
||||||
@ -283,5 +282,3 @@ AP_HAL::Semaphore *I2CDriver::get_semaphore()
|
|||||||
{
|
{
|
||||||
return _fake_dev->get_semaphore();
|
return _fake_dev->get_semaphore();
|
||||||
}
|
}
|
||||||
|
|
||||||
#endif // CONFIG_HAL_BOARD
|
|
||||||
|
@ -15,11 +15,8 @@
|
|||||||
* You should have received a copy of the GNU General Public License along
|
* You should have received a copy of the GNU General Public License along
|
||||||
* with this program. If not, see <http://www.gnu.org/licenses/>.
|
* with this program. If not, see <http://www.gnu.org/licenses/>.
|
||||||
*/
|
*/
|
||||||
|
|
||||||
#include <AP_HAL/AP_HAL.h>
|
#include <AP_HAL/AP_HAL.h>
|
||||||
|
|
||||||
#if CONFIG_HAL_BOARD == HAL_BOARD_LINUX
|
|
||||||
|
|
||||||
#include "PWM_Sysfs.h"
|
#include "PWM_Sysfs.h"
|
||||||
|
|
||||||
#include <errno.h>
|
#include <errno.h>
|
||||||
@ -283,4 +280,3 @@ PWM_Sysfs_Bebop::PWM_Sysfs_Bebop(uint8_t channel) :
|
|||||||
}
|
}
|
||||||
|
|
||||||
}
|
}
|
||||||
#endif
|
|
||||||
|
@ -18,7 +18,7 @@
|
|||||||
|
|
||||||
#include <AP_HAL/AP_HAL.h>
|
#include <AP_HAL/AP_HAL.h>
|
||||||
|
|
||||||
#if CONFIG_HAL_BOARD == HAL_BOARD_LINUX && !defined(PERF_LTTNG)
|
#if !defined(PERF_LTTNG)
|
||||||
|
|
||||||
#include <limits.h>
|
#include <limits.h>
|
||||||
#include <time.h>
|
#include <time.h>
|
||||||
|
@ -16,7 +16,8 @@
|
|||||||
#include <AP_HAL/AP_HAL.h>
|
#include <AP_HAL/AP_HAL.h>
|
||||||
|
|
||||||
#pragma GCC diagnostic ignored "-Wcast-align"
|
#pragma GCC diagnostic ignored "-Wcast-align"
|
||||||
#if CONFIG_HAL_BOARD == HAL_BOARD_LINUX && defined(PERF_LTTNG)
|
#if defined(PERF_LTTNG)
|
||||||
|
|
||||||
#define TRACEPOINT_CREATE_PROBES
|
#define TRACEPOINT_CREATE_PROBES
|
||||||
#define TRACEPOINT_DEFINE
|
#define TRACEPOINT_DEFINE
|
||||||
#include "Perf_Lttng_TracePoints.h"
|
#include "Perf_Lttng_TracePoints.h"
|
||||||
|
@ -1,6 +1,3 @@
|
|||||||
#include <AP_HAL/AP_HAL.h>
|
|
||||||
|
|
||||||
#if CONFIG_HAL_BOARD == HAL_BOARD_LINUX
|
|
||||||
#include <stdio.h>
|
#include <stdio.h>
|
||||||
#include <sys/time.h>
|
#include <sys/time.h>
|
||||||
#include <stdio.h>
|
#include <stdio.h>
|
||||||
@ -16,6 +13,7 @@
|
|||||||
|
|
||||||
#include "RCInput.h"
|
#include "RCInput.h"
|
||||||
#include "sbus.h"
|
#include "sbus.h"
|
||||||
|
#include <AP_HAL/AP_HAL.h>
|
||||||
#include <AP_HAL/utility/dsm.h>
|
#include <AP_HAL/utility/dsm.h>
|
||||||
|
|
||||||
extern const AP_HAL::HAL& hal;
|
extern const AP_HAL::HAL& hal;
|
||||||
@ -406,5 +404,3 @@ void RCInput::add_dsm_input(const uint8_t *bytes, size_t nbytes)
|
|||||||
}
|
}
|
||||||
}
|
}
|
||||||
}
|
}
|
||||||
|
|
||||||
#endif // CONFIG_HAL_BOARD
|
|
||||||
|
@ -1,7 +1,5 @@
|
|||||||
#include <AP_HAL/AP_HAL.h>
|
#include <AP_HAL/AP_HAL.h>
|
||||||
|
|
||||||
#if CONFIG_HAL_BOARD == HAL_BOARD_LINUX
|
|
||||||
|
|
||||||
#include "RCInput_UART.h"
|
#include "RCInput_UART.h"
|
||||||
|
|
||||||
#include <errno.h>
|
#include <errno.h>
|
||||||
@ -92,5 +90,3 @@ void RCInput_UART::_timer_tick()
|
|||||||
_pdata = (uint8_t *)&_data;
|
_pdata = (uint8_t *)&_data;
|
||||||
_remain = sizeof(_data);
|
_remain = sizeof(_data);
|
||||||
}
|
}
|
||||||
|
|
||||||
#endif
|
|
||||||
|
@ -1,6 +1,5 @@
|
|||||||
#include <AP_HAL/AP_HAL.h>
|
#include <AP_HAL/AP_HAL.h>
|
||||||
|
|
||||||
#if CONFIG_HAL_BOARD == HAL_BOARD_LINUX
|
|
||||||
#include "RCInput_UDP.h"
|
#include "RCInput_UDP.h"
|
||||||
#include <stdio.h>
|
#include <stdio.h>
|
||||||
|
|
||||||
@ -51,4 +50,3 @@ void RCInput_UDP::_timer_tick(void)
|
|||||||
_update_periods(_buf.pwms, RCINPUT_UDP_NUM_CHANNELS);
|
_update_periods(_buf.pwms, RCINPUT_UDP_NUM_CHANNELS);
|
||||||
}
|
}
|
||||||
}
|
}
|
||||||
#endif
|
|
||||||
|
@ -1,6 +1,5 @@
|
|||||||
#include <AP_HAL/AP_HAL.h>
|
#include <AP_HAL/AP_HAL.h>
|
||||||
|
|
||||||
#if CONFIG_HAL_BOARD == HAL_BOARD_LINUX
|
|
||||||
#include <stdio.h>
|
#include <stdio.h>
|
||||||
#include <sys/time.h>
|
#include <sys/time.h>
|
||||||
#include <stdio.h>
|
#include <stdio.h>
|
||||||
@ -50,5 +49,3 @@ void RCInput_ZYNQ::_timer_tick()
|
|||||||
_process_rc_pulse(_s0_time, (v & 0x7fffffff)/TICK_PER_US);
|
_process_rc_pulse(_s0_time, (v & 0x7fffffff)/TICK_PER_US);
|
||||||
}
|
}
|
||||||
}
|
}
|
||||||
|
|
||||||
#endif // CONFIG_HAL_BOARD
|
|
||||||
|
@ -12,8 +12,6 @@
|
|||||||
|
|
||||||
#include <AP_HAL/AP_HAL.h>
|
#include <AP_HAL/AP_HAL.h>
|
||||||
|
|
||||||
#if CONFIG_HAL_BOARD == HAL_BOARD_LINUX
|
|
||||||
|
|
||||||
#include "RCOutput_AioPRU.h"
|
#include "RCOutput_AioPRU.h"
|
||||||
#include <fcntl.h>
|
#include <fcntl.h>
|
||||||
#include <unistd.h>
|
#include <unistd.h>
|
||||||
@ -128,6 +126,3 @@ void RCOutput_AioPRU::read(uint16_t* period_us, uint8_t len)
|
|||||||
period_us[i] = pwm->channel[i].time_high / TICK_PER_US;
|
period_us[i] = pwm->channel[i].time_high / TICK_PER_US;
|
||||||
}
|
}
|
||||||
}
|
}
|
||||||
|
|
||||||
#endif
|
|
||||||
|
|
||||||
|
@ -2,8 +2,6 @@
|
|||||||
#include <AP_HAL/AP_HAL.h>
|
#include <AP_HAL/AP_HAL.h>
|
||||||
#include "GPIO.h"
|
#include "GPIO.h"
|
||||||
|
|
||||||
#if CONFIG_HAL_BOARD == HAL_BOARD_LINUX
|
|
||||||
|
|
||||||
#include "RCOutput_PCA9685.h"
|
#include "RCOutput_PCA9685.h"
|
||||||
#include <sys/types.h>
|
#include <sys/types.h>
|
||||||
#include <sys/stat.h>
|
#include <sys/stat.h>
|
||||||
@ -248,5 +246,3 @@ void RCOutput_PCA9685::read(uint16_t* period_us, uint8_t len)
|
|||||||
for (int i = 0; i < len; i++)
|
for (int i = 0; i < len; i++)
|
||||||
period_us[i] = read(0 + i);
|
period_us[i] = read(0 + i);
|
||||||
}
|
}
|
||||||
|
|
||||||
#endif
|
|
||||||
|
@ -1,8 +1,6 @@
|
|||||||
|
|
||||||
#include <AP_HAL/AP_HAL.h>
|
#include <AP_HAL/AP_HAL.h>
|
||||||
|
|
||||||
#if CONFIG_HAL_BOARD == HAL_BOARD_LINUX
|
|
||||||
|
|
||||||
#include "RCOutput_PRU.h"
|
#include "RCOutput_PRU.h"
|
||||||
#include <sys/types.h>
|
#include <sys/types.h>
|
||||||
#include <sys/stat.h>
|
#include <sys/stat.h>
|
||||||
@ -88,5 +86,3 @@ void RCOutput_PRU::read(uint16_t* period_us, uint8_t len)
|
|||||||
period_us[i] = sharedMem_cmd->hilo_read[chan_pru_map[i]][1]/TICK_PER_US;
|
period_us[i] = sharedMem_cmd->hilo_read[chan_pru_map[i]][1]/TICK_PER_US;
|
||||||
}
|
}
|
||||||
}
|
}
|
||||||
|
|
||||||
#endif
|
|
||||||
|
@ -18,8 +18,6 @@
|
|||||||
|
|
||||||
#include <AP_HAL/AP_HAL.h>
|
#include <AP_HAL/AP_HAL.h>
|
||||||
|
|
||||||
#if CONFIG_HAL_BOARD == HAL_BOARD_LINUX
|
|
||||||
|
|
||||||
#include "RCOutput_Sysfs.h"
|
#include "RCOutput_Sysfs.h"
|
||||||
|
|
||||||
#include <AP_Common/AP_Common.h>
|
#include <AP_Common/AP_Common.h>
|
||||||
@ -120,5 +118,3 @@ void RCOutput_Sysfs::read(uint16_t *period_us, uint8_t len)
|
|||||||
}
|
}
|
||||||
}
|
}
|
||||||
}
|
}
|
||||||
|
|
||||||
#endif
|
|
||||||
|
@ -1,8 +1,6 @@
|
|||||||
|
|
||||||
#include <AP_HAL/AP_HAL.h>
|
#include <AP_HAL/AP_HAL.h>
|
||||||
|
|
||||||
#if CONFIG_HAL_BOARD == HAL_BOARD_LINUX
|
|
||||||
|
|
||||||
#include "RCOutput_ZYNQ.h"
|
#include "RCOutput_ZYNQ.h"
|
||||||
#include <sys/types.h>
|
#include <sys/types.h>
|
||||||
#include <sys/stat.h>
|
#include <sys/stat.h>
|
||||||
@ -85,5 +83,3 @@ void RCOutput_ZYNQ::read(uint16_t* period_us, uint8_t len)
|
|||||||
period_us[i] = sharedMem_cmd->periodhi[i].hi/TICK_PER_US;
|
period_us[i] = sharedMem_cmd->periodhi[i].hi/TICK_PER_US;
|
||||||
}
|
}
|
||||||
}
|
}
|
||||||
|
|
||||||
#endif
|
|
||||||
|
@ -1,7 +1,5 @@
|
|||||||
#include <AP_HAL/AP_HAL.h>
|
#include <AP_HAL/AP_HAL.h>
|
||||||
|
|
||||||
#if CONFIG_HAL_BOARD == HAL_BOARD_LINUX
|
|
||||||
|
|
||||||
#include "RPIOUARTDriver.h"
|
#include "RPIOUARTDriver.h"
|
||||||
|
|
||||||
#include <stdlib.h>
|
#include <stdlib.h>
|
||||||
@ -289,5 +287,3 @@ void RPIOUARTDriver::_timer_tick(void)
|
|||||||
|
|
||||||
_last_update_timestamp = AP_HAL::micros();
|
_last_update_timestamp = AP_HAL::micros();
|
||||||
}
|
}
|
||||||
|
|
||||||
#endif
|
|
||||||
|
@ -1,7 +1,6 @@
|
|||||||
#include <AP_Common/AP_Common.h>
|
#include <AP_Common/AP_Common.h>
|
||||||
#include <AP_HAL/AP_HAL.h>
|
#include <AP_HAL/AP_HAL.h>
|
||||||
|
|
||||||
#if CONFIG_HAL_BOARD == HAL_BOARD_LINUX
|
|
||||||
#include "SPIDriver.h"
|
#include "SPIDriver.h"
|
||||||
#include <sys/types.h>
|
#include <sys/types.h>
|
||||||
#include <sys/stat.h>
|
#include <sys/stat.h>
|
||||||
@ -290,5 +289,3 @@ AP_HAL::SPIDeviceDriver *SPIDeviceManager::device(enum AP_HAL::SPIDeviceType dev
|
|||||||
}
|
}
|
||||||
return NULL;
|
return NULL;
|
||||||
}
|
}
|
||||||
|
|
||||||
#endif // CONFIG_HAL_BOARD
|
|
||||||
|
@ -1,7 +1,5 @@
|
|||||||
#include <AP_HAL/AP_HAL.h>
|
#include <AP_HAL/AP_HAL.h>
|
||||||
|
|
||||||
#if CONFIG_HAL_BOARD == HAL_BOARD_LINUX
|
|
||||||
|
|
||||||
#include <stdlib.h>
|
#include <stdlib.h>
|
||||||
#include <cstdio>
|
#include <cstdio>
|
||||||
#include "SPIUARTDriver.h"
|
#include "SPIUARTDriver.h"
|
||||||
@ -238,5 +236,3 @@ void SPIUARTDriver::_timer_tick(void)
|
|||||||
|
|
||||||
_last_update_timestamp = AP_HAL::micros();
|
_last_update_timestamp = AP_HAL::micros();
|
||||||
}
|
}
|
||||||
|
|
||||||
#endif
|
|
||||||
|
@ -1,7 +1,5 @@
|
|||||||
#include <AP_HAL/AP_HAL.h>
|
#include <AP_HAL/AP_HAL.h>
|
||||||
|
|
||||||
#if CONFIG_HAL_BOARD == HAL_BOARD_LINUX
|
|
||||||
|
|
||||||
#include "Semaphores.h"
|
#include "Semaphores.h"
|
||||||
|
|
||||||
extern const AP_HAL::HAL& hal;
|
extern const AP_HAL::HAL& hal;
|
||||||
@ -35,5 +33,3 @@ bool Semaphore::take_nonblocking()
|
|||||||
{
|
{
|
||||||
return pthread_mutex_trylock(&_lock) == 0;
|
return pthread_mutex_trylock(&_lock) == 0;
|
||||||
}
|
}
|
||||||
|
|
||||||
#endif // CONFIG_HAL_BOARD
|
|
||||||
|
@ -2,7 +2,6 @@
|
|||||||
|
|
||||||
#include <AP_HAL/AP_HAL_Boards.h>
|
#include <AP_HAL/AP_HAL_Boards.h>
|
||||||
|
|
||||||
#if CONFIG_HAL_BOARD == HAL_BOARD_LINUX
|
|
||||||
#include "AP_HAL_Linux.h"
|
#include "AP_HAL_Linux.h"
|
||||||
#include <pthread.h>
|
#include <pthread.h>
|
||||||
|
|
||||||
@ -17,4 +16,3 @@ public:
|
|||||||
private:
|
private:
|
||||||
pthread_mutex_t _lock;
|
pthread_mutex_t _lock;
|
||||||
};
|
};
|
||||||
#endif // CONFIG_HAL_BOARD
|
|
||||||
|
@ -1,7 +1,5 @@
|
|||||||
#include <AP_HAL/AP_HAL.h>
|
#include <AP_HAL/AP_HAL.h>
|
||||||
|
|
||||||
#if CONFIG_HAL_BOARD == HAL_BOARD_LINUX
|
|
||||||
|
|
||||||
#include <assert.h>
|
#include <assert.h>
|
||||||
#include <sys/types.h>
|
#include <sys/types.h>
|
||||||
#include <sys/stat.h>
|
#include <sys/stat.h>
|
||||||
@ -189,5 +187,3 @@ void Storage::_timer_tick(void)
|
|||||||
}
|
}
|
||||||
}
|
}
|
||||||
}
|
}
|
||||||
|
|
||||||
#endif // CONFIG_HAL_BOARD
|
|
||||||
|
@ -1,6 +1,5 @@
|
|||||||
#include <AP_HAL/AP_HAL.h>
|
#include <AP_HAL/AP_HAL.h>
|
||||||
|
|
||||||
#if CONFIG_HAL_BOARD == HAL_BOARD_LINUX
|
|
||||||
#include <assert.h>
|
#include <assert.h>
|
||||||
#include <sys/types.h>
|
#include <sys/types.h>
|
||||||
#include <sys/stat.h>
|
#include <sys/stat.h>
|
||||||
@ -258,5 +257,3 @@ int8_t Storage_FRAM::transaction(uint8_t* tx, uint8_t* rx, uint16_t len){
|
|||||||
_spi_sem->give();
|
_spi_sem->give();
|
||||||
return 0;
|
return 0;
|
||||||
}
|
}
|
||||||
|
|
||||||
#endif // CONFIG_HAL_BOARD
|
|
||||||
|
@ -1,7 +1,5 @@
|
|||||||
#include <AP_HAL/AP_HAL.h>
|
#include <AP_HAL/AP_HAL.h>
|
||||||
|
|
||||||
#if CONFIG_HAL_BOARD == HAL_BOARD_LINUX
|
|
||||||
|
|
||||||
#include <stdio.h>
|
#include <stdio.h>
|
||||||
#include <unistd.h>
|
#include <unistd.h>
|
||||||
#include <errno.h>
|
#include <errno.h>
|
||||||
@ -120,5 +118,3 @@ void TCPServerDevice::set_blocking(bool blocking)
|
|||||||
void TCPServerDevice::set_speed(uint32_t speed)
|
void TCPServerDevice::set_speed(uint32_t speed)
|
||||||
{
|
{
|
||||||
}
|
}
|
||||||
|
|
||||||
#endif
|
|
||||||
|
@ -1,7 +1,5 @@
|
|||||||
#include <AP_HAL/AP_HAL.h>
|
#include <AP_HAL/AP_HAL.h>
|
||||||
|
|
||||||
#if CONFIG_HAL_BOARD == HAL_BOARD_LINUX
|
|
||||||
|
|
||||||
#include "ToneAlarm.h"
|
#include "ToneAlarm.h"
|
||||||
|
|
||||||
#include <stdio.h>
|
#include <stdio.h>
|
||||||
@ -255,6 +253,3 @@ bool ToneAlarm::init_tune(){
|
|||||||
wholenote = (60 * 1000L / bpm) * 4; // this is the time for whole note (in milliseconds)
|
wholenote = (60 * 1000L / bpm) * 4; // this is the time for whole note (in milliseconds)
|
||||||
return true;
|
return true;
|
||||||
}
|
}
|
||||||
|
|
||||||
|
|
||||||
#endif
|
|
||||||
|
@ -1,7 +1,5 @@
|
|||||||
#include <AP_HAL/AP_HAL.h>
|
#include <AP_HAL/AP_HAL.h>
|
||||||
|
|
||||||
#if CONFIG_HAL_BOARD == HAL_BOARD_LINUX
|
|
||||||
|
|
||||||
#include <termios.h>
|
#include <termios.h>
|
||||||
#include <stdio.h>
|
#include <stdio.h>
|
||||||
#include <errno.h>
|
#include <errno.h>
|
||||||
@ -119,5 +117,3 @@ void UARTDevice::set_speed(uint32_t baudrate)
|
|||||||
cfsetspeed(&t, baudrate);
|
cfsetspeed(&t, baudrate);
|
||||||
tcsetattr(_fd, TCSANOW, &t);
|
tcsetattr(_fd, TCSANOW, &t);
|
||||||
}
|
}
|
||||||
|
|
||||||
#endif
|
|
||||||
|
@ -2,8 +2,6 @@
|
|||||||
|
|
||||||
#include <AP_HAL/AP_HAL.h>
|
#include <AP_HAL/AP_HAL.h>
|
||||||
|
|
||||||
#if CONFIG_HAL_BOARD == HAL_BOARD_LINUX
|
|
||||||
|
|
||||||
#include "UARTDriver.h"
|
#include "UARTDriver.h"
|
||||||
|
|
||||||
#include <stdio.h>
|
#include <stdio.h>
|
||||||
@ -628,5 +626,3 @@ void UARTDriver::_timer_tick(void)
|
|||||||
|
|
||||||
_in_timer = false;
|
_in_timer = false;
|
||||||
}
|
}
|
||||||
|
|
||||||
#endif // CONFIG_HAL_BOARD
|
|
||||||
|
@ -1,7 +1,5 @@
|
|||||||
#include <AP_HAL/AP_HAL.h>
|
#include <AP_HAL/AP_HAL.h>
|
||||||
|
|
||||||
#if CONFIG_HAL_BOARD == HAL_BOARD_LINUX
|
|
||||||
|
|
||||||
#include <stdio.h>
|
#include <stdio.h>
|
||||||
#include <sys/ioctl.h>
|
#include <sys/ioctl.h>
|
||||||
#include <fcntl.h>
|
#include <fcntl.h>
|
||||||
@ -67,5 +65,3 @@ void UDPDevice::set_speed(uint32_t speed)
|
|||||||
{
|
{
|
||||||
|
|
||||||
}
|
}
|
||||||
|
|
||||||
#endif
|
|
||||||
|
@ -1,6 +1,5 @@
|
|||||||
#include <AP_HAL/AP_HAL.h>
|
#include <AP_HAL/AP_HAL.h>
|
||||||
|
|
||||||
#if CONFIG_HAL_BOARD == HAL_BOARD_LINUX
|
|
||||||
#include <stdio.h>
|
#include <stdio.h>
|
||||||
#include <stdarg.h>
|
#include <stdarg.h>
|
||||||
#include <sys/stat.h>
|
#include <sys/stat.h>
|
||||||
@ -206,5 +205,3 @@ close_end:
|
|||||||
end:
|
end:
|
||||||
return ret;
|
return ret;
|
||||||
}
|
}
|
||||||
|
|
||||||
#endif // CONFIG_HAL_BOARD == HAL_BOARD_LINUX
|
|
||||||
|
Loading…
Reference in New Issue
Block a user