HAL_SITL: rename HAL_AVR_SITL to HAL_SITL

it is nothing to do with the original AVR emulation now
This commit is contained in:
Andrew Tridgell 2015-05-04 16:15:12 +10:00
parent 2559964f04
commit 40e3b422b5
38 changed files with 176 additions and 183 deletions

View File

@ -12,7 +12,7 @@
#define HAL_BOARD_APM1 1
#define HAL_BOARD_APM2 2
#define HAL_BOARD_AVR_SITL 3
#define HAL_BOARD_SITL 3
#define HAL_BOARD_SMACCM 4 // unused
#define HAL_BOARD_PX4 5
#define HAL_BOARD_FLYMAPLE 6
@ -139,8 +139,8 @@
#define CONFIG_HAL_BOARD_SUBTYPE HAL_BOARD_SUBTYPE_AVR_APM2
#endif
#elif CONFIG_HAL_BOARD == HAL_BOARD_AVR_SITL
#define AP_HAL_BOARD_DRIVER AP_HAL_AVR_SITL
#elif CONFIG_HAL_BOARD == HAL_BOARD_SITL
#define AP_HAL_BOARD_DRIVER AP_HAL_SITL
#define HAL_BOARD_NAME "SITL"
#define HAL_CPU_CLASS HAL_CPU_CLASS_1000
#define HAL_OS_POSIX_IO 1

View File

@ -6,7 +6,7 @@
#include <AP_HAL.h>
#include <AP_HAL_AVR.h>
#include <AP_HAL_AVR_SITL.h>
#include <AP_HAL_SITL.h>
#include <AP_HAL_PX4.h>
#include <AP_HAL_Empty.h>
#include <StorageManager.h>

View File

@ -1,6 +1,6 @@
#include <AP_HAL.h>
#include <AP_HAL_AVR.h>
#include <AP_HAL_AVR_SITL.h>
#include <AP_HAL_SITL.h>
#include <AP_HAL_PX4.h>
#include <AP_HAL_Linux.h>
#include <AP_HAL_Empty.h>

View File

@ -3,7 +3,7 @@
*/
#include <AP_HAL.h>
#include <AP_HAL_AVR.h>
#include <AP_HAL_AVR_SITL.h>
#include <AP_HAL_SITL.h>
#include <AP_HAL_PX4.h>
#include <AP_HAL_Linux.h>
#include <AP_HAL_Empty.h>

View File

@ -6,7 +6,7 @@
#include <AP_HAL.h>
#include <AP_HAL_AVR.h>
#include <AP_HAL_AVR_SITL.h>
#include <AP_HAL_SITL.h>
#include <AP_HAL_PX4.h>
#include <AP_HAL_Linux.h>
#include <AP_HAL_Empty.h>

View File

@ -3,7 +3,7 @@
*/
#include <AP_HAL.h>
#include <AP_HAL_AVR.h>
#include <AP_HAL_AVR_SITL.h>
#include <AP_HAL_SITL.h>
#include <AP_HAL_PX4.h>
#include <AP_HAL_Linux.h>
#include <AP_HAL_Empty.h>

View File

@ -3,7 +3,7 @@
*/
#include <AP_HAL.h>
#include <AP_HAL_AVR.h>
#include <AP_HAL_AVR_SITL.h>
#include <AP_HAL_SITL.h>
#include <AP_HAL_PX4.h>
#include <AP_HAL_Linux.h>
#include <AP_HAL_Empty.h>

View File

@ -1,15 +0,0 @@
#ifndef __AP_HAL_AVR_SITL_H__
#define __AP_HAL_AVR_SITL_H__
#include <AP_HAL.h>
#if CONFIG_HAL_BOARD == HAL_BOARD_AVR_SITL
#include "HAL_AVR_SITL_Class.h"
#include "AP_HAL_AVR_SITL_Main.h"
#endif // CONFIG_HAL_BOARD
#endif // __AP_HAL_AVR_SITL_H__

View File

@ -1,12 +0,0 @@
#ifndef __AP_HAL_AVR_SITL_PRIVATE_H__
#define __AP_HAL_AVR_SITL_PRIVATE_H__
#include "AP_HAL_AVR_SITL_Namespace.h"
#include "Scheduler.h"
#include "Storage.h"
#include "UARTDriver.h"
#include "SITL_State.h"
#endif // __AP_HAL_AVR_SITL_PRIVATE_H__

View File

@ -1,26 +0,0 @@
#ifndef __AP_HAL_AVR_SITL_CLASS_H__
#define __AP_HAL_AVR_SITL_CLASS_H__
#include <AP_HAL.h>
#if CONFIG_HAL_BOARD == HAL_BOARD_AVR_SITL
#include <AP_HAL_AVR_SITL.h>
#include "AP_HAL_AVR_SITL_Namespace.h"
#include "SITL_State.h"
class HAL_AVR_SITL : public AP_HAL::HAL {
public:
HAL_AVR_SITL();
void init(int argc, char * const argv[]) const;
private:
AVR_SITL::SITL_State *_sitl_state;
};
extern const HAL_AVR_SITL AP_HAL_AVR_SITL;
#endif // CONFIG_HAL_BOARD == HAL_BOARD_AVR_SITL
#endif // __AP_HAL_AVR_SITL_CLASS_H__

View File

@ -7,7 +7,7 @@
#include <AP_Math.h>
#include <AP_HAL_AVR.h>
#include <AP_HAL_AVR_SITL.h>
#include <AP_HAL_SITL.h>
#include <AP_HAL_Empty.h>
const AP_HAL::HAL& hal = AP_HAL_BOARD_DRIVER;

View File

@ -9,7 +9,7 @@
#include <AP_Progmem.h>
#include <AP_HAL.h>
#include <AP_HAL_AVR.h>
#include <AP_HAL_AVR_SITL.h>
#include <AP_HAL_SITL.h>
#include <AP_HAL_PX4.h>
#include <AP_HAL_Empty.h>
#include <AP_Math.h>

View File

@ -0,0 +1,15 @@
#ifndef __AP_HAL_SITL_H__
#define __AP_HAL_SITL_H__
#include <AP_HAL.h>
#if CONFIG_HAL_BOARD == HAL_BOARD_SITL
#include "HAL_SITL_Class.h"
#include "AP_HAL_SITL_Main.h"
#endif // CONFIG_HAL_BOARD
#endif // __AP_HAL_SITL_H__

View File

@ -1,8 +1,8 @@
#ifndef __AP_HAL_AVR_SITL_MAIN_H__
#define __AP_HAL_AVR_SITL_MAIN_H__
#ifndef __AP_HAL_SITL_MAIN_H__
#define __AP_HAL_SITL_MAIN_H__
#if CONFIG_HAL_BOARD == HAL_BOARD_AVR_SITL
#if CONFIG_HAL_BOARD == HAL_BOARD_SITL
#define AP_HAL_MAIN() extern "C" {\
int main (int argc, char * const argv[]) { \
hal.init(argc, argv); \
@ -16,4 +16,4 @@
}
#endif
#endif // __AP_HAL_AVR_SITL_MAIN_H__
#endif // __AP_HAL_SITL_MAIN_H__

View File

@ -1,8 +1,8 @@
#ifndef __AP_HAL_AVR_SITL_NAMESPACE_H__
#define __AP_HAL_AVR_SITL_NAMESPACE_H__
#ifndef __AP_HAL_SITL_NAMESPACE_H__
#define __AP_HAL_SITL_NAMESPACE_H__
namespace AVR_SITL {
namespace HALSITL {
class SITLUARTDriver;
class SITLScheduler;
class SITL_State;
@ -15,4 +15,4 @@ namespace AVR_SITL {
class SITLUtil;
}
#endif // __AP_HAL_AVR_SITL_NAMESPACE_H__
#endif // __AP_HAL_SITL_NAMESPACE_H__

View File

@ -0,0 +1,12 @@
#ifndef __AP_HAL_SITL_PRIVATE_H__
#define __AP_HAL_SITL_PRIVATE_H__
#include "AP_HAL_SITL_Namespace.h"
#include "Scheduler.h"
#include "Storage.h"
#include "UARTDriver.h"
#include "SITL_State.h"
#endif // __AP_HAL_SITL_PRIVATE_H__

View File

@ -1,13 +1,13 @@
/// -*- tab-width: 4; Mode: C++; c-basic-offset: 4; indent-tabs-mode: nil -*-
#include <AP_HAL.h>
#if CONFIG_HAL_BOARD == HAL_BOARD_AVR_SITL
#if CONFIG_HAL_BOARD == HAL_BOARD_SITL
#include "AP_HAL_AVR_SITL.h"
#include "AP_HAL_SITL.h"
#include "AnalogIn.h"
#include <stdint.h>
using namespace AVR_SITL;
using namespace HALSITL;
extern const AP_HAL::HAL& hal;

View File

@ -1,17 +1,16 @@
#ifndef __AP_HAL_AVR_SITL_ANALOG_IN_H__
#define __AP_HAL_AVR_SITL_ANALOG_IN_H__
#ifndef __AP_HAL_SITL_ANALOG_IN_H__
#define __AP_HAL_SITL_ANALOG_IN_H__
#include <AP_HAL.h>
#include "AP_HAL_AVR_SITL_Namespace.h"
#include "AP_HAL_SITL_Namespace.h"
#define SITL_INPUT_MAX_CHANNELS 12
class AVR_SITL::ADCSource : public AP_HAL::AnalogSource {
class HALSITL::ADCSource : public AP_HAL::AnalogSource {
public:
friend class AVR_SITL::SITLAnalogIn;
/* pin designates the ADC input number, or when == AVR_ANALOG_PIN_VCC,
* board vcc */
friend class HALSITL::SITLAnalogIn;
/* pin designates the ADC input number */
ADCSource(SITL_State *sitlState, uint8_t pin);
/* implement AnalogSource virtual api: */
@ -29,9 +28,9 @@ private:
uint8_t _pin;
};
/* AVRAnalogIn : a concrete class providing the implementations of the
/* SITLAnalogIn : a concrete class providing the implementations of the
* timer event and the AP_HAL::AnalogIn interface */
class AVR_SITL::SITLAnalogIn : public AP_HAL::AnalogIn {
class HALSITL::SITLAnalogIn : public AP_HAL::AnalogIn {
public:
SITLAnalogIn(SITL_State *sitlState) {
_sitlState = sitlState;
@ -44,4 +43,4 @@ private:
SITL_State *_sitlState;
};
#endif // __AP_HAL_AVR_SITL_ANALOG_IN_H__
#endif // __AP_HAL_SITL_ANALOG_IN_H__

View File

@ -2,13 +2,11 @@
#include <AP_HAL.h>
#if CONFIG_HAL_BOARD == HAL_BOARD_AVR_SITL
#if CONFIG_HAL_BOARD == HAL_BOARD_SITL
#include <AP_HAL_AVR.h>
#include <AP_HAL_AVR_private.h>
#include <AP_HAL_AVR_SITL.h>
#include "AP_HAL_AVR_SITL_Namespace.h"
#include "HAL_AVR_SITL_Class.h"
#include <AP_HAL_SITL.h>
#include "AP_HAL_SITL_Namespace.h"
#include "HAL_SITL_Class.h"
#include "Scheduler.h"
#include "AnalogIn.h"
#include "UARTDriver.h"
@ -21,7 +19,7 @@
#include <AP_HAL_Empty.h>
#include <AP_HAL_Empty_Private.h>
using namespace AVR_SITL;
using namespace HALSITL;
static SITLEEPROMStorage sitlEEPROMStorage;
static SITL_State sitlState;
@ -44,7 +42,7 @@ static SITLUARTDriver sitlUart4Driver(4, &sitlState);
static SITLUtil utilInstance;
HAL_AVR_SITL::HAL_AVR_SITL() :
HAL_SITL::HAL_SITL() :
AP_HAL::HAL(
&sitlUart0Driver, /* uartA */
&sitlUart1Driver, /* uartB */
@ -64,7 +62,7 @@ HAL_AVR_SITL::HAL_AVR_SITL() :
_sitl_state(&sitlState)
{}
void HAL_AVR_SITL::init(int argc, char * const argv[]) const
void HAL_SITL::init(int argc, char * const argv[]) const
{
_sitl_state->init(argc, argv);
scheduler->init(NULL);
@ -79,6 +77,6 @@ void HAL_AVR_SITL::init(int argc, char * const argv[]) const
analogin->init(NULL);
}
const HAL_AVR_SITL AP_HAL_AVR_SITL;
const HAL_SITL AP_HAL_SITL;
#endif // CONFIG_HAL_BOARD == HAL_BOARD_AVR_SITL
#endif // CONFIG_HAL_BOARD == HAL_BOARD_SITL

View File

@ -0,0 +1,26 @@
#ifndef __AP_HAL_SITL_CLASS_H__
#define __AP_HAL_SITL_CLASS_H__
#include <AP_HAL.h>
#if CONFIG_HAL_BOARD == HAL_BOARD_SITL
#include <AP_HAL_SITL.h>
#include "AP_HAL_SITL_Namespace.h"
#include "SITL_State.h"
class HAL_SITL : public AP_HAL::HAL {
public:
HAL_SITL();
void init(int argc, char * const argv[]) const;
private:
HALSITL::SITL_State *_sitl_state;
};
extern const HAL_SITL AP_HAL_SITL;
#endif // CONFIG_HAL_BOARD == HAL_BOARD_SITL
#endif // __AP_HAL_SITL_CLASS_H__

View File

@ -1,9 +1,9 @@
#include <AP_HAL.h>
#if CONFIG_HAL_BOARD == HAL_BOARD_AVR_SITL
#if CONFIG_HAL_BOARD == HAL_BOARD_SITL
#include "RCInput.h"
using namespace AVR_SITL;
using namespace HALSITL;
extern const AP_HAL::HAL& hal;

View File

@ -1,12 +1,12 @@
#ifndef __AP_HAL_AVR_SITL_RCINPUT_H__
#define __AP_HAL_AVR_SITL_RCINPUT_H__
#ifndef __AP_HAL_SITL_RCINPUT_H__
#define __AP_HAL_SITL_RCINPUT_H__
#include <AP_HAL.h>
#if CONFIG_HAL_BOARD == HAL_BOARD_AVR_SITL
#include <AP_HAL_AVR_SITL.h>
#if CONFIG_HAL_BOARD == HAL_BOARD_SITL
#include <AP_HAL_SITL.h>
class AVR_SITL::SITLRCInput : public AP_HAL::RCInput {
class HALSITL::SITLRCInput : public AP_HAL::RCInput {
public:
SITLRCInput(SITL_State *sitlState) {
_sitlState = sitlState;
@ -30,5 +30,5 @@ private:
};
#endif
#endif // __AP_HAL_AVR_SITL_RCINPUT_H__
#endif // __AP_HAL_SITL_RCINPUT_H__

View File

@ -1,9 +1,9 @@
#include <AP_HAL.h>
#if CONFIG_HAL_BOARD == HAL_BOARD_AVR_SITL
#if CONFIG_HAL_BOARD == HAL_BOARD_SITL
#include "RCOutput.h"
using namespace AVR_SITL;
using namespace HALSITL;
void SITLRCOutput::init(void* machtnichts) {}

View File

@ -1,12 +1,12 @@
#ifndef __AP_HAL_AVR_SITL_RCOUTPUT_H__
#define __AP_HAL_AVR_SITL_RCOUTPUT_H__
#ifndef __AP_HAL_SITL_RCOUTPUT_H__
#define __AP_HAL_SITL_RCOUTPUT_H__
#include <AP_HAL.h>
#if CONFIG_HAL_BOARD == HAL_BOARD_AVR_SITL
#include <AP_HAL_AVR_SITL.h>
#if CONFIG_HAL_BOARD == HAL_BOARD_SITL
#include <AP_HAL_SITL.h>
class AVR_SITL::SITLRCOutput : public AP_HAL::RCOutput {
class HALSITL::SITLRCOutput : public AP_HAL::RCOutput {
public:
SITLRCOutput(SITL_State *sitlState) {
_sitlState = sitlState;
@ -28,5 +28,5 @@ private:
};
#endif
#endif // __AP_HAL_AVR_SITL_RCOUTPUT_H__
#endif // __AP_HAL_SITL_RCOUTPUT_H__

View File

@ -2,12 +2,11 @@
#include <AP_HAL.h>
#if CONFIG_HAL_BOARD == HAL_BOARD_AVR_SITL
#if CONFIG_HAL_BOARD == HAL_BOARD_SITL
#include <AP_HAL_AVR.h>
#include <AP_HAL_AVR_SITL.h>
#include "AP_HAL_AVR_SITL_Namespace.h"
#include "HAL_AVR_SITL_Class.h"
#include <AP_HAL_SITL.h>
#include "AP_HAL_SITL_Namespace.h"
#include "HAL_SITL_Class.h"
#include "UARTDriver.h"
#include "Scheduler.h"
@ -51,7 +50,7 @@ void print_trace() {
extern const AP_HAL::HAL& hal;
using namespace AVR_SITL;
using namespace HALSITL;
// catch floating point exceptions
static void _sig_fpe(int signum)
@ -122,7 +121,7 @@ void SITL_State::_parse_command_line(int argc, char * const argv[])
_initial_height = atof(optarg);
break;
case 'C':
AVR_SITL::SITLUARTDriver::_console = true;
HALSITL::SITLUARTDriver::_console = true;
break;
case 'I': {
uint8_t instance = atoi(optarg);
@ -298,7 +297,7 @@ void SITL_State::_setup_fdm(void)
exit(1);
}
AVR_SITL::SITLUARTDriver::_set_nonblocking(_sitl_fd);
HALSITL::SITLUARTDriver::_set_nonblocking(_sitl_fd);
}
#endif

View File

@ -1,14 +1,14 @@
#ifndef __AP_HAL_AVR_SITL_STATE_H__
#define __AP_HAL_AVR_SITL_STATE_H__
#ifndef __AP_HAL_SITL_STATE_H__
#define __AP_HAL_SITL_STATE_H__
#include <AP_HAL.h>
#if CONFIG_HAL_BOARD == HAL_BOARD_AVR_SITL
#if CONFIG_HAL_BOARD == HAL_BOARD_SITL
#include <AP_HAL_AVR_SITL.h>
#include "AP_HAL_AVR_SITL_Namespace.h"
#include "HAL_AVR_SITL_Class.h"
#include <AP_HAL_SITL.h>
#include "AP_HAL_SITL_Namespace.h"
#include "HAL_SITL_Class.h"
#include <sys/types.h>
#include <sys/socket.h>
@ -24,10 +24,10 @@
#include "../SITL/SITL.h"
#include "../SITL/SIM_Multicopter.h"
class HAL_AVR_SITL;
class HAL_SITL;
class AVR_SITL::SITL_State {
friend class AVR_SITL::SITLScheduler;
class HALSITL::SITL_State {
friend class HALSITL::SITLScheduler;
public:
void init(int argc, char * const argv[]);
@ -187,6 +187,6 @@ private:
Aircraft *sitl_model;
};
#endif // CONFIG_HAL_BOARD == HAL_BOARD_AVR_SITL
#endif // __AP_HAL_AVR_SITL_STATE_H__
#endif // CONFIG_HAL_BOARD == HAL_BOARD_SITL
#endif // __AP_HAL_SITL_STATE_H__

View File

@ -1,15 +1,15 @@
/// -*- tab-width: 4; Mode: C++; c-basic-offset: 4; indent-tabs-mode: nil -*-
#include <AP_HAL.h>
#if CONFIG_HAL_BOARD == HAL_BOARD_AVR_SITL
#if CONFIG_HAL_BOARD == HAL_BOARD_SITL
#include "AP_HAL_AVR_SITL.h"
#include "AP_HAL_SITL.h"
#include "Scheduler.h"
#include <sys/time.h>
#include <unistd.h>
#include <fenv.h>
using namespace AVR_SITL;
using namespace HALSITL;
extern const AP_HAL::HAL& hal;

View File

@ -3,14 +3,14 @@
#define __AP_HAL_SITL_SCHEDULER_H__
#include <AP_HAL.h>
#if CONFIG_HAL_BOARD == HAL_BOARD_AVR_SITL
#include "AP_HAL_AVR_SITL_Namespace.h"
#if CONFIG_HAL_BOARD == HAL_BOARD_SITL
#include "AP_HAL_SITL_Namespace.h"
#include <sys/time.h>
#define SITL_SCHEDULER_MAX_TIMER_PROCS 4
/* Scheduler implementation: */
class AVR_SITL::SITLScheduler : public AP_HAL::Scheduler {
class HALSITL::SITLScheduler : public AP_HAL::Scheduler {
public:
SITLScheduler(SITL_State *sitlState);
/* AP_HAL::Scheduler methods */

View File

@ -1,5 +1,5 @@
#include <AP_HAL.h>
#if CONFIG_HAL_BOARD == HAL_BOARD_AVR_SITL
#if CONFIG_HAL_BOARD == HAL_BOARD_SITL
#include <assert.h>
#include <sys/types.h>
@ -8,7 +8,7 @@
#include <unistd.h>
#include "Storage.h"
using namespace AVR_SITL;
using namespace HALSITL;
void SITLEEPROMStorage::_eeprom_open(void)
{

View File

@ -1,12 +1,12 @@
#ifndef __AP_HAL_AVR_SITL_STORAGE_H__
#define __AP_HAL_AVR_SITL_STORAGE_H__
#ifndef __AP_HAL_SITL_STORAGE_H__
#define __AP_HAL_SITL_STORAGE_H__
#include <AP_HAL.h>
#include "AP_HAL_AVR_SITL_Namespace.h"
#include "AP_HAL_SITL_Namespace.h"
class AVR_SITL::SITLEEPROMStorage : public AP_HAL::Storage {
class HALSITL::SITLEEPROMStorage : public AP_HAL::Storage {
public:
SITLEEPROMStorage() {
_eeprom_fd = -1;
@ -20,4 +20,4 @@ private:
void _eeprom_open(void);
};
#endif // __AP_HAL_AVR_SITL_STORAGE_H__
#endif // __AP_HAL_SITL_STORAGE_H__

View File

@ -18,7 +18,7 @@
// Copyright (c) 2010 Michael Smith. All rights reserved.
//
#include <AP_HAL.h>
#if CONFIG_HAL_BOARD == HAL_BOARD_AVR_SITL
#if CONFIG_HAL_BOARD == HAL_BOARD_SITL
#include <limits.h>
#include <stdlib.h>
@ -39,7 +39,7 @@
#include "UARTDriver.h"
#include "SITL_State.h"
using namespace AVR_SITL;
using namespace HALSITL;
bool SITLUARTDriver::_console;

View File

@ -1,17 +1,17 @@
/// -*- tab-width: 4; Mode: C++; c-basic-offset: 4; indent-tabs-mode: nil -*-
#ifndef __AP_HAL_AVR_SITL_UART_DRIVER_H__
#define __AP_HAL_AVR_SITL_UART_DRIVER_H__
#ifndef __AP_HAL_SITL_UART_DRIVER_H__
#define __AP_HAL_SITL_UART_DRIVER_H__
#include <AP_HAL.h>
#if CONFIG_HAL_BOARD == HAL_BOARD_AVR_SITL
#if CONFIG_HAL_BOARD == HAL_BOARD_SITL
#include <stdint.h>
#include <stdarg.h>
#include "AP_HAL_AVR_SITL_Namespace.h"
#include "AP_HAL_SITL_Namespace.h"
class AVR_SITL::SITLUARTDriver : public AP_HAL::UARTDriver {
class HALSITL::SITLUARTDriver : public AP_HAL::UARTDriver {
public:
friend class AVR_SITL::SITL_State;
friend class HALSITL::SITL_State;
SITLUARTDriver(const uint8_t portNumber, SITL_State *sitlState) {
_portNumber = portNumber;
@ -83,5 +83,5 @@ private:
};
#endif
#endif // __AP_HAL_AVR_SITL_UART_DRIVER_H__
#endif // __AP_HAL_SITL_UART_DRIVER_H__

View File

@ -3,9 +3,9 @@
#define __AP_HAL_SITL_UTIL_H__
#include <AP_HAL.h>
#include "AP_HAL_AVR_SITL_Namespace.h"
#include "AP_HAL_SITL_Namespace.h"
class AVR_SITL::SITLUtil : public AP_HAL::Util {
class HALSITL::SITLUtil : public AP_HAL::Util {
public:
bool run_debug_shell(AP_HAL::BetterStream *stream) { return false; }
};

View File

@ -9,11 +9,11 @@
#include <AP_HAL.h>
#include <AP_Math.h>
#if CONFIG_HAL_BOARD == HAL_BOARD_AVR_SITL
#if CONFIG_HAL_BOARD == HAL_BOARD_SITL
#include "AP_HAL_AVR_SITL.h"
#include "AP_HAL_SITL.h"
using namespace AVR_SITL;
using namespace HALSITL;
extern const AP_HAL::HAL& hal;

View File

@ -7,12 +7,11 @@
*/
#include <AP_HAL.h>
#if CONFIG_HAL_BOARD == HAL_BOARD_AVR_SITL
#if CONFIG_HAL_BOARD == HAL_BOARD_SITL
#include <AP_HAL_AVR.h>
#include <AP_HAL_AVR_SITL.h>
#include "AP_HAL_AVR_SITL_Namespace.h"
#include "HAL_AVR_SITL_Class.h"
#include <AP_HAL_SITL.h>
#include "AP_HAL_SITL_Namespace.h"
#include "HAL_SITL_Class.h"
#include <AP_Math.h>
#include "../AP_Compass/AP_Compass.h"
@ -21,7 +20,7 @@
extern const AP_HAL::HAL& hal;
using namespace AVR_SITL;
using namespace HALSITL;
/*
setup the compass with new input

View File

@ -8,12 +8,11 @@
*/
#include <AP_HAL.h>
#if CONFIG_HAL_BOARD == HAL_BOARD_AVR_SITL
#if CONFIG_HAL_BOARD == HAL_BOARD_SITL
#include <AP_HAL_AVR.h>
#include <AP_HAL_AVR_SITL.h>
#include "AP_HAL_AVR_SITL_Namespace.h"
#include "HAL_AVR_SITL_Class.h"
#include <AP_HAL_SITL.h>
#include "AP_HAL_SITL_Namespace.h"
#include "HAL_SITL_Class.h"
#include <AP_Math.h>
#include "../SITL/SITL.h"
@ -27,7 +26,7 @@
#include <stdio.h>
#include <sys/time.h>
using namespace AVR_SITL;
using namespace HALSITL;
extern const AP_HAL::HAL& hal;
static uint8_t next_gps_index;
@ -72,8 +71,8 @@ int SITL_State::gps_pipe(void)
gps_state.gps_fd = fd[1];
gps_state.client_fd = fd[0];
gps_state.last_update = _scheduler->millis();
AVR_SITL::SITLUARTDriver::_set_nonblocking(gps_state.gps_fd);
AVR_SITL::SITLUARTDriver::_set_nonblocking(fd[0]);
HALSITL::SITLUARTDriver::_set_nonblocking(gps_state.gps_fd);
HALSITL::SITLUARTDriver::_set_nonblocking(fd[0]);
return gps_state.client_fd;
}
@ -90,8 +89,8 @@ int SITL_State::gps2_pipe(void)
gps2_state.gps_fd = fd[1];
gps2_state.client_fd = fd[0];
gps2_state.last_update = _scheduler->millis();
AVR_SITL::SITLUARTDriver::_set_nonblocking(gps2_state.gps_fd);
AVR_SITL::SITLUARTDriver::_set_nonblocking(fd[0]);
HALSITL::SITLUARTDriver::_set_nonblocking(gps2_state.gps_fd);
HALSITL::SITLUARTDriver::_set_nonblocking(fd[0]);
return gps2_state.client_fd;
}

View File

@ -7,12 +7,11 @@
*/
#include <AP_HAL.h>
#if CONFIG_HAL_BOARD == HAL_BOARD_AVR_SITL
#if CONFIG_HAL_BOARD == HAL_BOARD_SITL
#include <AP_HAL_AVR.h>
#include <AP_HAL_AVR_SITL.h>
#include "AP_HAL_AVR_SITL_Namespace.h"
#include "HAL_AVR_SITL_Class.h"
#include <AP_HAL_SITL.h>
#include "AP_HAL_SITL_Namespace.h"
#include "HAL_SITL_Class.h"
#include <AP_Math.h>
#include "../AP_Compass/AP_Compass.h"
@ -27,7 +26,7 @@
extern const AP_HAL::HAL& hal;
using namespace AVR_SITL;
using namespace HALSITL;
/*
convert airspeed in m/s to an airspeed sensor value

View File

@ -9,11 +9,11 @@
#include <AP_HAL.h>
#include <AP_Math.h>
#if CONFIG_HAL_BOARD == HAL_BOARD_AVR_SITL
#if CONFIG_HAL_BOARD == HAL_BOARD_SITL
#include "AP_HAL_AVR_SITL.h"
#include "AP_HAL_SITL.h"
using namespace AVR_SITL;
using namespace HALSITL;
extern const AP_HAL::HAL& hal;