ardupilot/libraries/AP_HAL_Linux/HAL_Linux_Class.cpp

136 lines
3.4 KiB
C++
Raw Normal View History

2013-09-22 03:01:24 -03:00
#include <AP_HAL.h>
2014-07-06 23:03:26 -03:00
#if CONFIG_HAL_BOARD == HAL_BOARD_LINUX
2013-09-22 03:01:24 -03:00
#include "HAL_Linux_Class.h"
#include "AP_HAL_Linux_Private.h"
#include <getopt.h>
#include <stdio.h>
#include <unistd.h>
#include <stdlib.h>
#include <AP_HAL_Empty.h>
#include <AP_HAL_Empty_Private.h>
2013-09-22 03:01:24 -03:00
using namespace Linux;
2013-09-28 11:51:43 -03:00
// 3 serial ports on Linux for now
static LinuxUARTDriver uartADriver(true);
static LinuxUARTDriver uartBDriver(false);
static LinuxUARTDriver uartCDriver(false);
2013-09-22 03:01:24 -03:00
static LinuxSemaphore i2cSemaphore;
static LinuxI2CDriver i2cDriver(&i2cSemaphore, "/dev/i2c-1");
2013-09-28 11:51:43 -03:00
static LinuxSPIDeviceManager spiDeviceManager;
2013-09-22 03:01:24 -03:00
static LinuxAnalogIn analogIn;
static LinuxStorage storageDriver;
/*
use the BBB gpio driver on ERLE and PXF
*/
#if CONFIG_HAL_BOARD_SUBTYPE == HAL_BOARD_SUBTYPE_LINUX_PXF || CONFIG_HAL_BOARD_SUBTYPE == HAL_BOARD_SUBTYPE_LINUX_ERLE
static LinuxGPIO_BBB gpioDriver;
/*
use the RPI gpio driver on Navio
*/
#elif CONFIG_HAL_BOARD_SUBTYPE == HAL_BOARD_SUBTYPE_LINUX_NAVIO
static LinuxGPIO_RPI gpioDriver;
#else
static Empty::EmptyGPIO gpioDriver;
#endif
/*
use the PRU based RCInput driver on ERLE and PXF
*/
#if CONFIG_HAL_BOARD_SUBTYPE == HAL_BOARD_SUBTYPE_LINUX_PXF || CONFIG_HAL_BOARD_SUBTYPE == HAL_BOARD_SUBTYPE_LINUX_ERLE
static LinuxRCInput_PRU rcinDriver;
#else
2013-09-22 03:01:24 -03:00
static LinuxRCInput rcinDriver;
#endif
/*
use the PRU based RCOutput driver on ERLE and PXF
*/
#if CONFIG_HAL_BOARD_SUBTYPE == HAL_BOARD_SUBTYPE_LINUX_PXF || CONFIG_HAL_BOARD_SUBTYPE == HAL_BOARD_SUBTYPE_LINUX_ERLE
static LinuxRCOutput_PRU rcoutDriver;
/*
use the PCA9685 based RCOutput driver on Navio
*/
#elif CONFIG_HAL_BOARD_SUBTYPE == HAL_BOARD_SUBTYPE_LINUX_NAVIO
static LinuxRCOutput_Navio rcoutDriver;
#else
static Empty::EmptyRCOutput rcoutDriver;
#endif
2013-09-22 03:01:24 -03:00
static LinuxScheduler schedulerInstance;
static LinuxUtil utilInstance;
HAL_Linux::HAL_Linux() :
AP_HAL::HAL(
&uartADriver,
&uartBDriver,
&uartCDriver,
2013-11-22 04:16:31 -04:00
NULL, /* no uartD */
2013-12-21 07:25:15 -04:00
NULL, /* no uartE */
2013-09-22 03:01:24 -03:00
&i2cDriver,
&spiDeviceManager,
&analogIn,
&storageDriver,
2013-10-05 05:32:57 -03:00
&uartADriver,
2013-09-22 03:01:24 -03:00
&gpioDriver,
&rcinDriver,
&rcoutDriver,
&schedulerInstance,
&utilInstance)
{}
void _usage(void)
{
printf("Usage: -A uartAPath -B uartBPath -C uartCPath\n");
printf("Options:\n");
printf("\t-serial: -A /dev/ttyO4\n");
printf("\t -B /dev/ttyS1\n");
printf("\t-tcp: -C tcp:192.168.2.15:1243:wait\n");
printf("\t -A tcp:11.0.0.2:5678\n");
}
2013-09-22 03:01:24 -03:00
void HAL_Linux::init(int argc,char* const argv[]) const
{
int opt;
/*
parse command line options
*/
2013-09-28 11:51:43 -03:00
while ((opt = getopt(argc, argv, "A:B:C:h")) != -1) {
2013-09-22 03:01:24 -03:00
switch (opt) {
case 'A':
uartADriver.set_device_path(optarg);
break;
case 'B':
uartBDriver.set_device_path(optarg);
break;
2013-09-28 11:51:43 -03:00
case 'C':
uartCDriver.set_device_path(optarg);
break;
2013-09-22 03:01:24 -03:00
case 'h':
_usage();
2013-09-22 03:01:24 -03:00
exit(0);
default:
printf("Unknown option '%c'\n", (char)opt);
exit(1);
}
}
scheduler->init(NULL);
2014-07-13 20:20:47 -03:00
gpio->init();
i2c->begin();
rcout->init(NULL);
rcin->init(NULL);
uartA->begin(115200);
2013-09-28 11:51:43 -03:00
spi->init(NULL);
utilInstance.init(argc, argv);
2013-09-22 03:01:24 -03:00
}
const HAL_Linux AP_HAL_Linux;
#endif