2016-02-17 21:25:25 -04:00
|
|
|
#pragma once
|
2012-08-20 15:37:46 -03:00
|
|
|
|
2018-02-02 16:35:15 -04:00
|
|
|
class AP_Param;
|
|
|
|
|
2012-08-20 15:37:46 -03:00
|
|
|
#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"
|
2016-07-22 11:19:59 -03:00
|
|
|
#include "SPIDevice.h"
|
2022-08-17 10:14:12 -03:00
|
|
|
#include "WSPIDevice.h"
|
2015-10-20 13:50:37 -03:00
|
|
|
#include "Storage.h"
|
|
|
|
#include "UARTDriver.h"
|
2015-11-19 23:24:56 -04:00
|
|
|
#include "system.h"
|
2015-11-23 14:45:20 -04:00
|
|
|
#include "OpticalFlow.h"
|
2019-08-09 13:04:00 -03:00
|
|
|
#include "DSP.h"
|
2020-05-31 09:12:02 -03:00
|
|
|
#include "CANIface.h"
|
2012-08-20 15:37:46 -03:00
|
|
|
|
2018-02-02 16:35:15 -04:00
|
|
|
|
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
|
2016-04-19 00:44:52 -03:00
|
|
|
AP_HAL::UARTDriver* _uartF, // extra1
|
2018-06-27 08:32:36 -03:00
|
|
|
AP_HAL::UARTDriver* _uartG, // extra2
|
2019-07-12 01:57:56 -03:00
|
|
|
AP_HAL::UARTDriver* _uartH, // extra3
|
2020-11-26 02:48:59 -04:00
|
|
|
AP_HAL::UARTDriver* _uartI, // extra4
|
2021-11-05 00:17:40 -03:00
|
|
|
AP_HAL::UARTDriver* _uartJ, // extra5
|
2015-11-22 19:39:44 -04:00
|
|
|
AP_HAL::I2CDeviceManager* _i2c_mgr,
|
2012-11-28 21:57:20 -04:00
|
|
|
AP_HAL::SPIDeviceManager* _spi,
|
2022-08-17 10:14:12 -03:00
|
|
|
AP_HAL::WSPIDeviceManager* _wspi,
|
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,
|
2015-11-23 14:45:20 -04:00
|
|
|
AP_HAL::Util* _util,
|
2019-08-09 13:04:00 -03:00
|
|
|
AP_HAL::OpticalFlow*_opticalflow,
|
|
|
|
AP_HAL::Flash* _flash,
|
2021-10-29 22:15:48 -03:00
|
|
|
#if AP_SIM_ENABLED && CONFIG_HAL_BOARD != HAL_BOARD_SITL
|
|
|
|
class AP_HAL::SIMState* _simstate,
|
|
|
|
#endif
|
2019-08-09 13:04:00 -03:00
|
|
|
AP_HAL::DSP* _dsp,
|
2020-05-31 09:12:02 -03:00
|
|
|
#if HAL_NUM_CAN_IFACES > 0
|
|
|
|
AP_HAL::CANIface* _can_ifaces[HAL_NUM_CAN_IFACES])
|
2017-05-06 06:12:19 -03:00
|
|
|
#else
|
2020-05-31 09:12:02 -03:00
|
|
|
AP_HAL::CANIface** _can_ifaces)
|
2017-05-06 06:12:19 -03:00
|
|
|
#endif
|
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),
|
2016-04-19 00:44:52 -03:00
|
|
|
uartF(_uartF),
|
2018-06-27 08:32:36 -03:00
|
|
|
uartG(_uartG),
|
2019-07-12 01:57:56 -03:00
|
|
|
uartH(_uartH),
|
2020-11-26 02:48:59 -04:00
|
|
|
uartI(_uartI),
|
2021-11-05 00:17:40 -03:00
|
|
|
uartJ(_uartJ),
|
2015-11-22 19:39:44 -04:00
|
|
|
i2c_mgr(_i2c_mgr),
|
2012-08-20 15:37:46 -03:00
|
|
|
spi(_spi),
|
2022-08-17 10:14:12 -03:00
|
|
|
wspi(_wspi),
|
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),
|
2015-11-23 14:45:20 -04:00
|
|
|
util(_util),
|
2019-03-25 21:13:39 -03:00
|
|
|
opticalflow(_opticalflow),
|
2019-08-09 13:04:00 -03:00
|
|
|
flash(_flash),
|
2021-10-29 22:15:48 -03:00
|
|
|
#if AP_SIM_ENABLED && CONFIG_HAL_BOARD != HAL_BOARD_SITL
|
|
|
|
simstate(_simstate),
|
|
|
|
#endif
|
2019-08-09 13:04:00 -03:00
|
|
|
dsp(_dsp)
|
2015-11-19 23:24:56 -04:00
|
|
|
{
|
2020-05-31 09:12:02 -03:00
|
|
|
#if HAL_NUM_CAN_IFACES > 0
|
|
|
|
if (_can_ifaces == nullptr) {
|
|
|
|
for (uint8_t i = 0; i < HAL_NUM_CAN_IFACES; i++)
|
|
|
|
can[i] = nullptr;
|
2017-05-06 06:12:19 -03:00
|
|
|
} else {
|
2020-05-31 09:12:02 -03:00
|
|
|
for (uint8_t i = 0; i < HAL_NUM_CAN_IFACES; i++)
|
|
|
|
can[i] = _can_ifaces[i];
|
2017-05-06 06:12:19 -03:00
|
|
|
}
|
|
|
|
#endif
|
|
|
|
|
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
|
|
|
|
2020-12-10 20:57:33 -04:00
|
|
|
private:
|
2020-12-10 20:18:03 -04:00
|
|
|
// the uartX ports must be contiguous in ram for the serial() method to work
|
2012-12-04 18:16:02 -04:00
|
|
|
AP_HAL::UARTDriver* uartA;
|
2022-02-26 09:54:07 -04:00
|
|
|
AP_HAL::UARTDriver* uartB UNUSED_PRIVATE_MEMBER;
|
|
|
|
AP_HAL::UARTDriver* uartC UNUSED_PRIVATE_MEMBER;
|
|
|
|
AP_HAL::UARTDriver* uartD UNUSED_PRIVATE_MEMBER;
|
|
|
|
AP_HAL::UARTDriver* uartE UNUSED_PRIVATE_MEMBER;
|
|
|
|
AP_HAL::UARTDriver* uartF UNUSED_PRIVATE_MEMBER;
|
|
|
|
AP_HAL::UARTDriver* uartG UNUSED_PRIVATE_MEMBER;
|
|
|
|
AP_HAL::UARTDriver* uartH UNUSED_PRIVATE_MEMBER;
|
|
|
|
AP_HAL::UARTDriver* uartI UNUSED_PRIVATE_MEMBER;
|
|
|
|
AP_HAL::UARTDriver* uartJ UNUSED_PRIVATE_MEMBER;
|
2020-12-10 20:57:33 -04:00
|
|
|
|
|
|
|
public:
|
2015-11-22 19:39:44 -04:00
|
|
|
AP_HAL::I2CDeviceManager* i2c_mgr;
|
2012-11-28 21:57:20 -04:00
|
|
|
AP_HAL::SPIDeviceManager* spi;
|
2022-08-17 10:14:12 -03:00
|
|
|
AP_HAL::WSPIDeviceManager* wspi;
|
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;
|
2015-12-14 08:37:56 -04:00
|
|
|
AP_HAL::Util *util;
|
|
|
|
AP_HAL::OpticalFlow *opticalflow;
|
2019-03-25 21:13:39 -03:00
|
|
|
AP_HAL::Flash *flash;
|
2019-08-09 13:04:00 -03:00
|
|
|
AP_HAL::DSP *dsp;
|
2020-05-31 09:12:02 -03:00
|
|
|
#if HAL_NUM_CAN_IFACES > 0
|
|
|
|
AP_HAL::CANIface* can[HAL_NUM_CAN_IFACES];
|
2017-05-06 06:12:19 -03:00
|
|
|
#else
|
2020-05-31 09:12:02 -03:00
|
|
|
AP_HAL::CANIface** can;
|
2017-05-06 06:12:19 -03:00
|
|
|
#endif
|
2020-12-10 20:18:03 -04:00
|
|
|
|
|
|
|
// access to serial ports using SERIALn_ numbering
|
2020-12-10 20:57:33 -04:00
|
|
|
UARTDriver* serial(uint8_t sernum) const;
|
|
|
|
|
2021-11-05 00:17:40 -03:00
|
|
|
static constexpr uint8_t num_serial = 10;
|
2021-10-29 22:15:48 -03:00
|
|
|
|
|
|
|
#if AP_SIM_ENABLED && CONFIG_HAL_BOARD != HAL_BOARD_SITL
|
|
|
|
AP_HAL::SIMState *simstate;
|
|
|
|
#endif
|
2022-03-21 06:34:45 -03:00
|
|
|
|
|
|
|
#ifndef HAL_CONSOLE_DISABLED
|
|
|
|
# define DEV_PRINTF(fmt, args ...) do { hal.console->printf(fmt, ## args); } while(0)
|
|
|
|
#else
|
|
|
|
# define DEV_PRINTF(fmt, args ...)
|
|
|
|
#endif
|
|
|
|
|
2012-08-20 15:37:46 -03:00
|
|
|
};
|