mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-30 12:38:33 -04:00
HAL_Linux: initial support for Disco
This commit is contained in:
parent
e407caaa41
commit
aaaa6d38c7
@ -407,7 +407,7 @@ void CameraSensor_Mt9v117::_init_sensor()
|
|||||||
|
|
||||||
id = _read_reg16(CHIP_ID);
|
id = _read_reg16(CHIP_ID);
|
||||||
if (id != MT9V117_CHIP_ID) {
|
if (id != MT9V117_CHIP_ID) {
|
||||||
AP_HAL::panic("Mt9v117: bad chip id\n");
|
AP_HAL::panic("Mt9v117: bad chip id 0x%04x\n", id);
|
||||||
}
|
}
|
||||||
_soft_reset();
|
_soft_reset();
|
||||||
_apply_patch();
|
_apply_patch();
|
||||||
|
@ -25,6 +25,6 @@ private:
|
|||||||
#include "GPIO_RPI.h"
|
#include "GPIO_RPI.h"
|
||||||
#elif CONFIG_HAL_BOARD_SUBTYPE == HAL_BOARD_SUBTYPE_LINUX_MINLURE
|
#elif CONFIG_HAL_BOARD_SUBTYPE == HAL_BOARD_SUBTYPE_LINUX_MINLURE
|
||||||
#include "GPIO_Minnow.h"
|
#include "GPIO_Minnow.h"
|
||||||
#elif CONFIG_HAL_BOARD_SUBTYPE == HAL_BOARD_SUBTYPE_LINUX_BEBOP
|
#elif CONFIG_HAL_BOARD_SUBTYPE == HAL_BOARD_SUBTYPE_LINUX_BEBOP || CONFIG_HAL_BOARD_SUBTYPE == HAL_BOARD_SUBTYPE_LINUX_DISCO
|
||||||
#include "GPIO_Bebop.h"
|
#include "GPIO_Bebop.h"
|
||||||
#endif
|
#endif
|
||||||
|
@ -2,7 +2,7 @@
|
|||||||
|
|
||||||
#include "GPIO_Bebop.h"
|
#include "GPIO_Bebop.h"
|
||||||
|
|
||||||
#if CONFIG_HAL_BOARD_SUBTYPE == HAL_BOARD_SUBTYPE_LINUX_BEBOP
|
#if CONFIG_HAL_BOARD_SUBTYPE == HAL_BOARD_SUBTYPE_LINUX_BEBOP || CONFIG_HAL_BOARD_SUBTYPE == HAL_BOARD_SUBTYPE_LINUX_DISCO
|
||||||
|
|
||||||
const unsigned Linux::GPIO_Sysfs::pin_table[] = {
|
const unsigned Linux::GPIO_Sysfs::pin_table[] = {
|
||||||
[BEBOP_GPIO_CAMV_NRST] = 129,
|
[BEBOP_GPIO_CAMV_NRST] = 129,
|
||||||
|
@ -45,7 +45,7 @@ static UARTDriver uartFDriver(false);
|
|||||||
|
|
||||||
static I2CDeviceManager i2c_mgr_instance;
|
static I2CDeviceManager i2c_mgr_instance;
|
||||||
|
|
||||||
#if CONFIG_HAL_BOARD_SUBTYPE == HAL_BOARD_SUBTYPE_LINUX_BEBOP
|
#if CONFIG_HAL_BOARD_SUBTYPE == HAL_BOARD_SUBTYPE_LINUX_BEBOP || CONFIG_HAL_BOARD_SUBTYPE == HAL_BOARD_SUBTYPE_LINUX_DISCO
|
||||||
static I2CDriver i2cDriver0(0);
|
static I2CDriver i2cDriver0(0);
|
||||||
static I2CDriver i2cDriver1(1);
|
static I2CDriver i2cDriver1(1);
|
||||||
static I2CDriver i2cDriver2(2);
|
static I2CDriver i2cDriver2(2);
|
||||||
@ -113,7 +113,9 @@ static GPIO_BBB gpioDriver;
|
|||||||
CONFIG_HAL_BOARD_SUBTYPE == HAL_BOARD_SUBTYPE_LINUX_BH || \
|
CONFIG_HAL_BOARD_SUBTYPE == HAL_BOARD_SUBTYPE_LINUX_BH || \
|
||||||
CONFIG_HAL_BOARD_SUBTYPE == HAL_BOARD_SUBTYPE_LINUX_PXFMINI
|
CONFIG_HAL_BOARD_SUBTYPE == HAL_BOARD_SUBTYPE_LINUX_PXFMINI
|
||||||
static GPIO_RPI gpioDriver;
|
static GPIO_RPI gpioDriver;
|
||||||
#elif CONFIG_HAL_BOARD_SUBTYPE == HAL_BOARD_SUBTYPE_LINUX_MINLURE || CONFIG_HAL_BOARD_SUBTYPE == HAL_BOARD_SUBTYPE_LINUX_BEBOP
|
#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
|
||||||
static GPIO_Sysfs gpioDriver;
|
static GPIO_Sysfs gpioDriver;
|
||||||
#else
|
#else
|
||||||
static Empty::GPIO gpioDriver;
|
static Empty::GPIO gpioDriver;
|
||||||
@ -135,7 +137,8 @@ static RCInput_RPI rcinDriver;
|
|||||||
static RCInput_Raspilot rcinDriver;
|
static RCInput_Raspilot rcinDriver;
|
||||||
#elif CONFIG_HAL_BOARD_SUBTYPE == HAL_BOARD_SUBTYPE_LINUX_ZYNQ
|
#elif CONFIG_HAL_BOARD_SUBTYPE == HAL_BOARD_SUBTYPE_LINUX_ZYNQ
|
||||||
static RCInput_ZYNQ rcinDriver;
|
static RCInput_ZYNQ rcinDriver;
|
||||||
#elif CONFIG_HAL_BOARD_SUBTYPE == HAL_BOARD_SUBTYPE_LINUX_BEBOP
|
#elif CONFIG_HAL_BOARD_SUBTYPE == HAL_BOARD_SUBTYPE_LINUX_BEBOP || \
|
||||||
|
CONFIG_HAL_BOARD_SUBTYPE == HAL_BOARD_SUBTYPE_LINUX_DISCO
|
||||||
static RCInput_UDP rcinDriver;
|
static RCInput_UDP rcinDriver;
|
||||||
#elif CONFIG_HAL_BOARD_SUBTYPE == HAL_BOARD_SUBTYPE_LINUX_MINLURE
|
#elif CONFIG_HAL_BOARD_SUBTYPE == HAL_BOARD_SUBTYPE_LINUX_MINLURE
|
||||||
static RCInput_UART rcinDriver("/dev/ttyS2");
|
static RCInput_UART rcinDriver("/dev/ttyS2");
|
||||||
@ -169,7 +172,8 @@ static RCOutput_PCA9685 rcoutDriver(i2c_mgr_instance.get_device(1, PCA9685_QUATE
|
|||||||
static RCOutput_Raspilot rcoutDriver;
|
static RCOutput_Raspilot rcoutDriver;
|
||||||
#elif CONFIG_HAL_BOARD_SUBTYPE == HAL_BOARD_SUBTYPE_LINUX_ZYNQ
|
#elif CONFIG_HAL_BOARD_SUBTYPE == HAL_BOARD_SUBTYPE_LINUX_ZYNQ
|
||||||
static RCOutput_ZYNQ rcoutDriver;
|
static RCOutput_ZYNQ rcoutDriver;
|
||||||
#elif CONFIG_HAL_BOARD_SUBTYPE == HAL_BOARD_SUBTYPE_LINUX_BEBOP
|
#elif CONFIG_HAL_BOARD_SUBTYPE == HAL_BOARD_SUBTYPE_LINUX_BEBOP || \
|
||||||
|
CONFIG_HAL_BOARD_SUBTYPE == HAL_BOARD_SUBTYPE_LINUX_DISCO
|
||||||
static RCOutput_Bebop rcoutDriver(i2c_mgr_instance.get_device(HAL_RCOUT_BEBOP_BLDC_I2C_BUS, HAL_RCOUT_BEBOP_BLDC_I2C_ADDR));
|
static RCOutput_Bebop rcoutDriver(i2c_mgr_instance.get_device(HAL_RCOUT_BEBOP_BLDC_I2C_BUS, HAL_RCOUT_BEBOP_BLDC_I2C_ADDR));
|
||||||
#elif CONFIG_HAL_BOARD_SUBTYPE == HAL_BOARD_SUBTYPE_LINUX_MINLURE
|
#elif CONFIG_HAL_BOARD_SUBTYPE == HAL_BOARD_SUBTYPE_LINUX_MINLURE
|
||||||
static RCOutput_PCA9685 rcoutDriver(i2c_mgr_instance.get_device(i2c_devpaths, PCA9685_PRIMARY_ADDRESS), false, 0, MINNOW_GPIO_S5_1);
|
static RCOutput_PCA9685 rcoutDriver(i2c_mgr_instance.get_device(i2c_devpaths, PCA9685_PRIMARY_ADDRESS), false, 0, MINNOW_GPIO_S5_1);
|
||||||
@ -200,7 +204,7 @@ HAL_Linux::HAL_Linux() :
|
|||||||
&uartEDriver,
|
&uartEDriver,
|
||||||
&uartFDriver,
|
&uartFDriver,
|
||||||
&i2c_mgr_instance,
|
&i2c_mgr_instance,
|
||||||
#if CONFIG_HAL_BOARD_SUBTYPE == HAL_BOARD_SUBTYPE_LINUX_BEBOP
|
#if CONFIG_HAL_BOARD_SUBTYPE == HAL_BOARD_SUBTYPE_LINUX_BEBOP || CONFIG_HAL_BOARD_SUBTYPE == HAL_BOARD_SUBTYPE_LINUX_DISCO
|
||||||
&i2cDriver0,
|
&i2cDriver0,
|
||||||
&i2cDriver1,
|
&i2cDriver1,
|
||||||
&i2cDriver2,
|
&i2cDriver2,
|
||||||
@ -330,7 +334,7 @@ void HAL_Linux::run(int argc, char* const argv[], Callbacks* callbacks) const
|
|||||||
scheduler->init();
|
scheduler->init();
|
||||||
gpio->init();
|
gpio->init();
|
||||||
i2c->begin();
|
i2c->begin();
|
||||||
#if CONFIG_HAL_BOARD_SUBTYPE == HAL_BOARD_SUBTYPE_LINUX_BEBOP
|
#if CONFIG_HAL_BOARD_SUBTYPE == HAL_BOARD_SUBTYPE_LINUX_BEBOP || CONFIG_HAL_BOARD_SUBTYPE == HAL_BOARD_SUBTYPE_LINUX_DISCO
|
||||||
i2c1->begin();
|
i2c1->begin();
|
||||||
i2c2->begin();
|
i2c2->begin();
|
||||||
#elif CONFIG_HAL_BOARD_SUBTYPE == HAL_BOARD_SUBTYPE_LINUX_MINLURE
|
#elif CONFIG_HAL_BOARD_SUBTYPE == HAL_BOARD_SUBTYPE_LINUX_MINLURE
|
||||||
|
@ -16,7 +16,7 @@
|
|||||||
|
|
||||||
#include <AP_HAL/AP_HAL.h>
|
#include <AP_HAL/AP_HAL.h>
|
||||||
|
|
||||||
#if CONFIG_HAL_BOARD_SUBTYPE == HAL_BOARD_SUBTYPE_LINUX_BEBOP
|
#if CONFIG_HAL_BOARD_SUBTYPE == HAL_BOARD_SUBTYPE_LINUX_BEBOP || CONFIG_HAL_BOARD_SUBTYPE == HAL_BOARD_SUBTYPE_LINUX_DISCO
|
||||||
#include <cmath>
|
#include <cmath>
|
||||||
#include <fcntl.h>
|
#include <fcntl.h>
|
||||||
#include <linux/limits.h>
|
#include <linux/limits.h>
|
||||||
|
@ -1,6 +1,6 @@
|
|||||||
#include <AP_HAL/AP_HAL.h>
|
#include <AP_HAL/AP_HAL.h>
|
||||||
|
|
||||||
#if CONFIG_HAL_BOARD_SUBTYPE == HAL_BOARD_SUBTYPE_LINUX_BEBOP
|
#if CONFIG_HAL_BOARD_SUBTYPE == HAL_BOARD_SUBTYPE_LINUX_BEBOP || CONFIG_HAL_BOARD_SUBTYPE == HAL_BOARD_SUBTYPE_LINUX_DISCO
|
||||||
#include "RCOutput_Bebop.h"
|
#include "RCOutput_Bebop.h"
|
||||||
|
|
||||||
#include <errno.h>
|
#include <errno.h>
|
||||||
@ -176,7 +176,7 @@ int RCOutput_Bebop::read_obs_data(BebopBLDC_ObsData &obs)
|
|||||||
_dev->get_semaphore()->give();
|
_dev->get_semaphore()->give();
|
||||||
|
|
||||||
if (data.checksum != _checksum((uint8_t *)&data, sizeof(data) - 1)) {
|
if (data.checksum != _checksum((uint8_t *)&data, sizeof(data) - 1)) {
|
||||||
hal.console->printf("RCOutput_Bebop: bad checksum in obs data");
|
return -EBUSY;
|
||||||
}
|
}
|
||||||
|
|
||||||
/* fill obs class */
|
/* fill obs class */
|
||||||
@ -425,6 +425,8 @@ void RCOutput_Bebop::_run_rcout()
|
|||||||
_max_rpm = BEBOP_BLDC_MAX_RPM_1;
|
_max_rpm = BEBOP_BLDC_MAX_RPM_1;
|
||||||
} else if (hw_version == UTIL_HARDWARE_BEBOP2) {
|
} else if (hw_version == UTIL_HARDWARE_BEBOP2) {
|
||||||
_max_rpm = BEBOP_BLDC_MAX_RPM_2;
|
_max_rpm = BEBOP_BLDC_MAX_RPM_2;
|
||||||
|
} else if (hw_version == UTIL_HARDWARE_DISCO) {
|
||||||
|
_max_rpm = BEBOP_BLDC_MAX_RPM_2;
|
||||||
} else if (hw_version < 0) {
|
} else if (hw_version < 0) {
|
||||||
AP_HAL::panic("failed to get hw version %s", strerror(hw_version));
|
AP_HAL::panic("failed to get hw version %s", strerror(hw_version));
|
||||||
} else {
|
} else {
|
||||||
|
@ -75,7 +75,7 @@ SPIDeviceDriver SPIDeviceManager::_device[] = {
|
|||||||
SPIDeviceDriver("mpu9250", 0, 0, AP_HAL::SPIDevice_MPU9250, SPI_MODE_0, 8, RPI_GPIO_7, 1*MHZ, 20*MHZ),
|
SPIDeviceDriver("mpu9250", 0, 0, AP_HAL::SPIDevice_MPU9250, SPI_MODE_0, 8, RPI_GPIO_7, 1*MHZ, 20*MHZ),
|
||||||
SPIDeviceDriver("ublox", 0, 0, AP_HAL::SPIDevice_Ublox, SPI_MODE_0, 8, RPI_GPIO_8, 250*KHZ, 5*MHZ),
|
SPIDeviceDriver("ublox", 0, 0, AP_HAL::SPIDevice_Ublox, SPI_MODE_0, 8, RPI_GPIO_8, 250*KHZ, 5*MHZ),
|
||||||
};
|
};
|
||||||
#elif CONFIG_HAL_BOARD_SUBTYPE == HAL_BOARD_SUBTYPE_LINUX_BEBOP
|
#elif CONFIG_HAL_BOARD_SUBTYPE == HAL_BOARD_SUBTYPE_LINUX_BEBOP || CONFIG_HAL_BOARD_SUBTYPE == HAL_BOARD_SUBTYPE_LINUX_DISCO
|
||||||
SPIDeviceDriver SPIDeviceManager::_device[] = {
|
SPIDeviceDriver SPIDeviceManager::_device[] = {
|
||||||
SPIDeviceDriver("bebop", 1, 0, AP_HAL::SPIDevice_Bebop, SPI_MODE_0, 8, SPI_CS_KERNEL, 320*KHZ, 320*KHZ),
|
SPIDeviceDriver("bebop", 1, 0, AP_HAL::SPIDevice_Bebop, SPI_MODE_0, 8, SPI_CS_KERNEL, 320*KHZ, 320*KHZ),
|
||||||
};
|
};
|
||||||
|
@ -185,7 +185,7 @@ void Scheduler::register_timer_process(AP_HAL::MemberProc proc)
|
|||||||
bool Scheduler::register_timer_process(AP_HAL::MemberProc proc,
|
bool Scheduler::register_timer_process(AP_HAL::MemberProc proc,
|
||||||
uint8_t freq_div)
|
uint8_t freq_div)
|
||||||
{
|
{
|
||||||
#if CONFIG_HAL_BOARD_SUBTYPE == HAL_BOARD_SUBTYPE_LINUX_BEBOP
|
#if CONFIG_HAL_BOARD_SUBTYPE == HAL_BOARD_SUBTYPE_LINUX_BEBOP || CONFIG_HAL_BOARD_SUBTYPE == HAL_BOARD_SUBTYPE_LINUX_DISCO
|
||||||
if (freq_div > 1) {
|
if (freq_div > 1) {
|
||||||
return _register_timesliced_proc(proc, freq_div);
|
return _register_timesliced_proc(proc, freq_div);
|
||||||
}
|
}
|
||||||
|
@ -20,7 +20,7 @@ using namespace Linux;
|
|||||||
|
|
||||||
// name the storage file after the sketch so you can use the same board
|
// name the storage file after the sketch so you can use the same board
|
||||||
// card for ArduCopter and ArduPlane
|
// card for ArduCopter and ArduPlane
|
||||||
#if CONFIG_HAL_BOARD_SUBTYPE == HAL_BOARD_SUBTYPE_LINUX_BEBOP
|
#if CONFIG_HAL_BOARD_SUBTYPE == HAL_BOARD_SUBTYPE_LINUX_BEBOP || CONFIG_HAL_BOARD_SUBTYPE == HAL_BOARD_SUBTYPE_LINUX_DISCO
|
||||||
#define STORAGE_DIR "/data/ftp/internal_000/APM"
|
#define STORAGE_DIR "/data/ftp/internal_000/APM"
|
||||||
#elif APM_BUILD_TYPE(APM_BUILD_Replay)
|
#elif APM_BUILD_TYPE(APM_BUILD_Replay)
|
||||||
#define STORAGE_DIR "."
|
#define STORAGE_DIR "."
|
||||||
|
@ -178,6 +178,7 @@ const char *Linux::Util::_hw_names[UTIL_NUM_HARDWARES] = {
|
|||||||
[UTIL_HARDWARE_RPI2] = "BCM2709",
|
[UTIL_HARDWARE_RPI2] = "BCM2709",
|
||||||
[UTIL_HARDWARE_BEBOP] = "Mykonos3 board",
|
[UTIL_HARDWARE_BEBOP] = "Mykonos3 board",
|
||||||
[UTIL_HARDWARE_BEBOP2] = "Milos board",
|
[UTIL_HARDWARE_BEBOP2] = "Milos board",
|
||||||
|
[UTIL_HARDWARE_DISCO] = "Evinrude board",
|
||||||
};
|
};
|
||||||
|
|
||||||
#define MAX_SIZE_LINE 50
|
#define MAX_SIZE_LINE 50
|
||||||
|
@ -13,6 +13,7 @@ enum hw_type {
|
|||||||
UTIL_HARDWARE_RPI2,
|
UTIL_HARDWARE_RPI2,
|
||||||
UTIL_HARDWARE_BEBOP,
|
UTIL_HARDWARE_BEBOP,
|
||||||
UTIL_HARDWARE_BEBOP2,
|
UTIL_HARDWARE_BEBOP2,
|
||||||
|
UTIL_HARDWARE_DISCO,
|
||||||
UTIL_NUM_HARDWARES,
|
UTIL_NUM_HARDWARES,
|
||||||
};
|
};
|
||||||
|
|
||||||
|
Loading…
Reference in New Issue
Block a user