ardupilot/libraries/AP_HAL_Empty/HAL_Empty_Class.cpp

75 lines
1.8 KiB
C++
Raw Normal View History

#include <AP_HAL/AP_HAL.h>
#if CONFIG_HAL_BOARD == HAL_BOARD_EMPTY
2015-10-19 11:25:59 -03:00
#include <assert.h>
#include "HAL_Empty_Class.h"
#include "AP_HAL_Empty_Private.h"
using namespace Empty;
static UARTDriver uartADriver;
static UARTDriver uartBDriver;
static UARTDriver uartCDriver;
static SPIDeviceManager spiDeviceManager;
static AnalogIn analogIn;
static Storage storageDriver;
static GPIO gpioDriver;
static RCInput rcinDriver;
static RCOutput rcoutDriver;
static Scheduler schedulerInstance;
static Util utilInstance;
static OpticalFlow opticalFlowDriver;
2019-03-25 21:14:05 -03:00
static Flash flashDriver;
HAL_Empty::HAL_Empty() :
AP_HAL::HAL(
&uartADriver,
&uartBDriver,
&uartCDriver,
nullptr, /* no uartD */
nullptr, /* no uartE */
nullptr, /* no uartF */
2018-06-27 08:34:23 -03:00
nullptr, /* no uartG */
2019-07-12 01:58:19 -03:00
nullptr, /* no uartH */
nullptr, /* no uartI */
2021-11-05 00:17:39 -03:00
nullptr, /* no uartJ */
&spiDeviceManager,
&analogIn,
&storageDriver,
2013-10-05 05:32:35 -03:00
&uartADriver,
&gpioDriver,
&rcinDriver,
&rcoutDriver,
2012-12-18 21:12:41 -04:00
&schedulerInstance,
&utilInstance,
2019-03-25 21:14:05 -03:00
&opticalFlowDriver,
&flashDriver,
nullptr) /* no DSP */
{}
2015-10-19 12:52:17 -03:00
void HAL_Empty::run(int argc, char* const argv[], Callbacks* callbacks) const
{
2012-12-17 15:54:55 -04:00
/* initialize all drivers and private members here.
* up to the programmer to do this in the correct order.
* Scheduler should likely come first. */
scheduler->init();
2020-12-10 21:15:28 -04:00
serial(0)->begin(115200);
2012-12-17 15:54:55 -04:00
_member->init();
2015-10-19 11:25:59 -03:00
callbacks->setup();
scheduler->set_system_initialized();
2015-10-19 11:25:59 -03:00
for (;;) {
callbacks->loop();
}
}
const AP_HAL::HAL& AP_HAL::get_HAL() {
static const HAL_Empty hal;
return hal;
}
#endif