2012-08-20 15:37:46 -03:00
|
|
|
|
|
|
|
#ifndef __AP_HAL_HAL_H__
|
|
|
|
#define __AP_HAL_HAL_H__
|
|
|
|
|
|
|
|
#include "AP_HAL_Namespace.h"
|
|
|
|
|
2015-10-20 13:50:37 -03:00
|
|
|
#include "AnalogIn.h"
|
|
|
|
#include "GPIO.h"
|
|
|
|
#include "RCInput.h"
|
|
|
|
#include "RCOutput.h"
|
|
|
|
#include "SPIDriver.h"
|
|
|
|
#include "Storage.h"
|
|
|
|
#include "UARTDriver.h"
|
2015-11-19 23:24:56 -04:00
|
|
|
#include "system.h"
|
2012-08-20 15:37:46 -03:00
|
|
|
|
|
|
|
class AP_HAL::HAL {
|
|
|
|
public:
|
2013-12-21 07:25:27 -04:00
|
|
|
HAL(AP_HAL::UARTDriver* _uartA, // console
|
|
|
|
AP_HAL::UARTDriver* _uartB, // 1st GPS
|
|
|
|
AP_HAL::UARTDriver* _uartC, // telem1
|
|
|
|
AP_HAL::UARTDriver* _uartD, // telem2
|
|
|
|
AP_HAL::UARTDriver* _uartE, // 2nd GPS
|
2015-06-15 14:46:31 -03:00
|
|
|
AP_HAL::I2CDriver* _i2c0,
|
|
|
|
AP_HAL::I2CDriver* _i2c1,
|
|
|
|
AP_HAL::I2CDriver* _i2c2,
|
2012-11-28 21:57:20 -04:00
|
|
|
AP_HAL::SPIDeviceManager* _spi,
|
2012-09-10 23:05:02 -03:00
|
|
|
AP_HAL::AnalogIn* _analogin,
|
2012-08-20 15:37:46 -03:00
|
|
|
AP_HAL::Storage* _storage,
|
2013-10-05 05:32:00 -03:00
|
|
|
AP_HAL::UARTDriver* _console,
|
2012-08-20 15:37:46 -03:00
|
|
|
AP_HAL::GPIO* _gpio,
|
2012-08-27 15:44:50 -03:00
|
|
|
AP_HAL::RCInput* _rcin,
|
|
|
|
AP_HAL::RCOutput* _rcout,
|
2012-12-18 20:09:24 -04:00
|
|
|
AP_HAL::Scheduler* _scheduler,
|
|
|
|
AP_HAL::Util* _util)
|
2012-08-20 15:37:46 -03:00
|
|
|
:
|
2012-12-04 18:16:02 -04:00
|
|
|
uartA(_uartA),
|
|
|
|
uartB(_uartB),
|
|
|
|
uartC(_uartC),
|
2013-11-22 04:15:29 -04:00
|
|
|
uartD(_uartD),
|
2013-12-21 07:25:27 -04:00
|
|
|
uartE(_uartE),
|
2015-06-15 14:46:31 -03:00
|
|
|
i2c(_i2c0),
|
|
|
|
i2c1(_i2c1),
|
|
|
|
i2c2(_i2c2),
|
2012-08-20 15:37:46 -03:00
|
|
|
spi(_spi),
|
2012-09-10 23:05:02 -03:00
|
|
|
analogin(_analogin),
|
2012-08-20 15:37:46 -03:00
|
|
|
storage(_storage),
|
|
|
|
console(_console),
|
|
|
|
gpio(_gpio),
|
2012-08-27 15:44:50 -03:00
|
|
|
rcin(_rcin),
|
|
|
|
rcout(_rcout),
|
2012-12-18 20:09:24 -04:00
|
|
|
scheduler(_scheduler),
|
|
|
|
util(_util)
|
2015-11-19 23:24:56 -04:00
|
|
|
{
|
|
|
|
AP_HAL::init();
|
|
|
|
}
|
2012-08-20 15:37:46 -03:00
|
|
|
|
2015-10-19 11:13:39 -03:00
|
|
|
struct Callbacks {
|
|
|
|
virtual void setup() = 0;
|
|
|
|
virtual void loop() = 0;
|
|
|
|
};
|
|
|
|
|
|
|
|
struct FunCallbacks : public Callbacks {
|
|
|
|
FunCallbacks(void (*setup_fun)(void), void (*loop_fun)(void));
|
|
|
|
|
|
|
|
void setup() override { _setup(); }
|
|
|
|
void loop() override { _loop(); }
|
|
|
|
|
|
|
|
private:
|
|
|
|
void (*_setup)(void);
|
|
|
|
void (*_loop)(void);
|
|
|
|
};
|
|
|
|
|
2015-10-19 12:48:04 -03:00
|
|
|
virtual void run(int argc, char * const argv[], Callbacks* callbacks) const = 0;
|
2015-10-19 11:13:39 -03:00
|
|
|
|
2012-12-04 18:16:02 -04:00
|
|
|
AP_HAL::UARTDriver* uartA;
|
|
|
|
AP_HAL::UARTDriver* uartB;
|
|
|
|
AP_HAL::UARTDriver* uartC;
|
2013-11-22 04:15:29 -04:00
|
|
|
AP_HAL::UARTDriver* uartD;
|
2013-12-21 07:25:27 -04:00
|
|
|
AP_HAL::UARTDriver* uartE;
|
2012-08-20 15:37:46 -03:00
|
|
|
AP_HAL::I2CDriver* i2c;
|
2015-06-15 14:46:31 -03:00
|
|
|
AP_HAL::I2CDriver* i2c1;
|
|
|
|
AP_HAL::I2CDriver* i2c2;
|
2012-11-28 21:57:20 -04:00
|
|
|
AP_HAL::SPIDeviceManager* spi;
|
2012-09-10 23:05:02 -03:00
|
|
|
AP_HAL::AnalogIn* analogin;
|
2012-08-20 15:37:46 -03:00
|
|
|
AP_HAL::Storage* storage;
|
2013-10-05 05:32:00 -03:00
|
|
|
AP_HAL::UARTDriver* console;
|
2012-08-20 15:37:46 -03:00
|
|
|
AP_HAL::GPIO* gpio;
|
2012-08-27 15:44:50 -03:00
|
|
|
AP_HAL::RCInput* rcin;
|
|
|
|
AP_HAL::RCOutput* rcout;
|
2012-08-23 15:36:13 -03:00
|
|
|
AP_HAL::Scheduler* scheduler;
|
2012-12-18 20:09:24 -04:00
|
|
|
AP_HAL::Util* util;
|
2012-08-20 15:37:46 -03:00
|
|
|
};
|
|
|
|
|
|
|
|
#endif // __AP_HAL_HAL_H__
|
|
|
|
|