/// -*- tab-width: 4; Mode: C++; c-basic-offset: 4; indent-tabs-mode: nil -*- #include #if CONFIG_HAL_BOARD == HAL_BOARD_PX4 #include #include "AP_HAL_PX4_Namespace.h" #include "HAL_PX4_Class.h" #include "Console.h" #include "Scheduler.h" #include "UARTDriver.h" #include "Storage.h" #include "RCInput.h" #include "RCOutput.h" #include "AnalogIn.h" #include "Util.h" #include #include #include #include #include #include #include #include using namespace PX4; static Empty::EmptySemaphore i2cSemaphore; static Empty::EmptyI2CDriver i2cDriver(&i2cSemaphore); static Empty::EmptySPIDeviceManager spiDeviceManager; static Empty::EmptyGPIO gpioDriver; static PX4ConsoleDriver consoleDriver; static PX4Scheduler schedulerInstance; static PX4EEPROMStorage storageDriver; static PX4RCInput rcinDriver; static PX4RCOutput rcoutDriver; static PX4AnalogIn analogIn; static PX4Util utilInstance; #define UARTA_DEFAULT_DEVICE "/dev/ttyS0" #define UARTB_DEFAULT_DEVICE "/dev/ttyS3" // only two real UART drivers for now static PX4UARTDriver uartADriver(UARTA_DEFAULT_DEVICE); static PX4UARTDriver uartBDriver(UARTB_DEFAULT_DEVICE); static Empty::EmptyUARTDriver uartCDriver; HAL_PX4::HAL_PX4() : AP_HAL::HAL( &uartADriver, /* uartA */ &uartBDriver, /* uartB */ &uartCDriver, /* uartC */ &i2cDriver, /* i2c */ &spiDeviceManager, /* spi */ &analogIn, /* analogin */ &storageDriver, /* storage */ &consoleDriver, /* console */ &gpioDriver, /* gpio */ &rcinDriver, /* rcinput */ &rcoutDriver, /* rcoutput */ &schedulerInstance, /* scheduler */ &utilInstance) /* util */ {} bool _px4_thread_should_exit = false; /**< Daemon exit flag */ static bool thread_running = false; /**< Daemon status flag */ static int daemon_task; /**< Handle of daemon task / thread */ extern const AP_HAL::HAL& hal; static int main_loop(int argc, char **argv) { extern void setup(void); extern void loop(void); hal.uartA->begin(57600); hal.console->init((void*) hal.uartA); hal.scheduler->init(NULL); hal.rcin->init(NULL); hal.rcout->init(NULL); hal.analogin->init(NULL); setup(); hal.scheduler->system_initialized(); thread_running = true; while (!_px4_thread_should_exit) { loop(); // yield the CPU between loops to let other apps // get some CPU time pthread_yield(); } thread_running = false; return 0; } static void usage(void) { printf("Usage: %s [options] {start,stop,status}\n", SKETCHNAME); printf("Options:\n"); printf("\t-d DEVICE set terminal device (default %s)\n", UARTA_DEFAULT_DEVICE); printf("\n"); } void HAL_PX4::init(int argc, char * const argv[]) const { int i; const char *device = UARTA_DEFAULT_DEVICE; if (argc < 1) { printf("%s: missing command (try '%s start')", SKETCHNAME, SKETCHNAME); usage(); exit(1); } for (i=0; i i + 1) { device = strdup(argv[i+1]); } else { printf("missing parameter to -d DEVICE\n"); usage(); exit(1); } } } usage(); exit(1); } const HAL_PX4 AP_HAL_PX4; #endif // CONFIG_HAL_BOARD == HAL_BOARD_PX4