mirror of
https://bitbucket.org/librepilot/librepilot.git
synced 2025-02-20 10:54:14 +01:00
LP-480 build discoveryf4bare
This commit is contained in:
parent
dd49ef0166
commit
c0adcb904b
@ -184,7 +184,7 @@
|
||||
/* Begin PBXLegacyTarget section */
|
||||
6581071511DE809D0049FB12 /* OpenPilotOSX */ = {
|
||||
isa = PBXLegacyTarget;
|
||||
buildArgumentsString = ef_sparky2;
|
||||
buildArgumentsString = ef_discoveryf4bare;
|
||||
buildConfigurationList = 6581071A11DE80A30049FB12 /* Build configuration list for PBXLegacyTarget "OpenPilotOSX" */;
|
||||
buildPhases = (
|
||||
);
|
||||
|
@ -708,14 +708,19 @@ void PIOS_BOARD_IO_Configure_I2C(uint32_t i2c_internal_id, uint32_t i2c_external
|
||||
|
||||
if (hmc5x83_internal_cfg) {
|
||||
// attach the 5x83 mag to internal i2c bus
|
||||
pios_hmc5x83_internal_id = PIOS_HMC5x83_Init(hmc5x83_internal_cfg, i2c_internal_id, 0);
|
||||
|
||||
pios_hmc5x83_dev_t internal_mag = PIOS_HMC5x83_Init(hmc5x83_internal_cfg, i2c_internal_id, 0);
|
||||
# ifdef PIOS_INCLUDE_WDG
|
||||
// give HMC5x83 on I2C some extra time to allow for reset, etc. if needed
|
||||
// this is not in a loop, so it is safe
|
||||
PIOS_WDG_Clear();
|
||||
# endif /* PIOS_INCLUDE_WDG */
|
||||
|
||||
#ifdef PIOS_HMC5X83_HAS_GPIOS
|
||||
pios_hmc5x83_internal_id = internal_mag;
|
||||
#endif
|
||||
// add this sensor to the sensor task's list
|
||||
PIOS_HMC5x83_Register(pios_hmc5x83_internal_id, PIOS_SENSORS_TYPE_3AXIS_MAG);
|
||||
PIOS_HMC5x83_Register(internal_mag, PIOS_SENSORS_TYPE_3AXIS_MAG);
|
||||
}
|
||||
|
||||
# endif /* PIOS_INCLUDE_HMC5X83_INTERNAL */
|
||||
|
@ -602,75 +602,20 @@ static const struct flashfs_logfs_cfg flashfs_internal_user_cfg = {
|
||||
|
||||
#include <pios_usart_priv.h>
|
||||
|
||||
#ifdef PIOS_INCLUDE_COM_TELEM
|
||||
|
||||
/*
|
||||
* MAIN USART
|
||||
*/
|
||||
// Inverter for SBUS handling
|
||||
#define MAIN_USART_INVERTER_GPIO GPIOC
|
||||
#define MAIN_USART_INVERTER_PIN GPIO_Pin_0
|
||||
#define MAIN_USART_INVERTER_ENABLE Bit_SET
|
||||
#define MAIN_USART_INVERTER_DISABLE Bit_RESET
|
||||
|
||||
static int32_t PIOS_BOARD_USART_Ioctl(uint32_t usart_id, uint32_t ctl, void *param);
|
||||
|
||||
static const struct pios_usart_cfg pios_usart_main_cfg = {
|
||||
.regs = USART1,
|
||||
.remap = GPIO_AF_USART1,
|
||||
.init = {
|
||||
.USART_BaudRate = 57600,
|
||||
.USART_WordLength = USART_WordLength_8b,
|
||||
.USART_Parity = USART_Parity_No,
|
||||
.USART_StopBits = USART_StopBits_1,
|
||||
.USART_HardwareFlowControl = USART_HardwareFlowControl_None,
|
||||
.USART_Mode = USART_Mode_Rx | USART_Mode_Tx,
|
||||
},
|
||||
.irq = {
|
||||
.init = {
|
||||
.NVIC_IRQChannel = USART1_IRQn,
|
||||
.NVIC_IRQChannelPreemptionPriority = PIOS_IRQ_PRIO_MID,
|
||||
.NVIC_IRQChannelSubPriority = 0,
|
||||
.NVIC_IRQChannelCmd = ENABLE,
|
||||
},
|
||||
},
|
||||
.rx = {
|
||||
.gpio = GPIOA,
|
||||
.init = {
|
||||
.GPIO_Pin = GPIO_Pin_10,
|
||||
.GPIO_Speed = GPIO_Speed_2MHz,
|
||||
.GPIO_Mode = GPIO_Mode_AF,
|
||||
.GPIO_OType = GPIO_OType_PP,
|
||||
.GPIO_PuPd = GPIO_PuPd_UP
|
||||
},
|
||||
},
|
||||
.tx = {
|
||||
.gpio = GPIOA,
|
||||
.init = {
|
||||
.GPIO_Pin = GPIO_Pin_9,
|
||||
.GPIO_Speed = GPIO_Speed_2MHz,
|
||||
.GPIO_Mode = GPIO_Mode_AF,
|
||||
.GPIO_OType = GPIO_OType_PP,
|
||||
.GPIO_PuPd = GPIO_PuPd_UP
|
||||
},
|
||||
},
|
||||
};
|
||||
#endif /* PIOS_INCLUDE_COM_TELEM */
|
||||
|
||||
#ifdef PIOS_INCLUDE_DSM
|
||||
|
||||
#include "pios_dsm_priv.h"
|
||||
static const struct pios_usart_cfg pios_usart_dsm_main_cfg = {
|
||||
.regs = USART1,
|
||||
.remap = GPIO_AF_USART1,
|
||||
.init = {
|
||||
.USART_BaudRate = 115200,
|
||||
.USART_WordLength = USART_WordLength_8b,
|
||||
.USART_Parity = USART_Parity_No,
|
||||
.USART_StopBits = USART_StopBits_1,
|
||||
.USART_HardwareFlowControl = USART_HardwareFlowControl_None,
|
||||
.USART_Mode = USART_Mode_Rx,
|
||||
},
|
||||
.irq = {
|
||||
.init = {
|
||||
.NVIC_IRQChannel = USART1_IRQn,
|
||||
.NVIC_IRQChannelPreemptionPriority = PIOS_IRQ_PRIO_HIGH,
|
||||
.NVIC_IRQChannelSubPriority = 0,
|
||||
.NVIC_IRQChannelCmd = ENABLE,
|
||||
},
|
||||
},
|
||||
.rx = {
|
||||
.gpio = GPIOA,
|
||||
.init = {
|
||||
@ -691,120 +636,15 @@ static const struct pios_usart_cfg pios_usart_dsm_main_cfg = {
|
||||
.GPIO_PuPd = GPIO_PuPd_UP
|
||||
},
|
||||
},
|
||||
.ioctl = PIOS_BOARD_USART_Ioctl,
|
||||
};
|
||||
|
||||
// Because of the inverter on the main port this will not
|
||||
// work. Notice the mode is set to IN to maintain API
|
||||
// compatibility but protect the pins
|
||||
static const struct pios_dsm_cfg pios_dsm_main_cfg = {
|
||||
.bind = {
|
||||
.gpio = GPIOA,
|
||||
.init = {
|
||||
.GPIO_Pin = GPIO_Pin_10,
|
||||
.GPIO_Speed = GPIO_Speed_2MHz,
|
||||
.GPIO_Mode = GPIO_Mode_IN,
|
||||
.GPIO_OType = GPIO_OType_PP,
|
||||
.GPIO_PuPd = GPIO_PuPd_NOPULL
|
||||
},
|
||||
},
|
||||
};
|
||||
|
||||
#endif /* PIOS_INCLUDE_DSM */
|
||||
|
||||
#include <pios_sbus_priv.h>
|
||||
#if defined(PIOS_INCLUDE_SBUS)
|
||||
/*
|
||||
* S.Bus USART
|
||||
*/
|
||||
#include <pios_sbus_priv.h>
|
||||
|
||||
static const struct pios_usart_cfg pios_usart_sbus_main_cfg = {
|
||||
.regs = USART1,
|
||||
.remap = GPIO_AF_USART1,
|
||||
.init = {
|
||||
.USART_BaudRate = 100000,
|
||||
.USART_WordLength = USART_WordLength_8b,
|
||||
.USART_Parity = USART_Parity_Even,
|
||||
.USART_StopBits = USART_StopBits_2,
|
||||
.USART_HardwareFlowControl = USART_HardwareFlowControl_None,
|
||||
.USART_Mode = USART_Mode_Rx,
|
||||
},
|
||||
.irq = {
|
||||
.init = {
|
||||
.NVIC_IRQChannel = USART1_IRQn,
|
||||
.NVIC_IRQChannelPreemptionPriority = PIOS_IRQ_PRIO_HIGH,
|
||||
.NVIC_IRQChannelSubPriority = 0,
|
||||
.NVIC_IRQChannelCmd = ENABLE,
|
||||
},
|
||||
},
|
||||
.rx = {
|
||||
.gpio = GPIOA,
|
||||
.init = {
|
||||
.GPIO_Pin = GPIO_Pin_10,
|
||||
.GPIO_Speed = GPIO_Speed_2MHz,
|
||||
.GPIO_Mode = GPIO_Mode_AF,
|
||||
.GPIO_OType = GPIO_OType_PP,
|
||||
.GPIO_PuPd = GPIO_PuPd_UP
|
||||
},
|
||||
},
|
||||
.tx = {
|
||||
.gpio = GPIOA,
|
||||
.init = {
|
||||
.GPIO_Pin = GPIO_Pin_9,
|
||||
.GPIO_Speed = GPIO_Speed_2MHz,
|
||||
.GPIO_Mode = GPIO_Mode_OUT,
|
||||
.GPIO_OType = GPIO_OType_PP,
|
||||
.GPIO_PuPd = GPIO_PuPd_NOPULL
|
||||
},
|
||||
},
|
||||
};
|
||||
|
||||
#endif /* PIOS_INCLUDE_SBUS */
|
||||
|
||||
// Need this defined regardless to be able to turn it off
|
||||
static const struct pios_sbus_cfg pios_sbus_cfg = {
|
||||
/* Inverter configuration */
|
||||
.inv = {
|
||||
.gpio = GPIOC,
|
||||
.init = {
|
||||
.GPIO_Pin = GPIO_Pin_0,
|
||||
.GPIO_Speed = GPIO_Speed_2MHz,
|
||||
.GPIO_Mode = GPIO_Mode_OUT,
|
||||
.GPIO_OType = GPIO_OType_PP,
|
||||
.GPIO_PuPd = GPIO_PuPd_UP
|
||||
},
|
||||
},
|
||||
.gpio_inv_enable = Bit_SET,
|
||||
.gpio_inv_disable = Bit_RESET,
|
||||
.gpio_clk_func = RCC_AHB1PeriphClockCmd,
|
||||
.gpio_clk_periph = RCC_AHB1Periph_GPIOC,
|
||||
};
|
||||
|
||||
|
||||
#ifdef PIOS_INCLUDE_COM_FLEXI
|
||||
/*
|
||||
* FLEXI PORT
|
||||
*/
|
||||
static const struct pios_usart_cfg pios_usart_flexi_cfg = {
|
||||
.regs = USART3,
|
||||
.remap = GPIO_AF_USART3,
|
||||
.init = {
|
||||
.USART_BaudRate = 57600,
|
||||
.USART_WordLength = USART_WordLength_8b,
|
||||
.USART_Parity = USART_Parity_No,
|
||||
.USART_StopBits = USART_StopBits_1,
|
||||
.USART_HardwareFlowControl =
|
||||
USART_HardwareFlowControl_None,
|
||||
.USART_Mode = USART_Mode_Rx | USART_Mode_Tx,
|
||||
},
|
||||
.irq = {
|
||||
.init = {
|
||||
.NVIC_IRQChannel = USART3_IRQn,
|
||||
.NVIC_IRQChannelPreemptionPriority = PIOS_IRQ_PRIO_MID,
|
||||
.NVIC_IRQChannelSubPriority = 0,
|
||||
.NVIC_IRQChannelCmd = ENABLE,
|
||||
},
|
||||
},
|
||||
.rx = {
|
||||
.gpio = GPIOB,
|
||||
.init = {
|
||||
@ -827,172 +667,10 @@ static const struct pios_usart_cfg pios_usart_flexi_cfg = {
|
||||
},
|
||||
};
|
||||
|
||||
#endif /* PIOS_INCLUDE_COM_FLEXI */
|
||||
|
||||
#ifdef PIOS_INCLUDE_DSM
|
||||
|
||||
#include "pios_dsm_priv.h"
|
||||
static const struct pios_usart_cfg pios_usart_dsm_flexi_cfg = {
|
||||
.regs = USART3,
|
||||
.remap = GPIO_AF_USART3,
|
||||
.init = {
|
||||
.USART_BaudRate = 115200,
|
||||
.USART_WordLength = USART_WordLength_8b,
|
||||
.USART_Parity = USART_Parity_No,
|
||||
.USART_StopBits = USART_StopBits_1,
|
||||
.USART_HardwareFlowControl = USART_HardwareFlowControl_None,
|
||||
.USART_Mode = USART_Mode_Rx,
|
||||
},
|
||||
.irq = {
|
||||
.init = {
|
||||
.NVIC_IRQChannel = USART3_IRQn,
|
||||
.NVIC_IRQChannelPreemptionPriority = PIOS_IRQ_PRIO_HIGH,
|
||||
.NVIC_IRQChannelSubPriority = 0,
|
||||
.NVIC_IRQChannelCmd = ENABLE,
|
||||
},
|
||||
},
|
||||
.rx = {
|
||||
.gpio = GPIOB,
|
||||
.init = {
|
||||
.GPIO_Pin = GPIO_Pin_11,
|
||||
.GPIO_Speed = GPIO_Speed_2MHz,
|
||||
.GPIO_Mode = GPIO_Mode_AF,
|
||||
.GPIO_OType = GPIO_OType_PP,
|
||||
.GPIO_PuPd = GPIO_PuPd_UP
|
||||
},
|
||||
},
|
||||
.tx = {
|
||||
.gpio = GPIOB,
|
||||
.init = {
|
||||
.GPIO_Pin = GPIO_Pin_10,
|
||||
.GPIO_Speed = GPIO_Speed_2MHz,
|
||||
.GPIO_Mode = GPIO_Mode_AF,
|
||||
.GPIO_OType = GPIO_OType_PP,
|
||||
.GPIO_PuPd = GPIO_PuPd_UP
|
||||
},
|
||||
},
|
||||
};
|
||||
|
||||
static const struct pios_dsm_cfg pios_dsm_flexi_cfg = {
|
||||
.bind = {
|
||||
.gpio = GPIOB,
|
||||
.init = {
|
||||
.GPIO_Pin = GPIO_Pin_11,
|
||||
.GPIO_Speed = GPIO_Speed_2MHz,
|
||||
.GPIO_Mode = GPIO_Mode_OUT,
|
||||
.GPIO_OType = GPIO_OType_PP,
|
||||
.GPIO_PuPd = GPIO_PuPd_NOPULL
|
||||
},
|
||||
},
|
||||
};
|
||||
|
||||
#endif /* PIOS_INCLUDE_DSM */
|
||||
|
||||
/*
|
||||
* HK OSD
|
||||
*/
|
||||
static const struct pios_usart_cfg pios_usart_hkosd_main_cfg = {
|
||||
.regs = USART1,
|
||||
.remap = GPIO_AF_USART1,
|
||||
.init = {
|
||||
.USART_BaudRate = 57600,
|
||||
.USART_WordLength = USART_WordLength_8b,
|
||||
.USART_Parity = USART_Parity_No,
|
||||
.USART_StopBits = USART_StopBits_1,
|
||||
.USART_HardwareFlowControl = USART_HardwareFlowControl_None,
|
||||
.USART_Mode = USART_Mode_Rx | USART_Mode_Tx,
|
||||
},
|
||||
.irq = {
|
||||
.init = {
|
||||
.NVIC_IRQChannel = USART1_IRQn,
|
||||
.NVIC_IRQChannelPreemptionPriority = PIOS_IRQ_PRIO_MID,
|
||||
.NVIC_IRQChannelSubPriority = 0,
|
||||
.NVIC_IRQChannelCmd = ENABLE,
|
||||
},
|
||||
},
|
||||
.rx = {
|
||||
.gpio = GPIOA,
|
||||
.init = {
|
||||
.GPIO_Pin = GPIO_Pin_10,
|
||||
.GPIO_Speed = GPIO_Speed_2MHz,
|
||||
.GPIO_Mode = GPIO_Mode_AF,
|
||||
.GPIO_OType = GPIO_OType_PP,
|
||||
.GPIO_PuPd = GPIO_PuPd_UP
|
||||
},
|
||||
},
|
||||
.tx = {
|
||||
.gpio = GPIOA,
|
||||
.init = {
|
||||
.GPIO_Pin = GPIO_Pin_9,
|
||||
.GPIO_Speed = GPIO_Speed_2MHz,
|
||||
.GPIO_Mode = GPIO_Mode_AF,
|
||||
.GPIO_OType = GPIO_OType_PP,
|
||||
.GPIO_PuPd = GPIO_PuPd_UP
|
||||
},
|
||||
},
|
||||
};
|
||||
|
||||
static const struct pios_usart_cfg pios_usart_hkosd_flexi_cfg = {
|
||||
.regs = USART3,
|
||||
.remap = GPIO_AF_USART3,
|
||||
.init = {
|
||||
.USART_BaudRate = 57600,
|
||||
.USART_WordLength = USART_WordLength_8b,
|
||||
.USART_Parity = USART_Parity_No,
|
||||
.USART_StopBits = USART_StopBits_1,
|
||||
.USART_HardwareFlowControl = USART_HardwareFlowControl_None,
|
||||
.USART_Mode = USART_Mode_Rx | USART_Mode_Tx,
|
||||
},
|
||||
.irq = {
|
||||
.init = {
|
||||
.NVIC_IRQChannel = USART3_IRQn,
|
||||
.NVIC_IRQChannelPreemptionPriority = PIOS_IRQ_PRIO_MID,
|
||||
.NVIC_IRQChannelSubPriority = 0,
|
||||
.NVIC_IRQChannelCmd = ENABLE,
|
||||
},
|
||||
},
|
||||
.rx = {
|
||||
.gpio = GPIOB,
|
||||
.init = {
|
||||
.GPIO_Pin = GPIO_Pin_11,
|
||||
.GPIO_Speed = GPIO_Speed_2MHz,
|
||||
.GPIO_Mode = GPIO_Mode_AF,
|
||||
.GPIO_OType = GPIO_OType_PP,
|
||||
.GPIO_PuPd = GPIO_PuPd_UP
|
||||
},
|
||||
},
|
||||
.tx = {
|
||||
.gpio = GPIOB,
|
||||
.init = {
|
||||
.GPIO_Pin = GPIO_Pin_10,
|
||||
.GPIO_Speed = GPIO_Speed_2MHz,
|
||||
.GPIO_Mode = GPIO_Mode_AF,
|
||||
.GPIO_OType = GPIO_OType_PP,
|
||||
.GPIO_PuPd = GPIO_PuPd_UP
|
||||
},
|
||||
},
|
||||
};
|
||||
|
||||
static const struct pios_usart_cfg pios_usart_rcvrport_cfg = {
|
||||
static const struct pios_usart_cfg pios_usart_flexiio_cfg = {
|
||||
.regs = USART6,
|
||||
.remap = GPIO_AF_USART6,
|
||||
.init = {
|
||||
.USART_BaudRate = 57600,
|
||||
.USART_WordLength = USART_WordLength_8b,
|
||||
.USART_Parity = USART_Parity_No,
|
||||
.USART_StopBits = USART_StopBits_1,
|
||||
.USART_HardwareFlowControl = USART_HardwareFlowControl_None,
|
||||
.USART_Mode = USART_Mode_Rx | USART_Mode_Tx,
|
||||
},
|
||||
.irq = {
|
||||
.init = {
|
||||
.NVIC_IRQChannel = USART6_IRQn,
|
||||
.NVIC_IRQChannelPreemptionPriority = PIOS_IRQ_PRIO_MID,
|
||||
.NVIC_IRQChannelSubPriority = 0,
|
||||
.NVIC_IRQChannelCmd = ENABLE,
|
||||
},
|
||||
},
|
||||
|
||||
.dtr = {
|
||||
// FlexIO pin 9
|
||||
.gpio = GPIOC,
|
||||
@ -1385,212 +1063,24 @@ static const struct pios_tim_clock_cfg tim_12_cfg = {
|
||||
* Using TIM3, TIM9, TIM2, TIM5
|
||||
*/
|
||||
#include <pios_servo_priv.h>
|
||||
#include <pios_servo_config.h>
|
||||
|
||||
static const struct pios_tim_channel pios_tim_servoport_all_pins[] = {
|
||||
{
|
||||
.timer = TIM3,
|
||||
.timer_chan = TIM_Channel_3,
|
||||
.pin = {
|
||||
.gpio = GPIOB,
|
||||
.init = {
|
||||
.GPIO_Pin = GPIO_Pin_0,
|
||||
.GPIO_Speed = GPIO_Speed_2MHz,
|
||||
.GPIO_Mode = GPIO_Mode_AF,
|
||||
.GPIO_OType = GPIO_OType_PP,
|
||||
.GPIO_PuPd = GPIO_PuPd_UP
|
||||
},
|
||||
.pin_source = GPIO_PinSource0,
|
||||
},
|
||||
.remap = GPIO_AF_TIM3,
|
||||
},
|
||||
{
|
||||
.timer = TIM3,
|
||||
.timer_chan = TIM_Channel_4,
|
||||
.pin = {
|
||||
.gpio = GPIOB,
|
||||
.init = {
|
||||
.GPIO_Pin = GPIO_Pin_1,
|
||||
.GPIO_Speed = GPIO_Speed_2MHz,
|
||||
.GPIO_Mode = GPIO_Mode_AF,
|
||||
.GPIO_OType = GPIO_OType_PP,
|
||||
.GPIO_PuPd = GPIO_PuPd_UP
|
||||
},
|
||||
.pin_source = GPIO_PinSource1,
|
||||
},
|
||||
.remap = GPIO_AF_TIM3,
|
||||
},
|
||||
{
|
||||
.timer = TIM9,
|
||||
.timer_chan = TIM_Channel_2,
|
||||
.pin = {
|
||||
.gpio = GPIOA,
|
||||
.init = {
|
||||
.GPIO_Pin = GPIO_Pin_3,
|
||||
.GPIO_Speed = GPIO_Speed_2MHz,
|
||||
.GPIO_Mode = GPIO_Mode_AF,
|
||||
.GPIO_OType = GPIO_OType_PP,
|
||||
.GPIO_PuPd = GPIO_PuPd_UP
|
||||
},
|
||||
.pin_source = GPIO_PinSource3,
|
||||
},
|
||||
.remap = GPIO_AF_TIM9,
|
||||
},
|
||||
{
|
||||
.timer = TIM2,
|
||||
.timer_chan = TIM_Channel_3,
|
||||
.pin = {
|
||||
.gpio = GPIOA,
|
||||
.init = {
|
||||
.GPIO_Pin = GPIO_Pin_2,
|
||||
.GPIO_Speed = GPIO_Speed_2MHz,
|
||||
.GPIO_Mode = GPIO_Mode_AF,
|
||||
.GPIO_OType = GPIO_OType_PP,
|
||||
.GPIO_PuPd = GPIO_PuPd_UP
|
||||
},
|
||||
.pin_source = GPIO_PinSource2,
|
||||
},
|
||||
.remap = GPIO_AF_TIM2,
|
||||
},
|
||||
{
|
||||
.timer = TIM5,
|
||||
.timer_chan = TIM_Channel_2,
|
||||
.pin = {
|
||||
.gpio = GPIOA,
|
||||
.init = {
|
||||
.GPIO_Pin = GPIO_Pin_1,
|
||||
.GPIO_Speed = GPIO_Speed_2MHz,
|
||||
.GPIO_Mode = GPIO_Mode_AF,
|
||||
.GPIO_OType = GPIO_OType_PP,
|
||||
.GPIO_PuPd = GPIO_PuPd_UP
|
||||
},
|
||||
.pin_source = GPIO_PinSource1,
|
||||
},
|
||||
.remap = GPIO_AF_TIM5,
|
||||
},
|
||||
{
|
||||
.timer = TIM5,
|
||||
.timer_chan = TIM_Channel_1,
|
||||
.pin = {
|
||||
.gpio = GPIOA,
|
||||
.init = {
|
||||
.GPIO_Pin = GPIO_Pin_0,
|
||||
.GPIO_Speed = GPIO_Speed_2MHz,
|
||||
.GPIO_Mode = GPIO_Mode_AF,
|
||||
.GPIO_OType = GPIO_OType_PP,
|
||||
.GPIO_PuPd = GPIO_PuPd_UP
|
||||
},
|
||||
.pin_source = GPIO_PinSource0,
|
||||
},
|
||||
.remap = GPIO_AF_TIM5,
|
||||
},
|
||||
TIM_SERVO_CHANNEL_CONFIG(TIM3, 3, B, 0),
|
||||
TIM_SERVO_CHANNEL_CONFIG(TIM3, 4, B, 1),
|
||||
TIM_SERVO_CHANNEL_CONFIG(TIM9, 2, A, 3),
|
||||
TIM_SERVO_CHANNEL_CONFIG(TIM2, 3, A, 2),
|
||||
TIM_SERVO_CHANNEL_CONFIG(TIM5, 2, A, 1),
|
||||
TIM_SERVO_CHANNEL_CONFIG(TIM5, 1, A, 0),
|
||||
// PWM pins on FlexiIO(receiver) port
|
||||
{
|
||||
// * 6: PB15 = SPI2 MOSI, TIM12 CH2
|
||||
|
||||
.timer = TIM12,
|
||||
.timer_chan = TIM_Channel_2,
|
||||
.pin = {
|
||||
.gpio = GPIOB,
|
||||
.init = {
|
||||
.GPIO_Pin = GPIO_Pin_15,
|
||||
.GPIO_Speed = GPIO_Speed_2MHz,
|
||||
.GPIO_Mode = GPIO_Mode_AF,
|
||||
.GPIO_OType = GPIO_OType_PP,
|
||||
.GPIO_PuPd = GPIO_PuPd_UP
|
||||
},
|
||||
.pin_source = GPIO_PinSource15,
|
||||
},
|
||||
.remap = GPIO_AF_TIM12,
|
||||
},
|
||||
{
|
||||
// * 7: PC6 = TIM8 CH1, USART6 TX
|
||||
.timer = TIM8,
|
||||
.timer_chan = TIM_Channel_1,
|
||||
.pin = {
|
||||
.gpio = GPIOC,
|
||||
.init = {
|
||||
.GPIO_Pin = GPIO_Pin_6,
|
||||
.GPIO_Speed = GPIO_Speed_2MHz,
|
||||
.GPIO_Mode = GPIO_Mode_AF,
|
||||
.GPIO_OType = GPIO_OType_PP,
|
||||
.GPIO_PuPd = GPIO_PuPd_UP
|
||||
},
|
||||
.pin_source = GPIO_PinSource6,
|
||||
},
|
||||
.remap = GPIO_AF_TIM8,
|
||||
},
|
||||
|
||||
{
|
||||
// * 8: PC7 = TIM8 CH2, USART6 RX
|
||||
.timer = TIM8,
|
||||
.timer_chan = TIM_Channel_2,
|
||||
.pin = {
|
||||
.gpio = GPIOC,
|
||||
.init = {
|
||||
.GPIO_Pin = GPIO_Pin_7,
|
||||
.GPIO_Speed = GPIO_Speed_2MHz,
|
||||
.GPIO_Mode = GPIO_Mode_AF,
|
||||
.GPIO_OType = GPIO_OType_PP,
|
||||
.GPIO_PuPd = GPIO_PuPd_UP
|
||||
},
|
||||
.pin_source = GPIO_PinSource7,
|
||||
},
|
||||
.remap = GPIO_AF_TIM8,
|
||||
},
|
||||
|
||||
{
|
||||
// * 9: PC8 = TIM8 CH3
|
||||
.timer = TIM8,
|
||||
.timer_chan = TIM_Channel_3,
|
||||
.pin = {
|
||||
.gpio = GPIOC,
|
||||
.init = {
|
||||
.GPIO_Pin = GPIO_Pin_8,
|
||||
.GPIO_Speed = GPIO_Speed_2MHz,
|
||||
.GPIO_Mode = GPIO_Mode_AF,
|
||||
.GPIO_OType = GPIO_OType_PP,
|
||||
.GPIO_PuPd = GPIO_PuPd_UP
|
||||
},
|
||||
.pin_source = GPIO_PinSource8,
|
||||
},
|
||||
.remap = GPIO_AF_TIM8,
|
||||
},
|
||||
|
||||
{
|
||||
// * 10: PC9 = TIM8 CH4
|
||||
.timer = TIM8,
|
||||
.timer_chan = TIM_Channel_4,
|
||||
.pin = {
|
||||
.gpio = GPIOC,
|
||||
.init = {
|
||||
.GPIO_Pin = GPIO_Pin_9,
|
||||
.GPIO_Speed = GPIO_Speed_2MHz,
|
||||
.GPIO_Mode = GPIO_Mode_AF,
|
||||
.GPIO_OType = GPIO_OType_PP,
|
||||
.GPIO_PuPd = GPIO_PuPd_UP
|
||||
},
|
||||
.pin_source = GPIO_PinSource9,
|
||||
},
|
||||
.remap = GPIO_AF_TIM8,
|
||||
},
|
||||
|
||||
{
|
||||
// * 5: PB14 = SPI2 MISO, TIM12 CH1, USART3 RTS
|
||||
.timer = TIM12,
|
||||
.timer_chan = TIM_Channel_1,
|
||||
.pin = {
|
||||
.gpio = GPIOB,
|
||||
.init = {
|
||||
.GPIO_Pin = GPIO_Pin_14,
|
||||
.GPIO_Speed = GPIO_Speed_2MHz,
|
||||
.GPIO_Mode = GPIO_Mode_AF,
|
||||
.GPIO_OType = GPIO_OType_PP,
|
||||
.GPIO_PuPd = GPIO_PuPd_UP
|
||||
},
|
||||
.pin_source = GPIO_PinSource14,
|
||||
},
|
||||
.remap = GPIO_AF_TIM12,
|
||||
},
|
||||
TIM_SERVO_CHANNEL_CONFIG(TIM12, 2, B, 15), // * 6: PB15 = SPI2 MOSI, TIM12 CH2
|
||||
TIM_SERVO_CHANNEL_CONFIG(TIM8, 1, C, 6), // * 7: PC6 = TIM8 CH1, USART6 TX
|
||||
TIM_SERVO_CHANNEL_CONFIG(TIM8, 2, C, 7), // * 8: PC7 = TIM8 CH2, USART6 RX
|
||||
TIM_SERVO_CHANNEL_CONFIG(TIM8, 3, C, 8), // * 9: PC8 = TIM8 CH3
|
||||
TIM_SERVO_CHANNEL_CONFIG(TIM8, 4, C, 9), // * 10: PC9 = TIM8 CH4
|
||||
TIM_SERVO_CHANNEL_CONFIG(TIM12, 1, B, 14), // * 5: PB14 = SPI2 MISO, TIM12 CH1, USART3 RTS
|
||||
};
|
||||
|
||||
#define PIOS_SERVOPORT_ALL_PINS_PWMOUT 6
|
||||
#define PIOS_SERVOPORT_ALL_PINS_PWMOUT_IN_PPM 11
|
||||
#define PIOS_SERVOPORT_ALL_PINS_PWMOUT_IN 12
|
||||
@ -1648,102 +1138,12 @@ const struct pios_servo_cfg pios_servo_cfg_out_in = {
|
||||
#if defined(PIOS_INCLUDE_PWM) || defined(PIOS_INCLUDE_PPM)
|
||||
#include <pios_pwm_priv.h>
|
||||
static const struct pios_tim_channel pios_tim_rcvrport_all_channels[] = {
|
||||
{
|
||||
.timer = TIM12,
|
||||
.timer_chan = TIM_Channel_1,
|
||||
.pin = {
|
||||
.gpio = GPIOB,
|
||||
.init = {
|
||||
.GPIO_Pin = GPIO_Pin_14,
|
||||
.GPIO_Speed = GPIO_Speed_2MHz,
|
||||
.GPIO_Mode = GPIO_Mode_AF,
|
||||
.GPIO_OType = GPIO_OType_PP,
|
||||
.GPIO_PuPd = GPIO_PuPd_UP
|
||||
},
|
||||
.pin_source = GPIO_PinSource14,
|
||||
},
|
||||
.remap = GPIO_AF_TIM12,
|
||||
},
|
||||
{
|
||||
.timer = TIM12,
|
||||
.timer_chan = TIM_Channel_2,
|
||||
.pin = {
|
||||
.gpio = GPIOB,
|
||||
.init = {
|
||||
.GPIO_Pin = GPIO_Pin_15,
|
||||
.GPIO_Speed = GPIO_Speed_2MHz,
|
||||
.GPIO_Mode = GPIO_Mode_AF,
|
||||
.GPIO_OType = GPIO_OType_PP,
|
||||
.GPIO_PuPd = GPIO_PuPd_UP
|
||||
},
|
||||
.pin_source = GPIO_PinSource15,
|
||||
},
|
||||
.remap = GPIO_AF_TIM12,
|
||||
},
|
||||
{
|
||||
.timer = TIM8,
|
||||
.timer_chan = TIM_Channel_1,
|
||||
.pin = {
|
||||
.gpio = GPIOC,
|
||||
.init = {
|
||||
.GPIO_Pin = GPIO_Pin_6,
|
||||
.GPIO_Speed = GPIO_Speed_2MHz,
|
||||
.GPIO_Mode = GPIO_Mode_AF,
|
||||
.GPIO_OType = GPIO_OType_PP,
|
||||
.GPIO_PuPd = GPIO_PuPd_UP
|
||||
},
|
||||
.pin_source = GPIO_PinSource6,
|
||||
},
|
||||
.remap = GPIO_AF_TIM8,
|
||||
},
|
||||
{
|
||||
.timer = TIM8,
|
||||
.timer_chan = TIM_Channel_2,
|
||||
.pin = {
|
||||
.gpio = GPIOC,
|
||||
.init = {
|
||||
.GPIO_Pin = GPIO_Pin_7,
|
||||
.GPIO_Speed = GPIO_Speed_2MHz,
|
||||
.GPIO_Mode = GPIO_Mode_AF,
|
||||
.GPIO_OType = GPIO_OType_PP,
|
||||
.GPIO_PuPd = GPIO_PuPd_UP
|
||||
},
|
||||
.pin_source = GPIO_PinSource7,
|
||||
},
|
||||
.remap = GPIO_AF_TIM8,
|
||||
},
|
||||
{
|
||||
.timer = TIM8,
|
||||
.timer_chan = TIM_Channel_3,
|
||||
.pin = {
|
||||
.gpio = GPIOC,
|
||||
.init = {
|
||||
.GPIO_Pin = GPIO_Pin_8,
|
||||
.GPIO_Speed = GPIO_Speed_2MHz,
|
||||
.GPIO_Mode = GPIO_Mode_AF,
|
||||
.GPIO_OType = GPIO_OType_PP,
|
||||
.GPIO_PuPd = GPIO_PuPd_UP
|
||||
},
|
||||
.pin_source = GPIO_PinSource8,
|
||||
},
|
||||
.remap = GPIO_AF_TIM8,
|
||||
},
|
||||
{
|
||||
.timer = TIM8,
|
||||
.timer_chan = TIM_Channel_4,
|
||||
.pin = {
|
||||
.gpio = GPIOC,
|
||||
.init = {
|
||||
.GPIO_Pin = GPIO_Pin_9,
|
||||
.GPIO_Speed = GPIO_Speed_2MHz,
|
||||
.GPIO_Mode = GPIO_Mode_AF,
|
||||
.GPIO_OType = GPIO_OType_PP,
|
||||
.GPIO_PuPd = GPIO_PuPd_UP
|
||||
},
|
||||
.pin_source = GPIO_PinSource9,
|
||||
},
|
||||
.remap = GPIO_AF_TIM8,
|
||||
},
|
||||
TIM_SERVO_CHANNEL_CONFIG(TIM12, 1, B, 14),
|
||||
TIM_SERVO_CHANNEL_CONFIG(TIM12, 2, B, 15),
|
||||
TIM_SERVO_CHANNEL_CONFIG(TIM8, 1, C, 6),
|
||||
TIM_SERVO_CHANNEL_CONFIG(TIM8, 2, C, 7),
|
||||
TIM_SERVO_CHANNEL_CONFIG(TIM8, 3, C, 8),
|
||||
TIM_SERVO_CHANNEL_CONFIG(TIM8, 4, C, 9),
|
||||
};
|
||||
|
||||
const struct pios_pwm_cfg pios_pwm_cfg = {
|
||||
@ -1840,36 +1240,6 @@ const struct pios_usb_cfg *PIOS_BOARD_HW_DEFS_GetUsbCfg(__attribute__((unused))
|
||||
|
||||
#endif /* PIOS_INCLUDE_COM_MSG */
|
||||
|
||||
#if defined(PIOS_INCLUDE_USB_HID) && !defined(PIOS_INCLUDE_USB_CDC)
|
||||
#include <pios_usb_hid_priv.h>
|
||||
|
||||
const struct pios_usb_hid_cfg pios_usb_hid_cfg = {
|
||||
.data_if = 0,
|
||||
.data_rx_ep = 1,
|
||||
.data_tx_ep = 1,
|
||||
};
|
||||
#endif /* PIOS_INCLUDE_USB_HID && !PIOS_INCLUDE_USB_CDC */
|
||||
|
||||
#if defined(PIOS_INCLUDE_USB_HID) && defined(PIOS_INCLUDE_USB_CDC)
|
||||
#include <pios_usb_cdc_priv.h>
|
||||
|
||||
const struct pios_usb_cdc_cfg pios_usb_cdc_cfg = {
|
||||
.ctrl_if = 0,
|
||||
.ctrl_tx_ep = 2,
|
||||
|
||||
.data_if = 1,
|
||||
.data_rx_ep = 3,
|
||||
.data_tx_ep = 3,
|
||||
};
|
||||
|
||||
#include <pios_usb_hid_priv.h>
|
||||
|
||||
const struct pios_usb_hid_cfg pios_usb_hid_cfg = {
|
||||
.data_if = 2,
|
||||
.data_rx_ep = 1,
|
||||
.data_tx_ep = 1,
|
||||
};
|
||||
#endif /* PIOS_INCLUDE_USB_HID && PIOS_INCLUDE_USB_CDC */
|
||||
#ifdef PIOS_INCLUDE_WS2811
|
||||
#include <pios_ws2811_cfg.h>
|
||||
#define PIOS_WS2811_TIM_DIVIDER (PIOS_PERIPHERAL_APB2_CLOCK / (800000 * PIOS_WS2811_TIM_PERIOD))
|
||||
@ -1936,3 +1306,196 @@ void PIOS_WS2811_irq_handler(void)
|
||||
PIOS_WS2811_DMA_irq_handler();
|
||||
}
|
||||
#endif // PIOS_INCLUDE_WS2811
|
||||
|
||||
/**
|
||||
* Sensor configurations
|
||||
*/
|
||||
|
||||
#if defined(PIOS_INCLUDE_ADC)
|
||||
#include "pios_adc_priv.h"
|
||||
void PIOS_ADC_DMC_irq_handler(void);
|
||||
void DMA2_Stream4_IRQHandler(void) __attribute__((alias("PIOS_ADC_DMC_irq_handler")));
|
||||
struct pios_adc_cfg pios_adc_cfg = {
|
||||
.adc_dev = ADC1,
|
||||
.dma = {
|
||||
.irq = {
|
||||
.flags = (DMA_FLAG_TCIF4 | DMA_FLAG_TEIF4 | DMA_FLAG_HTIF4),
|
||||
.init = {
|
||||
.NVIC_IRQChannel = DMA2_Stream4_IRQn,
|
||||
.NVIC_IRQChannelPreemptionPriority = PIOS_IRQ_PRIO_LOW,
|
||||
.NVIC_IRQChannelSubPriority = 0,
|
||||
.NVIC_IRQChannelCmd = ENABLE,
|
||||
},
|
||||
},
|
||||
.rx = {
|
||||
.channel = DMA2_Stream4,
|
||||
.init = {
|
||||
.DMA_Channel = DMA_Channel_0,
|
||||
.DMA_PeripheralBaseAddr = (uint32_t)&ADC1->DR
|
||||
},
|
||||
}
|
||||
},
|
||||
.half_flag = DMA_IT_HTIF4,
|
||||
.full_flag = DMA_IT_TCIF4,
|
||||
};
|
||||
void PIOS_ADC_DMC_irq_handler(void)
|
||||
{
|
||||
/* Call into the generic code to handle the IRQ for this specific device */
|
||||
PIOS_ADC_DMA_Handler();
|
||||
}
|
||||
|
||||
const struct pios_adc_cfg *PIOS_BOARD_HW_DEFS_GetAdcCfg(__attribute__((unused)) uint32_t board_revision)
|
||||
{
|
||||
return &pios_adc_cfg;
|
||||
}
|
||||
#endif /* if defined(PIOS_INCLUDE_ADC) */
|
||||
|
||||
#if defined(PIOS_INCLUDE_HMC5X83)
|
||||
#include "pios_hmc5x83.h"
|
||||
|
||||
#ifdef PIOS_HMC5X83_HAS_GPIOS
|
||||
bool pios_board_internal_mag_handler()
|
||||
{
|
||||
return PIOS_HMC5x83_IRQHandler(pios_hmc5x83_internal_id);
|
||||
}
|
||||
|
||||
static const struct pios_exti_cfg pios_exti_hmc5x83_cfg __exti_config = {
|
||||
.vector = pios_board_internal_mag_handler,
|
||||
.line = EXTI_Line7,
|
||||
.pin = {
|
||||
.gpio = GPIOB,
|
||||
.init = {
|
||||
.GPIO_Pin = GPIO_Pin_7,
|
||||
.GPIO_Speed = GPIO_Speed_100MHz,
|
||||
.GPIO_Mode = GPIO_Mode_IN,
|
||||
.GPIO_OType = GPIO_OType_OD,
|
||||
.GPIO_PuPd = GPIO_PuPd_NOPULL,
|
||||
},
|
||||
},
|
||||
.irq = {
|
||||
.init = {
|
||||
.NVIC_IRQChannel = EXTI9_5_IRQn,
|
||||
.NVIC_IRQChannelPreemptionPriority = PIOS_IRQ_PRIO_LOW,
|
||||
.NVIC_IRQChannelSubPriority = 0,
|
||||
.NVIC_IRQChannelCmd = ENABLE,
|
||||
},
|
||||
},
|
||||
.exti = {
|
||||
.init = {
|
||||
.EXTI_Line = EXTI_Line7, // matches above GPIO pin
|
||||
.EXTI_Mode = EXTI_Mode_Interrupt,
|
||||
.EXTI_Trigger = EXTI_Trigger_Rising,
|
||||
.EXTI_LineCmd = ENABLE,
|
||||
},
|
||||
},
|
||||
};
|
||||
#endif /* PIOS_HMC5X83_HAS_GPIOS */
|
||||
|
||||
static const struct pios_hmc5x83_cfg pios_hmc5x83_internal_cfg = {
|
||||
#ifdef PIOS_HMC5X83_HAS_GPIOS
|
||||
.exti_cfg = &pios_exti_hmc5x83_cfg,
|
||||
#endif
|
||||
.M_ODR = PIOS_HMC5x83_ODR_75,
|
||||
.Meas_Conf = PIOS_HMC5x83_MEASCONF_NORMAL,
|
||||
.Gain = PIOS_HMC5x83_GAIN_1_9,
|
||||
.Mode = PIOS_HMC5x83_MODE_CONTINUOUS,
|
||||
.TempCompensation = false,
|
||||
.Driver = &PIOS_HMC5x83_I2C_DRIVER,
|
||||
.Orientation = PIOS_HMC5X83_ORIENTATION_EAST_NORTH_UP,
|
||||
};
|
||||
|
||||
static const struct pios_hmc5x83_cfg pios_hmc5x83_external_cfg = {
|
||||
#ifdef PIOS_HMC5X83_HAS_GPIOS
|
||||
.exti_cfg = NULL,
|
||||
#endif
|
||||
.M_ODR = PIOS_HMC5x83_ODR_75, // if you change this for auxmag, change AUX_MAG_SKIP in sensors.c
|
||||
.Meas_Conf = PIOS_HMC5x83_MEASCONF_NORMAL,
|
||||
.Gain = PIOS_HMC5x83_GAIN_1_9,
|
||||
.Mode = PIOS_HMC5x83_MODE_CONTINUOUS,
|
||||
.TempCompensation = false,
|
||||
.Driver = &PIOS_HMC5x83_I2C_DRIVER,
|
||||
.Orientation = PIOS_HMC5X83_ORIENTATION_EAST_NORTH_UP, // ENU for GPSV9, WND for typical I2C mag
|
||||
};
|
||||
|
||||
const struct pios_hmc5x83_cfg *PIOS_BOARD_HW_DEFS_GetInternalHMC5x83Cfg(__attribute__((unused)) uint32_t board_revision)
|
||||
{
|
||||
return &pios_hmc5x83_internal_cfg;
|
||||
}
|
||||
|
||||
const struct pios_hmc5x83_cfg *PIOS_BOARD_HW_DEFS_GetExternalHMC5x83Cfg(__attribute__((unused)) uint32_t board_revision)
|
||||
{
|
||||
return &pios_hmc5x83_external_cfg;
|
||||
}
|
||||
#endif /* PIOS_INCLUDE_HMC5X83 */
|
||||
|
||||
/**
|
||||
* Configuration for the MS5611 chip
|
||||
*/
|
||||
#if defined(PIOS_INCLUDE_MS5611)
|
||||
#include "pios_ms5611.h"
|
||||
static const struct pios_ms5611_cfg pios_ms5611_cfg = {
|
||||
.oversampling = MS5611_OSR_512,
|
||||
};
|
||||
const struct pios_ms5611_cfg *PIOS_BOARD_HW_DEFS_GetMS5611Cfg(__attribute__((unused)) uint32_t board_revision)
|
||||
{
|
||||
return &pios_ms5611_cfg;
|
||||
}
|
||||
#endif /* PIOS_INCLUDE_MS5611 */
|
||||
|
||||
|
||||
/**
|
||||
* Configuration for the MPU6000 chip
|
||||
*/
|
||||
#if defined(PIOS_INCLUDE_MPU6000)
|
||||
#include "pios_mpu6000.h"
|
||||
#include "pios_mpu6000_config.h"
|
||||
static const struct pios_exti_cfg pios_exti_mpu6000_cfg __exti_config = {
|
||||
.vector = PIOS_MPU6000_IRQHandler,
|
||||
.line = EXTI_Line4,
|
||||
.pin = {
|
||||
.gpio = GPIOC,
|
||||
.init = {
|
||||
.GPIO_Pin = GPIO_Pin_4,
|
||||
.GPIO_Speed = GPIO_Speed_100MHz,
|
||||
.GPIO_Mode = GPIO_Mode_IN,
|
||||
.GPIO_OType = GPIO_OType_OD,
|
||||
.GPIO_PuPd = GPIO_PuPd_NOPULL,
|
||||
},
|
||||
},
|
||||
.irq = {
|
||||
.init = {
|
||||
.NVIC_IRQChannel = EXTI4_IRQn,
|
||||
.NVIC_IRQChannelPreemptionPriority = PIOS_IRQ_PRIO_HIGH,
|
||||
.NVIC_IRQChannelSubPriority = 0,
|
||||
.NVIC_IRQChannelCmd = ENABLE,
|
||||
},
|
||||
},
|
||||
.exti = {
|
||||
.init = {
|
||||
.EXTI_Line = EXTI_Line4, // matches above GPIO pin
|
||||
.EXTI_Mode = EXTI_Mode_Interrupt,
|
||||
.EXTI_Trigger = EXTI_Trigger_Rising,
|
||||
.EXTI_LineCmd = ENABLE,
|
||||
},
|
||||
},
|
||||
};
|
||||
|
||||
static const struct pios_mpu6000_cfg pios_mpu6000_cfg = {
|
||||
.exti_cfg = &pios_exti_mpu6000_cfg,
|
||||
.Fifo_store = PIOS_MPU6000_FIFO_TEMP_OUT | PIOS_MPU6000_FIFO_GYRO_X_OUT | PIOS_MPU6000_FIFO_GYRO_Y_OUT | PIOS_MPU6000_FIFO_GYRO_Z_OUT,
|
||||
// Clock at 8 khz, downsampled by 12 for 666Hz
|
||||
.Smpl_rate_div_no_dlp = 11,
|
||||
// with dlp on output rate is 500Hz
|
||||
.Smpl_rate_div_dlp = 1,
|
||||
.interrupt_cfg = PIOS_MPU6000_INT_CLR_ANYRD,
|
||||
.interrupt_en = PIOS_MPU6000_INTEN_DATA_RDY,
|
||||
.User_ctl = PIOS_MPU6000_USERCTL_FIFO_EN | PIOS_MPU6000_USERCTL_DIS_I2C,
|
||||
.Pwr_mgmt_clk = PIOS_MPU6000_PWRMGMT_PLL_X_CLK,
|
||||
.accel_range = PIOS_MPU6000_ACCEL_8G,
|
||||
.gyro_range = PIOS_MPU6000_SCALE_2000_DEG,
|
||||
.filter = PIOS_MPU6000_LOWPASS_256_HZ,
|
||||
.orientation = PIOS_MPU6000_TOP_180DEG
|
||||
};
|
||||
#endif /* PIOS_INCLUDE_MPU6000 */
|
||||
|
||||
|
||||
|
@ -25,7 +25,7 @@
|
||||
|
||||
#include <pios.h>
|
||||
#include <pios_board_info.h>
|
||||
|
||||
#include <pios_board_io.h>
|
||||
/*
|
||||
* Pull in the board-specific static HW definitions.
|
||||
* Including .c files is a bit ugly but this allows all of
|
||||
@ -39,6 +39,12 @@
|
||||
uint32_t pios_com_telem_usb_id;
|
||||
|
||||
static bool board_init_complete = false;
|
||||
|
||||
static int32_t PIOS_BOARD_USART_Ioctl(__attribute__((unused)) uint32_t usart_id, __attribute__((unused)) uint32_t ctl, __attribute__((unused)) void *param)
|
||||
{
|
||||
return -1;
|
||||
}
|
||||
|
||||
void PIOS_Board_Init()
|
||||
{
|
||||
if (board_init_complete) {
|
||||
@ -68,7 +74,7 @@ void PIOS_Board_Init()
|
||||
|
||||
#if defined(PIOS_INCLUDE_USB_HID) && defined(PIOS_INCLUDE_COM_MSG)
|
||||
uint32_t pios_usb_hid_id;
|
||||
if (PIOS_USB_HID_Init(&pios_usb_hid_id, &pios_usb_hid_cfg, pios_usb_id)) {
|
||||
if (PIOS_USB_HID_Init(&pios_usb_hid_id, &pios_usb_hid_only_cfg, pios_usb_id)) {
|
||||
PIOS_Assert(0);
|
||||
}
|
||||
if (PIOS_COM_MSG_Init(&pios_com_telem_usb_id, &pios_usb_hid_com_driver, pios_usb_hid_id)) {
|
||||
|
@ -30,19 +30,16 @@
|
||||
#include <pios_board_info.h>
|
||||
#include <uavobjectsinit.h>
|
||||
#include <hwsettings.h>
|
||||
#include <manualcontrolsettings.h>
|
||||
#include <oplinksettings.h>
|
||||
#include <oplinkstatus.h>
|
||||
#include <oplinkreceiver.h>
|
||||
#include <pios_oplinkrcvr_priv.h>
|
||||
#include <taskinfo.h>
|
||||
#include <pios_callbackscheduler.h>
|
||||
#include <auxmagsettings.h>
|
||||
#include <pios_ws2811.h>
|
||||
|
||||
|
||||
#ifdef PIOS_INCLUDE_INSTRUMENTATION
|
||||
#include <pios_instrumentation.h>
|
||||
#endif
|
||||
|
||||
#include <pios_board_io.h>
|
||||
|
||||
/*
|
||||
* Pull in the board-specific static HW definitions.
|
||||
* Including .c files is a bit ugly but this allows all of
|
||||
@ -53,312 +50,72 @@
|
||||
*/
|
||||
#include "../board_hw_defs.c"
|
||||
|
||||
/**
|
||||
* Sensor configurations
|
||||
*/
|
||||
|
||||
#if defined(PIOS_INCLUDE_ADC)
|
||||
#include "pios_adc_priv.h"
|
||||
void PIOS_ADC_DMC_irq_handler(void);
|
||||
void DMA2_Stream4_IRQHandler(void) __attribute__((alias("PIOS_ADC_DMC_irq_handler")));
|
||||
struct pios_adc_cfg pios_adc_cfg = {
|
||||
.adc_dev = ADC1,
|
||||
.dma = {
|
||||
.irq = {
|
||||
.flags = (DMA_FLAG_TCIF4 | DMA_FLAG_TEIF4 | DMA_FLAG_HTIF4),
|
||||
.init = {
|
||||
.NVIC_IRQChannel = DMA2_Stream4_IRQn,
|
||||
.NVIC_IRQChannelPreemptionPriority = PIOS_IRQ_PRIO_LOW,
|
||||
.NVIC_IRQChannelSubPriority = 0,
|
||||
.NVIC_IRQChannelCmd = ENABLE,
|
||||
},
|
||||
},
|
||||
.rx = {
|
||||
.channel = DMA2_Stream4,
|
||||
.init = {
|
||||
.DMA_Channel = DMA_Channel_0,
|
||||
.DMA_PeripheralBaseAddr = (uint32_t)&ADC1->DR
|
||||
},
|
||||
}
|
||||
},
|
||||
.half_flag = DMA_IT_HTIF4,
|
||||
.full_flag = DMA_IT_TCIF4,
|
||||
};
|
||||
void PIOS_ADC_DMC_irq_handler(void)
|
||||
{
|
||||
/* Call into the generic code to handle the IRQ for this specific device */
|
||||
PIOS_ADC_DMA_Handler();
|
||||
}
|
||||
|
||||
#endif /* if defined(PIOS_INCLUDE_ADC) */
|
||||
|
||||
#if defined(PIOS_INCLUDE_HMC5X83)
|
||||
#include "pios_hmc5x83.h"
|
||||
pios_hmc5x83_dev_t onboard_mag = 0;
|
||||
pios_hmc5x83_dev_t external_mag = 0;
|
||||
|
||||
bool pios_board_internal_mag_handler()
|
||||
{
|
||||
return PIOS_HMC5x83_IRQHandler(onboard_mag);
|
||||
}
|
||||
|
||||
static const struct pios_exti_cfg pios_exti_hmc5x83_cfg __exti_config = {
|
||||
.vector = pios_board_internal_mag_handler,
|
||||
.line = EXTI_Line7,
|
||||
.pin = {
|
||||
.gpio = GPIOB,
|
||||
.init = {
|
||||
.GPIO_Pin = GPIO_Pin_7,
|
||||
.GPIO_Speed = GPIO_Speed_100MHz,
|
||||
.GPIO_Mode = GPIO_Mode_IN,
|
||||
.GPIO_OType = GPIO_OType_OD,
|
||||
.GPIO_PuPd = GPIO_PuPd_NOPULL,
|
||||
},
|
||||
},
|
||||
.irq = {
|
||||
.init = {
|
||||
.NVIC_IRQChannel = EXTI9_5_IRQn,
|
||||
.NVIC_IRQChannelPreemptionPriority = PIOS_IRQ_PRIO_LOW,
|
||||
.NVIC_IRQChannelSubPriority = 0,
|
||||
.NVIC_IRQChannelCmd = ENABLE,
|
||||
},
|
||||
},
|
||||
.exti = {
|
||||
.init = {
|
||||
.EXTI_Line = EXTI_Line7, // matches above GPIO pin
|
||||
.EXTI_Mode = EXTI_Mode_Interrupt,
|
||||
.EXTI_Trigger = EXTI_Trigger_Rising,
|
||||
.EXTI_LineCmd = ENABLE,
|
||||
},
|
||||
},
|
||||
};
|
||||
|
||||
static const struct pios_hmc5x83_cfg pios_hmc5x83_internal_cfg = {
|
||||
#ifdef PIOS_HMC5X83_HAS_GPIOS
|
||||
.exti_cfg = &pios_exti_hmc5x83_cfg,
|
||||
#endif
|
||||
.M_ODR = PIOS_HMC5x83_ODR_75,
|
||||
.Meas_Conf = PIOS_HMC5x83_MEASCONF_NORMAL,
|
||||
.Gain = PIOS_HMC5x83_GAIN_1_9,
|
||||
.Mode = PIOS_HMC5x83_MODE_CONTINUOUS,
|
||||
.TempCompensation = false,
|
||||
.Driver = &PIOS_HMC5x83_I2C_DRIVER,
|
||||
.Orientation = PIOS_HMC5X83_ORIENTATION_EAST_NORTH_UP,
|
||||
};
|
||||
|
||||
static const struct pios_hmc5x83_cfg pios_hmc5x83_external_cfg = {
|
||||
#ifdef PIOS_HMC5X83_HAS_GPIOS
|
||||
.exti_cfg = NULL,
|
||||
#endif
|
||||
.M_ODR = PIOS_HMC5x83_ODR_75, // if you change this for auxmag, change AUX_MAG_SKIP in sensors.c
|
||||
.Meas_Conf = PIOS_HMC5x83_MEASCONF_NORMAL,
|
||||
.Gain = PIOS_HMC5x83_GAIN_1_9,
|
||||
.Mode = PIOS_HMC5x83_MODE_CONTINUOUS,
|
||||
.TempCompensation = false,
|
||||
.Driver = &PIOS_HMC5x83_I2C_DRIVER,
|
||||
.Orientation = PIOS_HMC5X83_ORIENTATION_EAST_NORTH_UP, // ENU for GPSV9, WND for typical I2C mag
|
||||
};
|
||||
#endif /* PIOS_INCLUDE_HMC5X83 */
|
||||
|
||||
/**
|
||||
* Configuration for the MS5611 chip
|
||||
*/
|
||||
#if defined(PIOS_INCLUDE_MS5611)
|
||||
#include "pios_ms5611.h"
|
||||
static const struct pios_ms5611_cfg pios_ms5611_cfg = {
|
||||
.oversampling = MS5611_OSR_512,
|
||||
};
|
||||
#endif /* PIOS_INCLUDE_MS5611 */
|
||||
|
||||
|
||||
/**
|
||||
* Configuration for the MPU6000 chip
|
||||
*/
|
||||
#if defined(PIOS_INCLUDE_MPU6000)
|
||||
#include "pios_mpu6000.h"
|
||||
#include "pios_mpu6000_config.h"
|
||||
static const struct pios_exti_cfg pios_exti_mpu6000_cfg __exti_config = {
|
||||
.vector = PIOS_MPU6000_IRQHandler,
|
||||
.line = EXTI_Line4,
|
||||
.pin = {
|
||||
.gpio = GPIOC,
|
||||
.init = {
|
||||
.GPIO_Pin = GPIO_Pin_4,
|
||||
.GPIO_Speed = GPIO_Speed_100MHz,
|
||||
.GPIO_Mode = GPIO_Mode_IN,
|
||||
.GPIO_OType = GPIO_OType_OD,
|
||||
.GPIO_PuPd = GPIO_PuPd_NOPULL,
|
||||
},
|
||||
},
|
||||
.irq = {
|
||||
.init = {
|
||||
.NVIC_IRQChannel = EXTI4_IRQn,
|
||||
.NVIC_IRQChannelPreemptionPriority = PIOS_IRQ_PRIO_HIGH,
|
||||
.NVIC_IRQChannelSubPriority = 0,
|
||||
.NVIC_IRQChannelCmd = ENABLE,
|
||||
},
|
||||
},
|
||||
.exti = {
|
||||
.init = {
|
||||
.EXTI_Line = EXTI_Line4, // matches above GPIO pin
|
||||
.EXTI_Mode = EXTI_Mode_Interrupt,
|
||||
.EXTI_Trigger = EXTI_Trigger_Rising,
|
||||
.EXTI_LineCmd = ENABLE,
|
||||
},
|
||||
},
|
||||
};
|
||||
|
||||
static const struct pios_mpu6000_cfg pios_mpu6000_cfg = {
|
||||
.exti_cfg = &pios_exti_mpu6000_cfg,
|
||||
.Fifo_store = PIOS_MPU6000_FIFO_TEMP_OUT | PIOS_MPU6000_FIFO_GYRO_X_OUT | PIOS_MPU6000_FIFO_GYRO_Y_OUT | PIOS_MPU6000_FIFO_GYRO_Z_OUT,
|
||||
// Clock at 8 khz, downsampled by 12 for 666Hz
|
||||
.Smpl_rate_div_no_dlp = 11,
|
||||
// with dlp on output rate is 500Hz
|
||||
.Smpl_rate_div_dlp = 1,
|
||||
.interrupt_cfg = PIOS_MPU6000_INT_CLR_ANYRD,
|
||||
.interrupt_en = PIOS_MPU6000_INTEN_DATA_RDY,
|
||||
.User_ctl = PIOS_MPU6000_USERCTL_FIFO_EN | PIOS_MPU6000_USERCTL_DIS_I2C,
|
||||
.Pwr_mgmt_clk = PIOS_MPU6000_PWRMGMT_PLL_X_CLK,
|
||||
.accel_range = PIOS_MPU6000_ACCEL_8G,
|
||||
.gyro_range = PIOS_MPU6000_SCALE_2000_DEG,
|
||||
.filter = PIOS_MPU6000_LOWPASS_256_HZ,
|
||||
.orientation = PIOS_MPU6000_TOP_180DEG
|
||||
};
|
||||
#endif /* PIOS_INCLUDE_MPU6000 */
|
||||
|
||||
/* One slot per selectable receiver group.
|
||||
* eg. PWM, PPM, GCS, SPEKTRUM1, SPEKTRUM2, SBUS
|
||||
* NOTE: No slot in this map for NONE.
|
||||
*/
|
||||
uint32_t pios_rcvr_group_map[MANUALCONTROLSETTINGS_CHANNELGROUPS_NONE];
|
||||
|
||||
#define PIOS_COM_TELEM_RF_RX_BUF_LEN 512
|
||||
#define PIOS_COM_TELEM_RF_TX_BUF_LEN 512
|
||||
|
||||
#define PIOS_COM_GPS_RX_BUF_LEN 128
|
||||
#define PIOS_COM_GPS_TX_BUF_LEN 32
|
||||
|
||||
#define PIOS_COM_TELEM_USB_RX_BUF_LEN 65
|
||||
#define PIOS_COM_TELEM_USB_TX_BUF_LEN 65
|
||||
|
||||
#define PIOS_COM_BRIDGE_RX_BUF_LEN 65
|
||||
#define PIOS_COM_BRIDGE_TX_BUF_LEN 12
|
||||
|
||||
#define PIOS_COM_RFM22B_RF_RX_BUF_LEN 512
|
||||
#define PIOS_COM_RFM22B_RF_TX_BUF_LEN 512
|
||||
|
||||
#define PIOS_COM_HKOSD_RX_BUF_LEN 22
|
||||
#define PIOS_COM_HKOSD_TX_BUF_LEN 22
|
||||
|
||||
#define PIOS_COM_MSP_TX_BUF_LEN 128
|
||||
#define PIOS_COM_MSP_RX_BUF_LEN 64
|
||||
|
||||
#define PIOS_COM_MAVLINK_TX_BUF_LEN 128
|
||||
|
||||
#if defined(PIOS_INCLUDE_DEBUG_CONSOLE)
|
||||
#define PIOS_COM_DEBUGCONSOLE_TX_BUF_LEN 40
|
||||
uint32_t pios_com_debug_id;
|
||||
#endif /* PIOS_INCLUDE_DEBUG_CONSOLE */
|
||||
|
||||
uint32_t pios_com_gps_id = 0;
|
||||
uint32_t pios_com_telem_usb_id = 0;
|
||||
uint32_t pios_com_telem_rf_id = 0;
|
||||
uint32_t pios_com_bridge_id = 0;
|
||||
uint32_t pios_com_overo_id = 0;
|
||||
uint32_t pios_com_hkosd_id = 0;
|
||||
uint32_t pios_com_msp_id = 0;
|
||||
uint32_t pios_com_mavlink_id = 0;
|
||||
uint32_t pios_com_vcp_id = 0;
|
||||
|
||||
#if defined(PIOS_INCLUDE_RFM22B)
|
||||
uint32_t pios_rfm22b_id = 0;
|
||||
#endif
|
||||
|
||||
uintptr_t pios_uavo_settings_fs_id;
|
||||
uintptr_t pios_user_fs_id;
|
||||
|
||||
/*
|
||||
* Setup a com port based on the passed cfg, driver and buffer sizes.
|
||||
* tx size = 0 make the port rx only
|
||||
* rx size = 0 make the port tx only
|
||||
* having both tx and rx size = 0 is not valid and will fail further down in PIOS_COM_Init()
|
||||
*/
|
||||
static void PIOS_Board_configure_com(const struct pios_usart_cfg *usart_port_cfg, uint16_t rx_buf_len, uint16_t tx_buf_len,
|
||||
const struct pios_com_driver *com_driver, uint32_t *pios_com_id)
|
||||
static const PIOS_BOARD_IO_UART_Function flexiio_function_map[] = {
|
||||
[HWSETTINGS_RM_RCVRPORT_PPMTELEMETRY] = PIOS_BOARD_IO_UART_TELEMETRY,
|
||||
[HWSETTINGS_RM_RCVRPORT_PPMDEBUGCONSOLE] = PIOS_BOARD_IO_UART_DEBUGCONSOLE,
|
||||
[HWSETTINGS_RM_RCVRPORT_PPMCOMBRIDGE] = PIOS_BOARD_IO_UART_COMBRIDGE,
|
||||
[HWSETTINGS_RM_RCVRPORT_PPMMSP] = PIOS_BOARD_IO_UART_MSP,
|
||||
[HWSETTINGS_RM_RCVRPORT_PPMMAVLINK] = PIOS_BOARD_IO_UART_MAVLINK,
|
||||
[HWSETTINGS_RM_RCVRPORT_PPMGPS] = PIOS_BOARD_IO_UART_GPS,
|
||||
[HWSETTINGS_RM_RCVRPORT_TELEMETRY] = PIOS_BOARD_IO_UART_TELEMETRY,
|
||||
[HWSETTINGS_RM_RCVRPORT_DEBUGCONSOLE] = PIOS_BOARD_IO_UART_DEBUGCONSOLE,
|
||||
[HWSETTINGS_RM_RCVRPORT_COMBRIDGE] = PIOS_BOARD_IO_UART_COMBRIDGE,
|
||||
[HWSETTINGS_RM_RCVRPORT_MSP] = PIOS_BOARD_IO_UART_MSP,
|
||||
[HWSETTINGS_RM_RCVRPORT_MAVLINK] = PIOS_BOARD_IO_UART_MAVLINK,
|
||||
[HWSETTINGS_RM_RCVRPORT_GPS] = PIOS_BOARD_IO_UART_GPS,
|
||||
[HWSETTINGS_RM_RCVRPORT_IBUS] = PIOS_BOARD_IO_UART_IBUS,
|
||||
};
|
||||
|
||||
static const PIOS_BOARD_IO_UART_Function main_function_map[] = {
|
||||
[HWSETTINGS_RM_MAINPORT_TELEMETRY] = PIOS_BOARD_IO_UART_TELEMETRY,
|
||||
[HWSETTINGS_RM_MAINPORT_GPS] = PIOS_BOARD_IO_UART_GPS,
|
||||
[HWSETTINGS_RM_MAINPORT_SBUS] = PIOS_BOARD_IO_UART_SBUS,
|
||||
[HWSETTINGS_RM_MAINPORT_DSM] = PIOS_BOARD_IO_UART_DSM_MAIN,
|
||||
[HWSETTINGS_RM_MAINPORT_DEBUGCONSOLE] = PIOS_BOARD_IO_UART_DEBUGCONSOLE,
|
||||
[HWSETTINGS_RM_MAINPORT_COMBRIDGE] = PIOS_BOARD_IO_UART_COMBRIDGE,
|
||||
[HWSETTINGS_RM_MAINPORT_OSDHK] = PIOS_BOARD_IO_UART_OSDHK,
|
||||
[HWSETTINGS_RM_MAINPORT_MSP] = PIOS_BOARD_IO_UART_MSP,
|
||||
[HWSETTINGS_RM_MAINPORT_MAVLINK] = PIOS_BOARD_IO_UART_MAVLINK,
|
||||
};
|
||||
|
||||
static const PIOS_BOARD_IO_UART_Function flexi_function_map[] = {
|
||||
[HWSETTINGS_RM_FLEXIPORT_TELEMETRY] = PIOS_BOARD_IO_UART_TELEMETRY,
|
||||
[HWSETTINGS_RM_FLEXIPORT_GPS] = PIOS_BOARD_IO_UART_GPS,
|
||||
[HWSETTINGS_RM_FLEXIPORT_DSM] = PIOS_BOARD_IO_UART_DSM_FLEXI,
|
||||
[HWSETTINGS_RM_FLEXIPORT_EXBUS] = PIOS_BOARD_IO_UART_EXBUS,
|
||||
[HWSETTINGS_RM_FLEXIPORT_HOTTSUMD] = PIOS_BOARD_IO_UART_HOTT_SUMD,
|
||||
[HWSETTINGS_RM_FLEXIPORT_HOTTSUMH] = PIOS_BOARD_IO_UART_HOTT_SUMH,
|
||||
[HWSETTINGS_RM_FLEXIPORT_SRXL] = PIOS_BOARD_IO_UART_SRXL,
|
||||
[HWSETTINGS_RM_FLEXIPORT_IBUS] = PIOS_BOARD_IO_UART_IBUS,
|
||||
[HWSETTINGS_RM_FLEXIPORT_DEBUGCONSOLE] = PIOS_BOARD_IO_UART_DEBUGCONSOLE,
|
||||
[HWSETTINGS_RM_FLEXIPORT_COMBRIDGE] = PIOS_BOARD_IO_UART_COMBRIDGE,
|
||||
[HWSETTINGS_RM_FLEXIPORT_OSDHK] = PIOS_BOARD_IO_UART_OSDHK,
|
||||
[HWSETTINGS_RM_FLEXIPORT_MSP] = PIOS_BOARD_IO_UART_MSP,
|
||||
[HWSETTINGS_RM_FLEXIPORT_MAVLINK] = PIOS_BOARD_IO_UART_MAVLINK,
|
||||
};
|
||||
|
||||
|
||||
int32_t PIOS_BOARD_USART_Ioctl(uint32_t usart_id, uint32_t ctl, void *param)
|
||||
{
|
||||
uint32_t pios_usart_id;
|
||||
|
||||
if (PIOS_USART_Init(&pios_usart_id, usart_port_cfg)) {
|
||||
PIOS_Assert(0);
|
||||
const struct pios_usart_cfg *usart_cfg = PIOS_USART_GetConfig(usart_id);
|
||||
|
||||
switch (ctl) {
|
||||
case PIOS_IOCTL_USART_SET_INVERTED:
|
||||
if (usart_cfg->regs == pios_usart_main_cfg.regs) { /* main port */
|
||||
GPIO_WriteBit(MAIN_USART_INVERTER_GPIO,
|
||||
MAIN_USART_INVERTER_PIN,
|
||||
(*(enum PIOS_USART_Inverted *)param & PIOS_USART_Inverted_Rx) ? MAIN_USART_INVERTER_ENABLE : MAIN_USART_INVERTER_DISABLE);
|
||||
|
||||
return 0;
|
||||
}
|
||||
break;
|
||||
}
|
||||
|
||||
uint8_t *rx_buffer = 0, *tx_buffer = 0;
|
||||
|
||||
if (rx_buf_len > 0) {
|
||||
rx_buffer = (uint8_t *)pios_malloc(rx_buf_len);
|
||||
PIOS_Assert(rx_buffer);
|
||||
}
|
||||
|
||||
if (tx_buf_len > 0) {
|
||||
tx_buffer = (uint8_t *)pios_malloc(tx_buf_len);
|
||||
PIOS_Assert(tx_buffer);
|
||||
}
|
||||
|
||||
if (PIOS_COM_Init(pios_com_id, com_driver, pios_usart_id,
|
||||
rx_buffer, rx_buf_len,
|
||||
tx_buffer, tx_buf_len)) {
|
||||
PIOS_Assert(0);
|
||||
}
|
||||
}
|
||||
|
||||
static void PIOS_Board_configure_dsm(const struct pios_usart_cfg *pios_usart_dsm_cfg, const struct pios_dsm_cfg *pios_dsm_cfg,
|
||||
const struct pios_com_driver *usart_com_driver,
|
||||
ManualControlSettingsChannelGroupsOptions channelgroup, uint8_t *bind)
|
||||
{
|
||||
uint32_t pios_usart_dsm_id;
|
||||
|
||||
if (PIOS_USART_Init(&pios_usart_dsm_id, pios_usart_dsm_cfg)) {
|
||||
PIOS_Assert(0);
|
||||
}
|
||||
|
||||
uint32_t pios_dsm_id;
|
||||
if (PIOS_DSM_Init(&pios_dsm_id, pios_dsm_cfg, usart_com_driver,
|
||||
pios_usart_dsm_id, *bind)) {
|
||||
PIOS_Assert(0);
|
||||
}
|
||||
|
||||
uint32_t pios_dsm_rcvr_id;
|
||||
if (PIOS_RCVR_Init(&pios_dsm_rcvr_id, &pios_dsm_rcvr_driver, pios_dsm_id)) {
|
||||
PIOS_Assert(0);
|
||||
}
|
||||
pios_rcvr_group_map[channelgroup] = pios_dsm_rcvr_id;
|
||||
}
|
||||
|
||||
static void PIOS_Board_configure_pwm(const struct pios_pwm_cfg *pwm_cfg)
|
||||
{
|
||||
/* Set up the receiver port. Later this should be optional */
|
||||
uint32_t pios_pwm_id;
|
||||
|
||||
PIOS_PWM_Init(&pios_pwm_id, pwm_cfg);
|
||||
|
||||
uint32_t pios_pwm_rcvr_id;
|
||||
if (PIOS_RCVR_Init(&pios_pwm_rcvr_id, &pios_pwm_rcvr_driver, pios_pwm_id)) {
|
||||
PIOS_Assert(0);
|
||||
}
|
||||
pios_rcvr_group_map[MANUALCONTROLSETTINGS_CHANNELGROUPS_PWM] = pios_pwm_rcvr_id;
|
||||
}
|
||||
|
||||
static void PIOS_Board_configure_ppm(const struct pios_ppm_cfg *ppm_cfg)
|
||||
{
|
||||
uint32_t pios_ppm_id;
|
||||
|
||||
PIOS_PPM_Init(&pios_ppm_id, ppm_cfg);
|
||||
|
||||
uint32_t pios_ppm_rcvr_id;
|
||||
if (PIOS_RCVR_Init(&pios_ppm_rcvr_id, &pios_ppm_rcvr_driver, pios_ppm_id)) {
|
||||
PIOS_Assert(0);
|
||||
}
|
||||
pios_rcvr_group_map[MANUALCONTROLSETTINGS_CHANNELGROUPS_PPM] = pios_ppm_rcvr_id;
|
||||
|
||||
return -1;
|
||||
}
|
||||
|
||||
/**
|
||||
@ -366,14 +123,8 @@ static void PIOS_Board_configure_ppm(const struct pios_ppm_cfg *ppm_cfg)
|
||||
* initializes all the core subsystems on this specific hardware
|
||||
* called from System/openpilot.c
|
||||
*/
|
||||
|
||||
#include <pios_board_info.h>
|
||||
|
||||
void PIOS_Board_Init(void)
|
||||
{
|
||||
/* Delay system */
|
||||
PIOS_DELAY_Init();
|
||||
|
||||
const struct pios_board_info *bdinfo = &pios_board_info_blob;
|
||||
|
||||
#if defined(PIOS_INCLUDE_LED)
|
||||
@ -446,12 +197,7 @@ void PIOS_Board_Init(void)
|
||||
/* Initialize UAVObject libraries */
|
||||
EventDispatcherInitialize();
|
||||
UAVObjInitialize();
|
||||
|
||||
HwSettingsInitialize();
|
||||
#if defined(PIOS_INCLUDE_RFM22B)
|
||||
OPLinkSettingsInitialize();
|
||||
OPLinkStatusInitialize();
|
||||
#endif /* PIOS_INCLUDE_RFM22B */
|
||||
|
||||
/* Initialize the alarms library */
|
||||
AlarmsInitialize();
|
||||
@ -477,397 +223,67 @@ void PIOS_Board_Init(void)
|
||||
AlarmsSet(SYSTEMALARMS_ALARM_BOOTFAULT, SYSTEMALARMS_ALARM_CRITICAL);
|
||||
}
|
||||
|
||||
|
||||
// PIOS_IAP_Init();
|
||||
|
||||
#if defined(PIOS_INCLUDE_USB)
|
||||
/* Initialize board specific USB data */
|
||||
PIOS_USB_BOARD_DATA_Init();
|
||||
|
||||
/* Flags to determine if various USB interfaces are advertised */
|
||||
bool usb_hid_present = false;
|
||||
bool usb_cdc_present = false;
|
||||
|
||||
#if defined(PIOS_INCLUDE_USB_CDC)
|
||||
if (PIOS_USB_DESC_HID_CDC_Init()) {
|
||||
PIOS_Assert(0);
|
||||
}
|
||||
usb_hid_present = true;
|
||||
usb_cdc_present = true;
|
||||
#else
|
||||
if (PIOS_USB_DESC_HID_ONLY_Init()) {
|
||||
PIOS_Assert(0);
|
||||
}
|
||||
usb_hid_present = true;
|
||||
#endif
|
||||
|
||||
uint32_t pios_usb_id;
|
||||
PIOS_USB_Init(&pios_usb_id, PIOS_BOARD_HW_DEFS_GetUsbCfg(bdinfo->board_rev));
|
||||
|
||||
#if defined(PIOS_INCLUDE_USB_CDC)
|
||||
|
||||
uint8_t hwsettings_usb_vcpport;
|
||||
/* Configure the USB VCP port */
|
||||
HwSettingsUSB_VCPPortGet(&hwsettings_usb_vcpport);
|
||||
|
||||
if (!usb_cdc_present) {
|
||||
/* Force VCP port function to disabled if we haven't advertised VCP in our USB descriptor */
|
||||
hwsettings_usb_vcpport = HWSETTINGS_USB_VCPPORT_DISABLED;
|
||||
}
|
||||
uint32_t pios_usb_cdc_id;
|
||||
if (PIOS_USB_CDC_Init(&pios_usb_cdc_id, &pios_usb_cdc_cfg, pios_usb_id)) {
|
||||
PIOS_Assert(0);
|
||||
}
|
||||
|
||||
uint32_t pios_usb_hid_id;
|
||||
if (PIOS_USB_HID_Init(&pios_usb_hid_id, &pios_usb_hid_cfg, pios_usb_id)) {
|
||||
PIOS_Assert(0);
|
||||
}
|
||||
|
||||
switch (hwsettings_usb_vcpport) {
|
||||
case HWSETTINGS_USB_VCPPORT_DISABLED:
|
||||
break;
|
||||
case HWSETTINGS_USB_VCPPORT_USBTELEMETRY:
|
||||
#if defined(PIOS_INCLUDE_COM)
|
||||
{
|
||||
uint8_t *rx_buffer = (uint8_t *)pios_malloc(PIOS_COM_TELEM_USB_RX_BUF_LEN);
|
||||
uint8_t *tx_buffer = (uint8_t *)pios_malloc(PIOS_COM_TELEM_USB_TX_BUF_LEN);
|
||||
PIOS_Assert(rx_buffer);
|
||||
PIOS_Assert(tx_buffer);
|
||||
if (PIOS_COM_Init(&pios_com_telem_usb_id, &pios_usb_cdc_com_driver, pios_usb_cdc_id,
|
||||
rx_buffer, PIOS_COM_TELEM_USB_RX_BUF_LEN,
|
||||
tx_buffer, PIOS_COM_TELEM_USB_TX_BUF_LEN)) {
|
||||
PIOS_Assert(0);
|
||||
}
|
||||
}
|
||||
#endif /* PIOS_INCLUDE_COM */
|
||||
break;
|
||||
case HWSETTINGS_USB_VCPPORT_COMBRIDGE:
|
||||
#if defined(PIOS_INCLUDE_COM)
|
||||
{
|
||||
uint8_t *rx_buffer = (uint8_t *)pios_malloc(PIOS_COM_BRIDGE_RX_BUF_LEN);
|
||||
uint8_t *tx_buffer = (uint8_t *)pios_malloc(PIOS_COM_BRIDGE_TX_BUF_LEN);
|
||||
PIOS_Assert(rx_buffer);
|
||||
PIOS_Assert(tx_buffer);
|
||||
if (PIOS_COM_Init(&pios_com_vcp_id, &pios_usb_cdc_com_driver, pios_usb_cdc_id,
|
||||
rx_buffer, PIOS_COM_BRIDGE_RX_BUF_LEN,
|
||||
tx_buffer, PIOS_COM_BRIDGE_TX_BUF_LEN)) {
|
||||
PIOS_Assert(0);
|
||||
}
|
||||
}
|
||||
#endif /* PIOS_INCLUDE_COM */
|
||||
break;
|
||||
case HWSETTINGS_USB_VCPPORT_DEBUGCONSOLE:
|
||||
#if defined(PIOS_INCLUDE_COM)
|
||||
#if defined(PIOS_INCLUDE_DEBUG_CONSOLE)
|
||||
{
|
||||
uint8_t *tx_buffer = (uint8_t *)pios_malloc(PIOS_COM_DEBUGCONSOLE_TX_BUF_LEN);
|
||||
PIOS_Assert(tx_buffer);
|
||||
if (PIOS_COM_Init(&pios_com_debug_id, &pios_usb_cdc_com_driver, pios_usb_cdc_id,
|
||||
NULL, 0,
|
||||
tx_buffer, PIOS_COM_DEBUGCONSOLE_TX_BUF_LEN)) {
|
||||
PIOS_Assert(0);
|
||||
}
|
||||
}
|
||||
#endif /* PIOS_INCLUDE_DEBUG_CONSOLE */
|
||||
#endif /* PIOS_INCLUDE_COM */
|
||||
|
||||
break;
|
||||
}
|
||||
#endif /* PIOS_INCLUDE_USB_CDC */
|
||||
|
||||
#if defined(PIOS_INCLUDE_USB_HID)
|
||||
/* Configure the usb HID port */
|
||||
uint8_t hwsettings_usb_hidport;
|
||||
HwSettingsUSB_HIDPortGet(&hwsettings_usb_hidport);
|
||||
|
||||
if (!usb_hid_present) {
|
||||
/* Force HID port function to disabled if we haven't advertised HID in our USB descriptor */
|
||||
hwsettings_usb_hidport = HWSETTINGS_USB_HIDPORT_DISABLED;
|
||||
}
|
||||
|
||||
switch (hwsettings_usb_hidport) {
|
||||
case HWSETTINGS_USB_HIDPORT_DISABLED:
|
||||
break;
|
||||
case HWSETTINGS_USB_HIDPORT_USBTELEMETRY:
|
||||
#if defined(PIOS_INCLUDE_COM)
|
||||
{
|
||||
uint8_t *rx_buffer = (uint8_t *)pios_malloc(PIOS_COM_TELEM_USB_RX_BUF_LEN);
|
||||
uint8_t *tx_buffer = (uint8_t *)pios_malloc(PIOS_COM_TELEM_USB_TX_BUF_LEN);
|
||||
PIOS_Assert(rx_buffer);
|
||||
PIOS_Assert(tx_buffer);
|
||||
if (PIOS_COM_Init(&pios_com_telem_usb_id, &pios_usb_hid_com_driver, pios_usb_hid_id,
|
||||
rx_buffer, PIOS_COM_TELEM_USB_RX_BUF_LEN,
|
||||
tx_buffer, PIOS_COM_TELEM_USB_TX_BUF_LEN)) {
|
||||
PIOS_Assert(0);
|
||||
}
|
||||
}
|
||||
#endif /* PIOS_INCLUDE_COM */
|
||||
break;
|
||||
}
|
||||
|
||||
#endif /* PIOS_INCLUDE_USB_HID */
|
||||
|
||||
if (usb_hid_present || usb_cdc_present) {
|
||||
PIOS_USBHOOK_Activate();
|
||||
}
|
||||
#endif /* PIOS_INCLUDE_USB */
|
||||
|
||||
/* Configure IO ports */
|
||||
uint8_t hwsettings_DSMxBind;
|
||||
HwSettingsDSMxBindGet(&hwsettings_DSMxBind);
|
||||
|
||||
/* Configure main USART port */
|
||||
uint8_t hwsettings_mainport;
|
||||
HwSettingsRM_MainPortGet(&hwsettings_mainport);
|
||||
switch (hwsettings_mainport) {
|
||||
case HWSETTINGS_RM_MAINPORT_DISABLED:
|
||||
break;
|
||||
case HWSETTINGS_RM_MAINPORT_TELEMETRY:
|
||||
PIOS_Board_configure_com(&pios_usart_main_cfg, PIOS_COM_TELEM_RF_RX_BUF_LEN, PIOS_COM_TELEM_RF_TX_BUF_LEN, &pios_usart_com_driver, &pios_com_telem_rf_id);
|
||||
break;
|
||||
case HWSETTINGS_RM_MAINPORT_GPS:
|
||||
PIOS_Board_configure_com(&pios_usart_main_cfg, PIOS_COM_GPS_RX_BUF_LEN, PIOS_COM_GPS_TX_BUF_LEN, &pios_usart_com_driver, &pios_com_gps_id);
|
||||
break;
|
||||
case HWSETTINGS_RM_MAINPORT_SBUS:
|
||||
#if defined(PIOS_INCLUDE_SBUS)
|
||||
{
|
||||
uint32_t pios_usart_sbus_id;
|
||||
if (PIOS_USART_Init(&pios_usart_sbus_id, &pios_usart_sbus_main_cfg)) {
|
||||
PIOS_Assert(0);
|
||||
}
|
||||
|
||||
uint32_t pios_sbus_id;
|
||||
if (PIOS_SBus_Init(&pios_sbus_id, &pios_sbus_cfg, &pios_usart_com_driver, pios_usart_sbus_id)) {
|
||||
PIOS_Assert(0);
|
||||
}
|
||||
|
||||
uint32_t pios_sbus_rcvr_id;
|
||||
if (PIOS_RCVR_Init(&pios_sbus_rcvr_id, &pios_sbus_rcvr_driver, pios_sbus_id)) {
|
||||
PIOS_Assert(0);
|
||||
}
|
||||
pios_rcvr_group_map[MANUALCONTROLSETTINGS_CHANNELGROUPS_SBUS] = pios_sbus_rcvr_id;
|
||||
}
|
||||
#endif
|
||||
break;
|
||||
case HWSETTINGS_RM_MAINPORT_DSM:
|
||||
// Force binding to zero on the main port
|
||||
hwsettings_DSMxBind = 0;
|
||||
|
||||
// TODO: Define the various Channelgroup for Revo dsm inputs and handle here
|
||||
PIOS_Board_configure_dsm(&pios_usart_dsm_main_cfg, &pios_dsm_main_cfg,
|
||||
&pios_usart_com_driver, MANUALCONTROLSETTINGS_CHANNELGROUPS_DSMMAINPORT, &hwsettings_DSMxBind);
|
||||
break;
|
||||
case HWSETTINGS_RM_MAINPORT_DEBUGCONSOLE:
|
||||
#if defined(PIOS_INCLUDE_DEBUG_CONSOLE)
|
||||
{
|
||||
PIOS_Board_configure_com(&pios_usart_main_cfg, 0, PIOS_COM_DEBUGCONSOLE_TX_BUF_LEN, &pios_usart_com_driver, &pios_com_debug_id);
|
||||
}
|
||||
#endif /* PIOS_INCLUDE_DEBUG_CONSOLE */
|
||||
break;
|
||||
case HWSETTINGS_RM_MAINPORT_COMBRIDGE:
|
||||
PIOS_Board_configure_com(&pios_usart_main_cfg, PIOS_COM_BRIDGE_RX_BUF_LEN, PIOS_COM_BRIDGE_TX_BUF_LEN, &pios_usart_com_driver, &pios_com_bridge_id);
|
||||
break;
|
||||
case HWSETTINGS_RM_MAINPORT_MSP:
|
||||
PIOS_Board_configure_com(&pios_usart_main_cfg, PIOS_COM_MSP_RX_BUF_LEN, PIOS_COM_MSP_TX_BUF_LEN, &pios_usart_com_driver, &pios_com_msp_id);
|
||||
break;
|
||||
case HWSETTINGS_RM_MAINPORT_MAVLINK:
|
||||
PIOS_Board_configure_com(&pios_usart_main_cfg, 0, PIOS_COM_MAVLINK_TX_BUF_LEN, &pios_usart_com_driver, &pios_com_mavlink_id);
|
||||
break;
|
||||
case HWSETTINGS_RM_MAINPORT_OSDHK:
|
||||
PIOS_Board_configure_com(&pios_usart_hkosd_main_cfg, PIOS_COM_HKOSD_RX_BUF_LEN, PIOS_COM_HKOSD_TX_BUF_LEN, &pios_usart_com_driver, &pios_com_hkosd_id);
|
||||
break;
|
||||
} /* hwsettings_rm_mainport */
|
||||
|
||||
if (hwsettings_mainport != HWSETTINGS_RM_MAINPORT_SBUS) {
|
||||
GPIO_Init(pios_sbus_cfg.inv.gpio, &pios_sbus_cfg.inv.init);
|
||||
GPIO_WriteBit(pios_sbus_cfg.inv.gpio, pios_sbus_cfg.inv.init.GPIO_Pin, pios_sbus_cfg.gpio_inv_disable);
|
||||
}
|
||||
|
||||
|
||||
/* Configure FlexiPort */
|
||||
uint8_t hwsettings_flexiport;
|
||||
HwSettingsRM_FlexiPortGet(&hwsettings_flexiport);
|
||||
switch (hwsettings_flexiport) {
|
||||
case HWSETTINGS_RM_FLEXIPORT_DISABLED:
|
||||
break;
|
||||
case HWSETTINGS_RM_FLEXIPORT_TELEMETRY:
|
||||
PIOS_Board_configure_com(&pios_usart_flexi_cfg, PIOS_COM_TELEM_RF_RX_BUF_LEN, PIOS_COM_TELEM_RF_TX_BUF_LEN, &pios_usart_com_driver, &pios_com_telem_rf_id);
|
||||
break;
|
||||
case HWSETTINGS_RM_FLEXIPORT_I2C:
|
||||
|
||||
if (hwsettings_flexiport < NELEMENTS(flexi_function_map)) {
|
||||
PIOS_BOARD_IO_Configure_UART(&pios_usart_flexi_cfg, flexi_function_map[hwsettings_flexiport]);
|
||||
}
|
||||
|
||||
#if defined(PIOS_INCLUDE_I2C)
|
||||
/* Set up internal I2C bus */
|
||||
if (PIOS_I2C_Init(&pios_i2c_mag_pressure_adapter_id, &pios_i2c_mag_pressure_adapter_cfg)) {
|
||||
PIOS_DEBUG_Assert(0);
|
||||
}
|
||||
PIOS_DELAY_WaitmS(50);
|
||||
|
||||
if (hwsettings_flexiport == HWSETTINGS_RM_FLEXIPORT_I2C) {
|
||||
if (PIOS_I2C_Init(&pios_i2c_flexiport_adapter_id, &pios_i2c_flexiport_adapter_cfg)) {
|
||||
PIOS_Assert(0);
|
||||
}
|
||||
PIOS_DELAY_WaitmS(50); // this was after the other PIOS_I2C_Init(), so I copied it here too
|
||||
#ifdef PIOS_INCLUDE_WDG
|
||||
// give HMC5x83 on I2C some extra time to allow for reset, etc. if needed
|
||||
// this is not in a loop, so it is safe
|
||||
// leave this here even if PIOS_INCLUDE_HMC5X83 is undefined
|
||||
// to avoid making something else fail when HMC5X83 is removed
|
||||
PIOS_WDG_Clear();
|
||||
#endif /* PIOS_INCLUDE_WDG */
|
||||
#if defined(PIOS_INCLUDE_HMC5X83)
|
||||
// get auxmag type
|
||||
AuxMagSettingsTypeOptions option;
|
||||
AuxMagSettingsInitialize();
|
||||
AuxMagSettingsTypeGet(&option);
|
||||
// if the aux mag type is FlexiPort then set it up
|
||||
if (option == AUXMAGSETTINGS_TYPE_FLEXI) {
|
||||
// attach the 5x83 mag to the previously inited I2C2
|
||||
external_mag = PIOS_HMC5x83_Init(&pios_hmc5x83_external_cfg, pios_i2c_flexiport_adapter_id, 0);
|
||||
#ifdef PIOS_INCLUDE_WDG
|
||||
// give HMC5x83 on I2C some extra time to allow for reset, etc. if needed
|
||||
// this is not in a loop, so it is safe
|
||||
PIOS_WDG_Clear();
|
||||
#endif /* PIOS_INCLUDE_WDG */
|
||||
// add this sensor to the sensor task's list
|
||||
// be careful that you don't register a slow, unimportant sensor after registering the fastest sensor
|
||||
// and before registering some other fast and important sensor
|
||||
// as that would cause delay and time jitter for the second fast sensor
|
||||
PIOS_HMC5x83_Register(external_mag, PIOS_SENSORS_TYPE_3AXIS_AUXMAG);
|
||||
// mag alarm is cleared later, so use I2C
|
||||
AlarmsSet(SYSTEMALARMS_ALARM_I2C, (external_mag) ? SYSTEMALARMS_ALARM_OK : SYSTEMALARMS_ALARM_WARNING);
|
||||
}
|
||||
#endif /* PIOS_INCLUDE_HMC5X83 */
|
||||
#endif /* PIOS_INCLUDE_I2C */
|
||||
break;
|
||||
case HWSETTINGS_RM_FLEXIPORT_GPS:
|
||||
PIOS_Board_configure_com(&pios_usart_flexi_cfg, PIOS_COM_GPS_RX_BUF_LEN, PIOS_COM_GPS_TX_BUF_LEN, &pios_usart_com_driver, &pios_com_gps_id);
|
||||
break;
|
||||
case HWSETTINGS_RM_FLEXIPORT_DSM:
|
||||
// TODO: Define the various Channelgroup for Revo dsm inputs and handle here
|
||||
PIOS_Board_configure_dsm(&pios_usart_dsm_flexi_cfg, &pios_dsm_flexi_cfg,
|
||||
&pios_usart_com_driver, MANUALCONTROLSETTINGS_CHANNELGROUPS_DSMFLEXIPORT, &hwsettings_DSMxBind);
|
||||
break;
|
||||
case HWSETTINGS_RM_FLEXIPORT_DEBUGCONSOLE:
|
||||
#if defined(PIOS_INCLUDE_DEBUG_CONSOLE)
|
||||
{
|
||||
PIOS_Board_configure_com(&pios_usart_flexi_cfg, 0, PIOS_COM_DEBUGCONSOLE_TX_BUF_LEN, &pios_usart_com_driver, &pios_com_debug_id);
|
||||
}
|
||||
#endif /* PIOS_INCLUDE_DEBUG_CONSOLE */
|
||||
break;
|
||||
case HWSETTINGS_RM_FLEXIPORT_COMBRIDGE:
|
||||
PIOS_Board_configure_com(&pios_usart_flexi_cfg, PIOS_COM_BRIDGE_RX_BUF_LEN, PIOS_COM_BRIDGE_TX_BUF_LEN, &pios_usart_com_driver, &pios_com_bridge_id);
|
||||
break;
|
||||
case HWSETTINGS_RM_FLEXIPORT_MSP:
|
||||
PIOS_Board_configure_com(&pios_usart_flexi_cfg, PIOS_COM_MSP_RX_BUF_LEN, PIOS_COM_MSP_TX_BUF_LEN, &pios_usart_com_driver, &pios_com_msp_id);
|
||||
break;
|
||||
case HWSETTINGS_RM_FLEXIPORT_MAVLINK:
|
||||
PIOS_Board_configure_com(&pios_usart_flexi_cfg, 0, PIOS_COM_MAVLINK_TX_BUF_LEN, &pios_usart_com_driver, &pios_com_mavlink_id);
|
||||
break;
|
||||
case HWSETTINGS_RM_FLEXIPORT_OSDHK:
|
||||
PIOS_Board_configure_com(&pios_usart_hkosd_flexi_cfg, PIOS_COM_HKOSD_RX_BUF_LEN, PIOS_COM_HKOSD_TX_BUF_LEN, &pios_usart_com_driver, &pios_com_hkosd_id);
|
||||
break;
|
||||
} /* hwsettings_rm_flexiport */
|
||||
|
||||
|
||||
/* Initialize the RFM22B radio COM device. */
|
||||
#if defined(PIOS_INCLUDE_RFM22B)
|
||||
|
||||
/* Fetch the OPLinkSettings object. */
|
||||
OPLinkSettingsData oplinkSettings;
|
||||
OPLinkSettingsGet(&oplinkSettings);
|
||||
|
||||
// Initialize out status object.
|
||||
OPLinkStatusData oplinkStatus;
|
||||
OPLinkStatusGet(&oplinkStatus);
|
||||
oplinkStatus.BoardType = bdinfo->board_type;
|
||||
PIOS_BL_HELPER_FLASH_Read_Description(oplinkStatus.Description, OPLINKSTATUS_DESCRIPTION_NUMELEM);
|
||||
PIOS_SYS_SerialNumberGetBinary(oplinkStatus.CPUSerial);
|
||||
oplinkStatus.BoardRevision = bdinfo->board_rev;
|
||||
|
||||
/* Is the radio turned on? */
|
||||
bool is_coordinator = (oplinkSettings.Coordinator == OPLINKSETTINGS_COORDINATOR_TRUE);
|
||||
bool is_oneway = (oplinkSettings.OneWay == OPLINKSETTINGS_ONEWAY_TRUE);
|
||||
bool ppm_mode = (oplinkSettings.PPM == OPLINKSETTINGS_PPM_TRUE);
|
||||
if (oplinkSettings.MaxRFPower != OPLINKSETTINGS_MAXRFPOWER_0) {
|
||||
/* Configure the RFM22B device. */
|
||||
const struct pios_rfm22b_cfg *rfm22b_cfg = PIOS_BOARD_HW_DEFS_GetRfm22Cfg(bdinfo->board_rev);
|
||||
if (PIOS_RFM22B_Init(&pios_rfm22b_id, PIOS_RFM22_SPI_PORT, rfm22b_cfg->slave_num, rfm22b_cfg, oplinkSettings.RFBand)) {
|
||||
PIOS_Assert(0);
|
||||
}
|
||||
|
||||
/* Configure the radio com interface */
|
||||
uint8_t *rx_buffer = (uint8_t *)pios_malloc(PIOS_COM_RFM22B_RF_RX_BUF_LEN);
|
||||
uint8_t *tx_buffer = (uint8_t *)pios_malloc(PIOS_COM_RFM22B_RF_TX_BUF_LEN);
|
||||
PIOS_Assert(rx_buffer);
|
||||
PIOS_Assert(tx_buffer);
|
||||
if (PIOS_COM_Init(&pios_com_telem_rf_id, &pios_rfm22b_com_driver, pios_rfm22b_id,
|
||||
rx_buffer, PIOS_COM_RFM22B_RF_RX_BUF_LEN,
|
||||
tx_buffer, PIOS_COM_RFM22B_RF_TX_BUF_LEN)) {
|
||||
PIOS_Assert(0);
|
||||
}
|
||||
oplinkStatus.LinkState = OPLINKSTATUS_LINKSTATE_ENABLED;
|
||||
|
||||
// Set the RF data rate on the modem to ~2X the selected buad rate because the modem is half duplex.
|
||||
enum rfm22b_datarate datarate = RFM22_datarate_64000;
|
||||
switch (oplinkSettings.ComSpeed) {
|
||||
case OPLINKSETTINGS_COMSPEED_4800:
|
||||
datarate = RFM22_datarate_9600;
|
||||
break;
|
||||
case OPLINKSETTINGS_COMSPEED_9600:
|
||||
datarate = RFM22_datarate_19200;
|
||||
break;
|
||||
case OPLINKSETTINGS_COMSPEED_19200:
|
||||
datarate = RFM22_datarate_32000;
|
||||
break;
|
||||
case OPLINKSETTINGS_COMSPEED_38400:
|
||||
datarate = RFM22_datarate_64000;
|
||||
break;
|
||||
case OPLINKSETTINGS_COMSPEED_57600:
|
||||
datarate = RFM22_datarate_100000;
|
||||
break;
|
||||
case OPLINKSETTINGS_COMSPEED_115200:
|
||||
datarate = RFM22_datarate_192000;
|
||||
break;
|
||||
}
|
||||
|
||||
/* Set the radio configuration parameters. */
|
||||
PIOS_RFM22B_SetDeviceID(pios_rfm22b_id, oplinkSettings.CustomDeviceID);
|
||||
PIOS_RFM22B_SetCoordinatorID(pios_rfm22b_id, oplinkSettings.CoordID);
|
||||
PIOS_RFM22B_SetXtalCap(pios_rfm22b_id, oplinkSettings.RFXtalCap);
|
||||
PIOS_RFM22B_SetChannelConfig(pios_rfm22b_id, datarate, oplinkSettings.MinChannel, oplinkSettings.MaxChannel, is_coordinator, data_mode, ppm_mode);
|
||||
|
||||
/* Set the modem Tx power level */
|
||||
switch (oplinkSettings.MaxRFPower) {
|
||||
case OPLINKSETTINGS_MAXRFPOWER_125:
|
||||
PIOS_RFM22B_SetTxPower(pios_rfm22b_id, RFM22_tx_pwr_txpow_0);
|
||||
break;
|
||||
case OPLINKSETTINGS_MAXRFPOWER_16:
|
||||
PIOS_RFM22B_SetTxPower(pios_rfm22b_id, RFM22_tx_pwr_txpow_1);
|
||||
break;
|
||||
case OPLINKSETTINGS_MAXRFPOWER_316:
|
||||
PIOS_RFM22B_SetTxPower(pios_rfm22b_id, RFM22_tx_pwr_txpow_2);
|
||||
break;
|
||||
case OPLINKSETTINGS_MAXRFPOWER_63:
|
||||
PIOS_RFM22B_SetTxPower(pios_rfm22b_id, RFM22_tx_pwr_txpow_3);
|
||||
break;
|
||||
case OPLINKSETTINGS_MAXRFPOWER_126:
|
||||
PIOS_RFM22B_SetTxPower(pios_rfm22b_id, RFM22_tx_pwr_txpow_4);
|
||||
break;
|
||||
case OPLINKSETTINGS_MAXRFPOWER_25:
|
||||
PIOS_RFM22B_SetTxPower(pios_rfm22b_id, RFM22_tx_pwr_txpow_5);
|
||||
break;
|
||||
case OPLINKSETTINGS_MAXRFPOWER_50:
|
||||
PIOS_RFM22B_SetTxPower(pios_rfm22b_id, RFM22_tx_pwr_txpow_6);
|
||||
break;
|
||||
case OPLINKSETTINGS_MAXRFPOWER_100:
|
||||
PIOS_RFM22B_SetTxPower(pios_rfm22b_id, RFM22_tx_pwr_txpow_7);
|
||||
break;
|
||||
default:
|
||||
// do nothing
|
||||
break;
|
||||
}
|
||||
|
||||
/* Reinitialize the modem. */
|
||||
PIOS_RFM22B_Reinit(pios_rfm22b_id);
|
||||
} else {
|
||||
oplinkStatus.LinkState = OPLINKSTATUS_LINKSTATE_DISABLED;
|
||||
PIOS_DELAY_WaitmS(50);
|
||||
}
|
||||
|
||||
PIOS_BOARD_IO_Configure_I2C(pios_i2c_mag_pressure_adapter_id, pios_i2c_flexiport_adapter_id);
|
||||
#endif
|
||||
|
||||
OPLinkStatusSet(&oplinkStatus);
|
||||
#if defined(PIOS_INCLUDE_USB)
|
||||
PIOS_BOARD_IO_Configure_USB();
|
||||
#endif
|
||||
|
||||
/* Configure main USART port */
|
||||
|
||||
/* Initialize inverter gpio and set it to off */
|
||||
{
|
||||
GPIO_InitTypeDef inverterGPIOInit = {
|
||||
.GPIO_Pin = MAIN_USART_INVERTER_PIN,
|
||||
.GPIO_Speed = GPIO_Speed_2MHz,
|
||||
.GPIO_Mode = GPIO_Mode_OUT,
|
||||
.GPIO_OType = GPIO_OType_PP,
|
||||
.GPIO_PuPd = GPIO_PuPd_UP
|
||||
};
|
||||
|
||||
GPIO_Init(MAIN_USART_INVERTER_GPIO, &inverterGPIOInit);
|
||||
GPIO_WriteBit(MAIN_USART_INVERTER_GPIO,
|
||||
MAIN_USART_INVERTER_PIN,
|
||||
MAIN_USART_INVERTER_DISABLE);
|
||||
}
|
||||
|
||||
uint8_t hwsettings_mainport;
|
||||
HwSettingsRM_MainPortGet(&hwsettings_mainport);
|
||||
|
||||
if (hwsettings_mainport < NELEMENTS(main_function_map)) {
|
||||
PIOS_BOARD_IO_Configure_UART(&pios_usart_main_cfg, main_function_map[hwsettings_mainport]);
|
||||
}
|
||||
|
||||
#if defined(PIOS_INCLUDE_RFM22B)
|
||||
PIOS_BOARD_IO_Configure_RFM22B();
|
||||
#endif /* PIOS_INCLUDE_RFM22B */
|
||||
|
||||
|
||||
#if defined(PIOS_INCLUDE_PWM) || defined(PIOS_INCLUDE_PPM)
|
||||
|
||||
const struct pios_servo_cfg *pios_servo_cfg;
|
||||
@ -878,99 +294,51 @@ void PIOS_Board_Init(void)
|
||||
/* Configure the receiver port*/
|
||||
uint8_t hwsettings_rcvrport;
|
||||
HwSettingsRM_RcvrPortGet(&hwsettings_rcvrport);
|
||||
//
|
||||
|
||||
if (hwsettings_rcvrport < NELEMENTS(flexiio_function_map)) {
|
||||
PIOS_BOARD_IO_Configure_UART(&pios_usart_flexiio_cfg, flexiio_function_map[hwsettings_rcvrport]);
|
||||
}
|
||||
|
||||
// Configure rcvrport PPM/PWM/OUTPUTS
|
||||
switch (hwsettings_rcvrport) {
|
||||
case HWSETTINGS_RM_RCVRPORT_DISABLED:
|
||||
break;
|
||||
case HWSETTINGS_RM_RCVRPORT_PWM:
|
||||
case HWSETTINGS_RM_RCVRPORT_PWM:
|
||||
#if defined(PIOS_INCLUDE_PWM)
|
||||
/* Set up the receiver port. Later this should be optional */
|
||||
PIOS_Board_configure_pwm(&pios_pwm_cfg);
|
||||
/* Set up the receiver port. Later this should be optional */
|
||||
PIOS_BOARD_IO_Configure_PWM(&pios_pwm_cfg);
|
||||
#endif /* PIOS_INCLUDE_PWM */
|
||||
break;
|
||||
case HWSETTINGS_RM_RCVRPORT_PPM:
|
||||
case HWSETTINGS_RM_RCVRPORT_PPMOUTPUTS:
|
||||
case HWSETTINGS_RM_RCVRPORT_PPMPWM:
|
||||
case HWSETTINGS_RM_RCVRPORT_PPMTELEMETRY:
|
||||
case HWSETTINGS_RM_RCVRPORT_PPMDEBUGCONSOLE:
|
||||
case HWSETTINGS_RM_RCVRPORT_PPMCOMBRIDGE:
|
||||
case HWSETTINGS_RM_RCVRPORT_PPMMSP:
|
||||
case HWSETTINGS_RM_RCVRPORT_PPMMAVLINK:
|
||||
case HWSETTINGS_RM_RCVRPORT_PPMGPS:
|
||||
break;
|
||||
case HWSETTINGS_RM_RCVRPORT_PPM:
|
||||
case HWSETTINGS_RM_RCVRPORT_PPMOUTPUTS:
|
||||
case HWSETTINGS_RM_RCVRPORT_PPMPWM:
|
||||
case HWSETTINGS_RM_RCVRPORT_PPMTELEMETRY:
|
||||
case HWSETTINGS_RM_RCVRPORT_PPMDEBUGCONSOLE:
|
||||
case HWSETTINGS_RM_RCVRPORT_PPMCOMBRIDGE:
|
||||
case HWSETTINGS_RM_RCVRPORT_PPMMSP:
|
||||
case HWSETTINGS_RM_RCVRPORT_PPMMAVLINK:
|
||||
case HWSETTINGS_RM_RCVRPORT_PPMGPS:
|
||||
#if defined(PIOS_INCLUDE_PPM)
|
||||
if (hwsettings_rcvrport == HWSETTINGS_RM_RCVRPORT_PPMOUTPUTS) {
|
||||
// configure servo outputs and the remaining 5 inputs as outputs
|
||||
pios_servo_cfg = &pios_servo_cfg_out_in_ppm;
|
||||
}
|
||||
|
||||
PIOS_Board_configure_ppm(&pios_ppm_cfg);
|
||||
|
||||
// enable pwm on the remaining channels
|
||||
if (hwsettings_rcvrport == HWSETTINGS_RM_RCVRPORT_PPMPWM) {
|
||||
PIOS_Board_configure_pwm(&pios_pwm_ppm_cfg);
|
||||
}
|
||||
|
||||
break;
|
||||
PIOS_BOARD_IO_Configure_PPM(&pios_ppm_cfg);
|
||||
|
||||
if (hwsettings_rcvrport == HWSETTINGS_RM_RCVRPORT_PPMOUTPUTS) {
|
||||
// configure servo outputs and the remaining 5 inputs as outputs
|
||||
pios_servo_cfg = &pios_servo_cfg_out_in_ppm;
|
||||
}
|
||||
|
||||
// enable pwm on the remaining channels
|
||||
if (hwsettings_rcvrport == HWSETTINGS_RM_RCVRPORT_PPMPWM) {
|
||||
PIOS_BOARD_IO_Configure_PWM(&pios_pwm_ppm_cfg);
|
||||
}
|
||||
|
||||
break;
|
||||
#endif /* PIOS_INCLUDE_PPM */
|
||||
case HWSETTINGS_RM_RCVRPORT_OUTPUTS:
|
||||
// configure only the servo outputs
|
||||
pios_servo_cfg = &pios_servo_cfg_out_in;
|
||||
break;
|
||||
case HWSETTINGS_RM_RCVRPORT_OUTPUTS:
|
||||
// configure only the servo outputs
|
||||
pios_servo_cfg = &pios_servo_cfg_out_in;
|
||||
break;
|
||||
}
|
||||
|
||||
// Configure rcvrport usart
|
||||
switch (hwsettings_rcvrport) {
|
||||
case HWSETTINGS_RM_RCVRPORT_TELEMETRY:
|
||||
case HWSETTINGS_RM_RCVRPORT_PPMTELEMETRY:
|
||||
PIOS_Board_configure_com(&pios_usart_rcvrport_cfg, PIOS_COM_TELEM_RF_RX_BUF_LEN, PIOS_COM_TELEM_RF_TX_BUF_LEN, &pios_usart_com_driver, &pios_com_telem_rf_id);
|
||||
break;
|
||||
case HWSETTINGS_RM_RCVRPORT_DEBUGCONSOLE:
|
||||
case HWSETTINGS_RM_RCVRPORT_PPMDEBUGCONSOLE:
|
||||
#if defined(PIOS_INCLUDE_DEBUG_CONSOLE)
|
||||
PIOS_Board_configure_com(&pios_usart_rcvrport_cfg, 0, PIOS_COM_DEBUGCONSOLE_TX_BUF_LEN, &pios_usart_com_driver, &pios_com_debug_id);
|
||||
#endif /* PIOS_INCLUDE_DEBUG_CONSOLE */
|
||||
break;
|
||||
case HWSETTINGS_RM_RCVRPORT_COMBRIDGE:
|
||||
case HWSETTINGS_RM_RCVRPORT_PPMCOMBRIDGE:
|
||||
PIOS_Board_configure_com(&pios_usart_rcvrport_cfg, PIOS_COM_BRIDGE_RX_BUF_LEN, PIOS_COM_BRIDGE_TX_BUF_LEN, &pios_usart_com_driver, &pios_com_bridge_id);
|
||||
break;
|
||||
case HWSETTINGS_RM_RCVRPORT_MSP:
|
||||
case HWSETTINGS_RM_RCVRPORT_PPMMSP:
|
||||
PIOS_Board_configure_com(&pios_usart_rcvrport_cfg, PIOS_COM_MSP_RX_BUF_LEN, PIOS_COM_MSP_TX_BUF_LEN, &pios_usart_com_driver, &pios_com_msp_id);
|
||||
break;
|
||||
case HWSETTINGS_RM_RCVRPORT_MAVLINK:
|
||||
case HWSETTINGS_RM_RCVRPORT_PPMMAVLINK:
|
||||
PIOS_Board_configure_com(&pios_usart_rcvrport_cfg, 0, PIOS_COM_MAVLINK_TX_BUF_LEN, &pios_usart_com_driver, &pios_com_mavlink_id);
|
||||
break;
|
||||
case HWSETTINGS_RM_RCVRPORT_GPS:
|
||||
case HWSETTINGS_RM_RCVRPORT_PPMGPS:
|
||||
PIOS_Board_configure_com(&pios_usart_rcvrport_cfg, PIOS_COM_GPS_RX_BUF_LEN, PIOS_COM_GPS_TX_BUF_LEN, &pios_usart_com_driver, &pios_com_gps_id);
|
||||
break;
|
||||
}
|
||||
|
||||
#if defined(PIOS_INCLUDE_GCSRCVR)
|
||||
GCSReceiverInitialize();
|
||||
uint32_t pios_gcsrcvr_id;
|
||||
PIOS_GCSRCVR_Init(&pios_gcsrcvr_id);
|
||||
uint32_t pios_gcsrcvr_rcvr_id;
|
||||
if (PIOS_RCVR_Init(&pios_gcsrcvr_rcvr_id, &pios_gcsrcvr_rcvr_driver, pios_gcsrcvr_id)) {
|
||||
PIOS_Assert(0);
|
||||
}
|
||||
pios_rcvr_group_map[MANUALCONTROLSETTINGS_CHANNELGROUPS_GCS] = pios_gcsrcvr_rcvr_id;
|
||||
#endif /* PIOS_INCLUDE_GCSRCVR */
|
||||
|
||||
#if defined(PIOS_INCLUDE_OPLINKRCVR)
|
||||
{
|
||||
OPLinkReceiverInitialize();
|
||||
uint32_t pios_oplinkrcvr_id;
|
||||
PIOS_OPLinkRCVR_Init(&pios_oplinkrcvr_id, pios_rfm22b_id);
|
||||
uint32_t pios_oplinkrcvr_rcvr_id;
|
||||
if (PIOS_RCVR_Init(&pios_oplinkrcvr_rcvr_id, &pios_oplinkrcvr_rcvr_driver, pios_oplinkrcvr_id)) {
|
||||
PIOS_Assert(0);
|
||||
}
|
||||
pios_rcvr_group_map[MANUALCONTROLSETTINGS_CHANNELGROUPS_OPLINK] = pios_oplinkrcvr_rcvr_id;
|
||||
}
|
||||
#endif /* PIOS_INCLUDE_OPLINKRCVR */
|
||||
#ifdef PIOS_INCLUDE_GCSRCVR
|
||||
PIOS_BOARD_IO_Configure_GCSRCVR();
|
||||
#endif
|
||||
|
||||
#ifndef PIOS_ENABLE_DEBUG_PINS
|
||||
// pios_servo_cfg points to the correct configuration based on input port settings
|
||||
@ -979,6 +347,17 @@ void PIOS_Board_Init(void)
|
||||
PIOS_DEBUG_Init(pios_tim_servoport_all_pins, NELEMENTS(pios_tim_servoport_all_pins));
|
||||
#endif
|
||||
|
||||
#if defined(PIOS_INCLUDE_MPU6000)
|
||||
PIOS_MPU6000_Init(pios_spi_gyro_id, 0, &pios_mpu6000_cfg);
|
||||
PIOS_MPU6000_CONFIG_Configure();
|
||||
PIOS_MPU6000_Register();
|
||||
#endif
|
||||
|
||||
#ifdef PIOS_INCLUDE_WS2811
|
||||
PIOS_WS2811_Init(&pios_ws2811_cfg, &pios_ws2811_pin_cfg);
|
||||
#endif // PIOS_INCLUDE_WS2811
|
||||
|
||||
#ifdef PIOS_INCLUDE_ADC
|
||||
// Disable GPIO_A8 Pullup to prevent wrong results on battery voltage readout
|
||||
GPIO_InitTypeDef gpioA8 = {
|
||||
.GPIO_Speed = GPIO_Speed_2MHz,
|
||||
@ -988,61 +367,8 @@ void PIOS_Board_Init(void)
|
||||
.GPIO_OType = GPIO_OType_OD,
|
||||
};
|
||||
GPIO_Init(GPIOA, &gpioA8);
|
||||
|
||||
// init I2C1 for use with the internal mag and baro
|
||||
if (PIOS_I2C_Init(&pios_i2c_mag_pressure_adapter_id, &pios_i2c_mag_pressure_adapter_cfg)) {
|
||||
PIOS_DEBUG_Assert(0);
|
||||
}
|
||||
|
||||
PIOS_DELAY_WaitmS(50);
|
||||
|
||||
#if defined(PIOS_INCLUDE_ADC)
|
||||
PIOS_ADC_Init(&pios_adc_cfg);
|
||||
#endif
|
||||
|
||||
#ifdef PIOS_INCLUDE_WDG
|
||||
// give HMC5x83 on I2C some extra time to allow for reset, etc. if needed
|
||||
// this is not in a loop, so it is safe
|
||||
// leave this here even if PIOS_INCLUDE_HMC5X83 is undefined
|
||||
// to avoid making something else fail when HMC5X83 is removed
|
||||
PIOS_WDG_Clear();
|
||||
#endif /* PIOS_INCLUDE_WDG */
|
||||
|
||||
#if defined(PIOS_INCLUDE_HMC5X83)
|
||||
// attach the 5x83 mag to the previously inited I2C1
|
||||
onboard_mag = PIOS_HMC5x83_Init(&pios_hmc5x83_internal_cfg, pios_i2c_mag_pressure_adapter_id, 0);
|
||||
#ifdef PIOS_INCLUDE_WDG
|
||||
// give HMC5x83 on I2C some extra time to allow for reset, etc. if needed
|
||||
// this is not in a loop, so it is safe
|
||||
PIOS_WDG_Clear();
|
||||
#endif /* PIOS_INCLUDE_WDG */
|
||||
// add this sensor to the sensor task's list
|
||||
PIOS_HMC5x83_Register(onboard_mag, PIOS_SENSORS_TYPE_3AXIS_MAG);
|
||||
#endif
|
||||
|
||||
#if defined(PIOS_INCLUDE_MS5611)
|
||||
PIOS_MS5611_Init(&pios_ms5611_cfg, pios_i2c_mag_pressure_adapter_id);
|
||||
#endif
|
||||
|
||||
#if defined(PIOS_INCLUDE_MPU6000)
|
||||
PIOS_MPU6000_Init(pios_spi_gyro_id, 0, &pios_mpu6000_cfg);
|
||||
PIOS_MPU6000_CONFIG_Configure();
|
||||
#endif
|
||||
|
||||
#ifdef PIOS_INCLUDE_WS2811
|
||||
#include <pios_ws2811.h>
|
||||
PIOS_WS2811_Init(&pios_ws2811_cfg, &pios_ws2811_pin_cfg);
|
||||
#endif // PIOS_INCLUDE_WS2811
|
||||
#ifdef PIOS_INCLUDE_ADC
|
||||
{
|
||||
uint8_t adc_config[HWSETTINGS_ADCROUTING_NUMELEM];
|
||||
HwSettingsADCRoutingArrayGet(adc_config);
|
||||
for (uint32_t i = 0; i < HWSETTINGS_ADCROUTING_NUMELEM; i++) {
|
||||
if (adc_config[i] != HWSETTINGS_ADCROUTING_DISABLED) {
|
||||
PIOS_ADC_PinSetup(i);
|
||||
}
|
||||
}
|
||||
}
|
||||
|
||||
PIOS_BOARD_IO_Configure_ADC();
|
||||
#endif // PIOS_INCLUDE_ADC
|
||||
}
|
||||
|
||||
|
@ -46,7 +46,6 @@ static int32_t PIOS_BOARD_USART_Ioctl(__attribute__((unused)) uint32_t usart_id,
|
||||
return -1;
|
||||
}
|
||||
|
||||
|
||||
void PIOS_Board_Init()
|
||||
{
|
||||
if (board_init_complete) {
|
||||
|
Loading…
x
Reference in New Issue
Block a user