mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-03 14:38:30 -04:00
Add aerofc support
Flight Controller board that comes on Intel Aero RTF Drone.
This commit is contained in:
parent
d2aef41b08
commit
b17acfee12
@ -191,6 +191,7 @@ bool AP_Arming_Copter::board_voltage_checks(bool display_failure)
|
||||
{
|
||||
#if CONFIG_HAL_BOARD != HAL_BOARD_VRBRAIN
|
||||
#ifndef CONFIG_ARCH_BOARD_PX4FMU_V1
|
||||
#ifndef CONFIG_ARCH_BOARD_AEROFC_V1
|
||||
// check board voltage
|
||||
if ((checks_to_perform == ARMING_CHECK_ALL) || (checks_to_perform & ARMING_CHECK_VOLTAGE)) {
|
||||
if (hal.analogin->board_voltage() < BOARD_VOLTAGE_MIN || hal.analogin->board_voltage() > BOARD_VOLTAGE_MAX) {
|
||||
@ -202,6 +203,7 @@ bool AP_Arming_Copter::board_voltage_checks(bool display_failure)
|
||||
}
|
||||
#endif
|
||||
#endif
|
||||
#endif
|
||||
|
||||
Parameters &g = copter.g;
|
||||
|
||||
|
@ -508,3 +508,11 @@ class px4_v4(px4):
|
||||
self.bootloader_name = 'px4fmuv4_bl.bin'
|
||||
self.board_name = 'px4fmu-v4'
|
||||
self.romfs_exclude(['oreoled.bin'])
|
||||
|
||||
class aerofc_v1(px4):
|
||||
name = 'aerofc-v1'
|
||||
def __init__(self):
|
||||
super(aerofc_v1, self).__init__()
|
||||
self.bootloader_name = 'aerofcv1_bl.bin'
|
||||
self.board_name = 'aerofc-v1'
|
||||
self.romfs_exclude(['oreoled.bin'])
|
||||
|
@ -0,0 +1,11 @@
|
||||
include(configs/nuttx_px4fmu-common_apm)
|
||||
|
||||
list(APPEND config_module_list
|
||||
drivers/boards/aerofc-v1
|
||||
lib/rc
|
||||
)
|
||||
|
||||
list(REMOVE_ITEM config_module_list
|
||||
drivers/stm32/adc
|
||||
drivers/stm32/tone_alarm
|
||||
)
|
@ -38,6 +38,11 @@
|
||||
#elif defined(CONFIG_ARCH_BOARD_PX4FMU_V4)
|
||||
#define BOARD_PWM_COUNT_DEFAULT 6
|
||||
#define BOARD_SER1_RTSCTS_DEFAULT 2
|
||||
#elif defined(CONFIG_ARCH_BOARD_AEROFC_V1)
|
||||
#define BOARD_PWM_COUNT_DEFAULT 0
|
||||
#define BOARD_SER1_RTSCTS_DEFAULT 0
|
||||
# undef BOARD_SAFETY_ENABLE_DEFAULT
|
||||
# define BOARD_SAFETY_ENABLE_DEFAULT 0
|
||||
#else // V2
|
||||
#define BOARD_PWM_COUNT_DEFAULT 4
|
||||
#define BOARD_SER1_RTSCTS_DEFAULT 2
|
||||
@ -154,7 +159,7 @@ const AP_Param::GroupInfo AP_BoardConfig::var_info[] = {
|
||||
// @Param: TYPE
|
||||
// @DisplayName: Board type
|
||||
// @Description: This allows selection of a PX4 or VRBRAIN board type. If set to zero then the board type is auto-detected (PX4)
|
||||
// @Values: 0:AUTO,1:PX4V1,2:Pixhawk,3:Pixhawk2,4:Pixracer,5:PixhawkMini,6:Pixhawk2Slim,7:VRBrain 5.1,8:VRBrain 5.2,9:VR Micro Brain 5.1,10:VR Micro Brain 5.2,11:VRBrain Core 1.0,12:VRBrain 5.4,20:AUAV2.1
|
||||
// @Values: 0:AUTO,1:PX4V1,2:Pixhawk,3:Pixhawk2,4:Pixracer,5:PixhawkMini,6:Pixhawk2Slim,7:VRBrain 5.1,8:VRBrain 5.2,9:VR Micro Brain 5.1,10:VR Micro Brain 5.2,11:VRBrain Core 1.0,12:VRBrain 5.4,13:Intel Aero FC,20:AUAV2.1
|
||||
// @RebootRequired: True
|
||||
// @User: Advanced
|
||||
AP_GROUPINFO("TYPE", 9, AP_BoardConfig, px4.board_type, BOARD_TYPE_DEFAULT),
|
||||
|
@ -46,6 +46,7 @@ public:
|
||||
PX4_BOARD_PIXRACER = 4,
|
||||
PX4_BOARD_PHMINI = 5,
|
||||
PX4_BOARD_PH2SLIM = 6,
|
||||
PX4_BOARD_AEROFC = 7,
|
||||
PX4_BOARD_AUAV21 = 20,
|
||||
PX4_BOARD_OLDDRIVERS = 100,
|
||||
#endif
|
||||
|
@ -402,6 +402,7 @@ void AP_BoardConfig::px4_setup_px4io(void)
|
||||
*/
|
||||
void AP_BoardConfig::px4_setup_peripherals(void)
|
||||
{
|
||||
#ifndef CONFIG_ARCH_BOARD_AEROFC_V1
|
||||
// always start adc
|
||||
if (px4_start_driver(adc_main, "adc", "start")) {
|
||||
hal.analogin->init();
|
||||
@ -409,13 +410,17 @@ void AP_BoardConfig::px4_setup_peripherals(void)
|
||||
} else {
|
||||
px4_sensor_error("no ADC found");
|
||||
}
|
||||
#endif
|
||||
|
||||
#ifndef CONFIG_ARCH_BOARD_PX4FMU_V4
|
||||
#if !defined(CONFIG_ARCH_BOARD_PX4FMU_V4) && \
|
||||
!defined(CONFIG_ARCH_BOARD_AEROFC_V1)
|
||||
px4_setup_px4io();
|
||||
#endif
|
||||
|
||||
#ifdef CONFIG_ARCH_BOARD_PX4FMU_V1
|
||||
#if defined(CONFIG_ARCH_BOARD_PX4FMU_V1)
|
||||
const char *fmu_mode = "mode_serial";
|
||||
#elif defined(CONFIG_ARCH_BOARD_AEROFC_V1)
|
||||
const char *fmu_mode = "mode_rcin";
|
||||
#else
|
||||
const char *fmu_mode = "mode_pwm4";
|
||||
#endif
|
||||
@ -504,6 +509,9 @@ void AP_BoardConfig::px4_autodetect(void)
|
||||
// only one choice
|
||||
px4.board_type.set_and_notify(PX4_BOARD_PIXRACER);
|
||||
hal.console->printf("Detected Pixracer\n");
|
||||
#elif defined(CONFIG_ARCH_BOARD_AEROFC_V1)
|
||||
px4.board_type.set_and_notify(PX4_BOARD_AEROFC);
|
||||
hal.console->printf("Detected Aero FC\n");
|
||||
#endif
|
||||
|
||||
}
|
||||
|
@ -43,6 +43,7 @@
|
||||
#define HAL_BOARD_SUBTYPE_PX4_V2 2001
|
||||
#define HAL_BOARD_SUBTYPE_PX4_V4 2002
|
||||
#define HAL_BOARD_SUBTYPE_PX4_V3 2003
|
||||
#define HAL_BOARD_SUBTYPE_PX4_AEROFC_V1 2004
|
||||
|
||||
/* HAL VRBRAIN sub-types, starting at 4000 */
|
||||
#define HAL_BOARD_SUBTYPE_VRBRAIN_V45 4000
|
||||
|
@ -31,6 +31,12 @@
|
||||
#define CONFIG_HAL_BOARD_SUBTYPE HAL_BOARD_SUBTYPE_PX4_V4
|
||||
#define HAL_STORAGE_SIZE 16384
|
||||
#define HAL_WITH_UAVCAN 1
|
||||
#elif defined(CONFIG_ARCH_BOARD_AEROFC_V1)
|
||||
#define CONFIG_HAL_BOARD_SUBTYPE HAL_BOARD_SUBTYPE_PX4_AEROFC_V1
|
||||
#define HAL_STORAGE_SIZE 16384
|
||||
#define USE_FLASH_STORAGE 1
|
||||
// we don't have any sdcard
|
||||
#undef HAL_OS_POSIX_IO
|
||||
#else
|
||||
#error "Unknown PX4 board type"
|
||||
#endif
|
||||
|
@ -58,9 +58,11 @@ static const struct {
|
||||
{ 13, 3.3f/4096 }, // AUX ADC pin 4
|
||||
{ 14, 3.3f/4096 }, // AUX ADC pin 3
|
||||
{ 15, 6.6f/4096 }, // analog airspeed sensor, 2:1 scaling
|
||||
#elif defined(CONFIG_ARCH_BOARD_AEROFC_V1)
|
||||
#else
|
||||
#error "Unknown board type for AnalogIn scaling"
|
||||
#endif
|
||||
{ 0, 0.f },
|
||||
};
|
||||
|
||||
using namespace PX4;
|
||||
@ -114,7 +116,7 @@ float PX4AnalogSource::read_latest()
|
||||
float PX4AnalogSource::_pin_scaler(void)
|
||||
{
|
||||
float scaling = PX4_VOLTAGE_SCALING;
|
||||
uint8_t num_scalings = ARRAY_SIZE(pin_scaling);
|
||||
uint8_t num_scalings = ARRAY_SIZE(pin_scaling) - 1;
|
||||
for (uint8_t i=0; i<num_scalings; i++) {
|
||||
if (pin_scaling[i].pin == _pin) {
|
||||
scaling = pin_scaling[i].scaling;
|
||||
|
@ -57,6 +57,15 @@ static PX4::SPIDeviceManager spi_mgr_instance;
|
||||
#define UARTD_DEFAULT_DEVICE "/dev/ttyS2"
|
||||
#define UARTE_DEFAULT_DEVICE "/dev/ttyS6" // frsky telem
|
||||
#define UARTF_DEFAULT_DEVICE "/dev/ttyS0" // wifi
|
||||
#elif defined(CONFIG_ARCH_BOARD_AEROFC_V1)
|
||||
#define UARTA_DEFAULT_DEVICE "/dev/ttyS1" // Aero
|
||||
#define UARTB_DEFAULT_DEVICE "/dev/ttyS2" // GPS
|
||||
#define UARTC_DEFAULT_DEVICE "/dev/ttyS4" // Telem
|
||||
// ttyS0: ESC
|
||||
// ttyS3: RC
|
||||
#define UARTD_DEFAULT_DEVICE "/dev/null"
|
||||
#define UARTE_DEFAULT_DEVICE "/dev/null"
|
||||
#define UARTF_DEFAULT_DEVICE "/dev/null"
|
||||
#else
|
||||
#define UARTA_DEFAULT_DEVICE "/dev/ttyACM0"
|
||||
#define UARTB_DEFAULT_DEVICE "/dev/ttyS3"
|
||||
|
@ -114,6 +114,8 @@ bool PX4Util::get_system_id(char buf[40])
|
||||
const char *board_type = "PX4v2";
|
||||
#elif defined(CONFIG_ARCH_BOARD_PX4FMU_V4)
|
||||
const char *board_type = "PX4v4";
|
||||
#elif defined(CONFIG_ARCH_BOARD_AEROFC_V1)
|
||||
const char *board_type = "AEROFCv1";
|
||||
#else
|
||||
const char *board_type = "PX4v?";
|
||||
#endif
|
||||
@ -236,7 +238,8 @@ extern "C" {
|
||||
*/
|
||||
void *PX4Util::dma_allocate(size_t size)
|
||||
{
|
||||
#ifndef CONFIG_ARCH_BOARD_PX4FMU_V1
|
||||
#if !defined(CONFIG_ARCH_BOARD_PX4FMU_V1) && \
|
||||
!defined(CONFIG_ARCH_BOARD_AEROFC_V1)
|
||||
return fat_dma_alloc(size);
|
||||
#else
|
||||
return malloc(size);
|
||||
@ -244,7 +247,8 @@ void *PX4Util::dma_allocate(size_t size)
|
||||
}
|
||||
void PX4Util::dma_free(void *ptr, size_t size)
|
||||
{
|
||||
#ifndef CONFIG_ARCH_BOARD_PX4FMU_V1
|
||||
#if !defined(CONFIG_ARCH_BOARD_PX4FMU_V1) && \
|
||||
!defined(CONFIG_ARCH_BOARD_AEROFC_V1)
|
||||
fat_dma_free(ptr, size);
|
||||
#else
|
||||
return free(ptr);
|
||||
|
@ -46,7 +46,8 @@ extern "C" {
|
||||
AP_RPM_PX4_PWM::AP_RPM_PX4_PWM(AP_RPM &_ap_rpm, uint8_t instance, AP_RPM::RPM_State &_state) :
|
||||
AP_RPM_Backend(_ap_rpm, instance, _state)
|
||||
{
|
||||
#ifndef CONFIG_ARCH_BOARD_PX4FMU_V1
|
||||
#if !defined(CONFIG_ARCH_BOARD_PX4FMU_V1) && \
|
||||
!defined(CONFIG_ARCH_BOARD_AEROFC_V1)
|
||||
if (AP_BoardConfig::px4_start_driver(pwm_input_main, "pwm_input", "start")) {
|
||||
hal.console->printf("started pwm_input driver\n");
|
||||
}
|
||||
|
@ -85,7 +85,8 @@ AP_RangeFinder_PX4_PWM::~AP_RangeFinder_PX4_PWM()
|
||||
*/
|
||||
bool AP_RangeFinder_PX4_PWM::detect(RangeFinder &_ranger, uint8_t instance)
|
||||
{
|
||||
#ifndef CONFIG_ARCH_BOARD_PX4FMU_V1
|
||||
#if !defined(CONFIG_ARCH_BOARD_PX4FMU_V1) && \
|
||||
!defined(CONFIG_ARCH_BOARD_AEROFC_V1)
|
||||
if (AP_BoardConfig::px4_start_driver(pwm_input_main, "pwm_input", "start")) {
|
||||
hal.console->printf("started pwm_input driver\n");
|
||||
}
|
||||
|
Loading…
Reference in New Issue
Block a user