mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-02-19 14:23:57 -04:00
AP_HAL_Linux: add port to Intel Aero
Contributions from: - Gustavo Jose de Sousa <gustavo.sousa@intel.com> - José Roberto de Souza <jose.souza@intel.com> - Lucas De Marchi <lucas.demarchi@intel.com> - Patrick J.P <patrick.pereira@intel.com>
This commit is contained in:
parent
0b0be31a29
commit
025082b280
@ -33,4 +33,6 @@ private:
|
||||
#include "GPIO_Bebop.h"
|
||||
#elif CONFIG_HAL_BOARD_SUBTYPE == HAL_BOARD_SUBTYPE_LINUX_DISCO
|
||||
#include "GPIO_Disco.h"
|
||||
#elif CONFIG_HAL_BOARD_SUBTYPE == HAL_BOARD_SUBTYPE_LINUX_AERO
|
||||
#include "GPIO_Aero.h"
|
||||
#endif
|
||||
|
34
libraries/AP_HAL_Linux/GPIO_Aero.cpp
Normal file
34
libraries/AP_HAL_Linux/GPIO_Aero.cpp
Normal file
@ -0,0 +1,34 @@
|
||||
/*
|
||||
* Copyright (C) 2016 Intel Corporation. All rights reserved.
|
||||
*
|
||||
* This file is free software: you can redistribute it and/or modify it
|
||||
* under the terms of the GNU General Public License as published by the
|
||||
* Free Software Foundation, either version 3 of the License, or
|
||||
* (at your option) any later version.
|
||||
*
|
||||
* This file is distributed in the hope that it will be useful, but
|
||||
* WITHOUT ANY WARRANTY; without even the implied warranty of
|
||||
* MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE.
|
||||
* See the GNU General Public License for more details.
|
||||
*
|
||||
* You should have received a copy of the GNU General Public License along
|
||||
* with this program. If not, see <http://www.gnu.org/licenses/>.
|
||||
*/
|
||||
#include <AP_HAL/AP_HAL.h>
|
||||
|
||||
#if CONFIG_HAL_BOARD_SUBTYPE == HAL_BOARD_SUBTYPE_LINUX_AERO
|
||||
|
||||
#include <AP_Common/AP_Common.h>
|
||||
|
||||
#include "GPIO_Aero.h"
|
||||
|
||||
const unsigned Linux::GPIO_Sysfs::pin_table[] = {
|
||||
[AERO_GPIO_BMI160_INT1] = 411,
|
||||
};
|
||||
|
||||
const uint8_t Linux::GPIO_Sysfs::n_pins = _AERO_GPIO_MAX;
|
||||
|
||||
static_assert(ARRAY_SIZE(Linux::GPIO_Sysfs::pin_table) == _AERO_GPIO_MAX,
|
||||
"GPIO pin_table must have the same size of entries in enum gpio_aero");
|
||||
|
||||
#endif
|
24
libraries/AP_HAL_Linux/GPIO_Aero.h
Normal file
24
libraries/AP_HAL_Linux/GPIO_Aero.h
Normal file
@ -0,0 +1,24 @@
|
||||
/*
|
||||
* Copyright (C) 2016 Intel Corporation. All rights reserved.
|
||||
*
|
||||
* This file is free software: you can redistribute it and/or modify it
|
||||
* under the terms of the GNU General Public License as published by the
|
||||
* Free Software Foundation, either version 3 of the License, or
|
||||
* (at your option) any later version.
|
||||
*
|
||||
* This file is distributed in the hope that it will be useful, but
|
||||
* WITHOUT ANY WARRANTY; without even the implied warranty of
|
||||
* MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE.
|
||||
* See the GNU General Public License for more details.
|
||||
*
|
||||
* You should have received a copy of the GNU General Public License along
|
||||
* with this program. If not, see <http://www.gnu.org/licenses/>.
|
||||
*/
|
||||
#pragma once
|
||||
|
||||
#include "GPIO_Sysfs.h"
|
||||
|
||||
enum gpio_aero {
|
||||
AERO_GPIO_BMI160_INT1,
|
||||
_AERO_GPIO_MAX
|
||||
};
|
@ -28,6 +28,7 @@
|
||||
#include "RCInput_SBUS.h"
|
||||
#include "RCInput_UART.h"
|
||||
#include "RCInput_UDP.h"
|
||||
#include "RCOutput_AeroIO.h"
|
||||
#include "RCOutput_AioPRU.h"
|
||||
#include "RCOutput_Bebop.h"
|
||||
#include "RCOutput_Disco.h"
|
||||
@ -116,7 +117,8 @@ static GPIO_BBB gpioDriver;
|
||||
static GPIO_RPI gpioDriver;
|
||||
#elif CONFIG_HAL_BOARD_SUBTYPE == HAL_BOARD_SUBTYPE_LINUX_MINLURE || \
|
||||
CONFIG_HAL_BOARD_SUBTYPE == HAL_BOARD_SUBTYPE_LINUX_BEBOP || \
|
||||
CONFIG_HAL_BOARD_SUBTYPE == HAL_BOARD_SUBTYPE_LINUX_DISCO
|
||||
CONFIG_HAL_BOARD_SUBTYPE == HAL_BOARD_SUBTYPE_LINUX_DISCO || \
|
||||
CONFIG_HAL_BOARD_SUBTYPE == HAL_BOARD_SUBTYPE_LINUX_AERO
|
||||
static GPIO_Sysfs gpioDriver;
|
||||
#else
|
||||
static Empty::GPIO gpioDriver;
|
||||
@ -144,7 +146,8 @@ static RCInput_UDP rcinDriver;
|
||||
static RCInput_UART rcinDriver("/dev/ttyS2");
|
||||
#elif CONFIG_HAL_BOARD_SUBTYPE == HAL_BOARD_SUBTYPE_LINUX_QFLIGHT
|
||||
static RCInput_DSM rcinDriver;
|
||||
#elif CONFIG_HAL_BOARD_SUBTYPE == HAL_BOARD_SUBTYPE_LINUX_DISCO
|
||||
#elif CONFIG_HAL_BOARD_SUBTYPE == HAL_BOARD_SUBTYPE_LINUX_DISCO || \
|
||||
CONFIG_HAL_BOARD_SUBTYPE == HAL_BOARD_SUBTYPE_LINUX_AERO
|
||||
static RCInput_SBUS rcinDriver;
|
||||
#elif CONFIG_HAL_BOARD_SUBTYPE == HAL_BOARD_SUBTYPE_LINUX_NAVIO2
|
||||
static RCInput_Navio2 rcinDriver;
|
||||
@ -195,6 +198,8 @@ static RCOutput_QFLIGHT rcoutDriver;
|
||||
static RCOutput_Disco rcoutDriver(i2c_mgr_instance.get_device(HAL_RCOUT_DISCO_BLDC_I2C_BUS, HAL_RCOUT_DISCO_BLDC_I2C_ADDR));
|
||||
#elif CONFIG_HAL_BOARD_SUBTYPE == HAL_BOARD_SUBTYPE_LINUX_NAVIO2
|
||||
static RCOutput_Sysfs rcoutDriver(0, 0, 14);
|
||||
#elif CONFIG_HAL_BOARD_SUBTYPE == HAL_BOARD_SUBTYPE_LINUX_AERO
|
||||
static RCOutput_AeroIO rcoutDriver;
|
||||
#else
|
||||
static Empty::RCOutput rcoutDriver;
|
||||
#endif
|
||||
|
@ -21,7 +21,8 @@
|
||||
|
||||
#include <AP_HAL/AP_HAL.h>
|
||||
|
||||
#if CONFIG_HAL_BOARD_SUBTYPE == HAL_BOARD_SUBTYPE_LINUX_DISCO
|
||||
#if CONFIG_HAL_BOARD_SUBTYPE == HAL_BOARD_SUBTYPE_LINUX_DISCO || \
|
||||
CONFIG_HAL_BOARD_SUBTYPE == HAL_BOARD_SUBTYPE_LINUX_AERO
|
||||
#include "RCInput_SBUS.h"
|
||||
#include <stdio.h>
|
||||
#include <fcntl.h>
|
||||
|
@ -16,7 +16,8 @@
|
||||
#pragma once
|
||||
|
||||
#include <AP_HAL/AP_HAL.h>
|
||||
#if CONFIG_HAL_BOARD_SUBTYPE == HAL_BOARD_SUBTYPE_LINUX_DISCO
|
||||
#if CONFIG_HAL_BOARD_SUBTYPE == HAL_BOARD_SUBTYPE_LINUX_DISCO || \
|
||||
CONFIG_HAL_BOARD_SUBTYPE == HAL_BOARD_SUBTYPE_LINUX_AERO
|
||||
|
||||
#include "RCInput.h"
|
||||
#include "RCInput_SBUS.h"
|
||||
@ -31,7 +32,13 @@ public:
|
||||
void set_device_path(const char *path);
|
||||
|
||||
private:
|
||||
#if CONFIG_HAL_BOARD_SUBTYPE == HAL_BOARD_SUBTYPE_LINUX_AERO
|
||||
const char *device_path = "/dev/ttyS1";
|
||||
#elif CONFIG_HAL_BOARD_SUBTYPE == HAL_BOARD_SUBTYPE_LINUX_DISCO
|
||||
const char *device_path = "/dev/uart-sbus";
|
||||
#else
|
||||
const char *device_path = nullptr;
|
||||
#endif
|
||||
int32_t fd = -1;
|
||||
};
|
||||
|
||||
|
@ -122,6 +122,11 @@ SPIDesc SPIDeviceManager::_device[] = {
|
||||
SPIDesc SPIDeviceManager::_device[] = {
|
||||
SPIDesc("bebop", 1, 0, SPI_MODE_0, 8, SPI_CS_KERNEL, 320*KHZ, 320*KHZ),
|
||||
};
|
||||
#elif CONFIG_HAL_BOARD_SUBTYPE == HAL_BOARD_SUBTYPE_LINUX_AERO
|
||||
SPIDesc SPIDeviceManager::_device[] = {
|
||||
SPIDesc("aeroio", 1, 1, SPI_MODE_0, 8, SPI_CS_KERNEL, 10*MHZ, 10*MHZ),
|
||||
SPIDesc("bmi160", 3, 0, SPI_MODE_3, 8, SPI_CS_KERNEL, 1*MHZ, 10*MHZ),
|
||||
};
|
||||
#else
|
||||
// empty device table
|
||||
SPIDesc SPIDeviceManager::_device[] = {
|
||||
|
Loading…
Reference in New Issue
Block a user