1
0
mirror of https://bitbucket.org/librepilot/librepilot.git synced 2025-02-26 15:54:15 +01:00

LP-480 all targets build nicely.

This commit is contained in:
Vladimir Zidar 2017-04-16 02:38:42 +02:00
parent a6f7cc6cdf
commit 83326eaca3
29 changed files with 655 additions and 1547 deletions

View File

@ -184,7 +184,7 @@
/* Begin PBXLegacyTarget section */
6581071511DE809D0049FB12 /* OpenPilotOSX */ = {
isa = PBXLegacyTarget;
buildArgumentsString = ef_gpsplatinum;
buildArgumentsString = ef_osd;
buildConfigurationList = 6581071A11DE80A30049FB12 /* Build configuration list for PBXLegacyTarget "OpenPilotOSX" */;
buildPhases = (
);

View File

@ -87,6 +87,10 @@ uint32_t pios_rfm22b_id; /* RFM22B handle */
uint32_t pios_com_rf_id; /* RFM22B telemetry */
#endif
#ifdef PIOS_INCLUDE_OPENLRS
uint32_t pios_openlrs_id; /* OpenLRS handle */
#endif
uint32_t pios_com_hkosd_id; /* HK OSD ?? */
uint32_t pios_com_msp_id; /* MSP */
uint32_t pios_com_mavlink_id; /* MAVLink */
@ -157,18 +161,47 @@ static void PIOS_BOARD_IO_HID_Init(uint32_t *com_id, uint16_t rx_buf_len, uint16
}
}
PIOS_BOARD_IO_USB_HID_Function PIOS_BOARD_IO_HWSettings_USB_HID_Function()
{
static const PIOS_BOARD_IO_USB_HID_Function map[] = {
[HWSETTINGS_USB_HIDPORT_USBTELEMETRY] = PIOS_BOARD_IO_USB_HID_TELEMETRY,
[HWSETTINGS_USB_HIDPORT_RCTRANSMITTER] = PIOS_BOARD_IO_USB_HID_RCTX,
};
uint8_t hwsettings_usb_hidport;
HwSettingsUSB_HIDPortGet(&hwsettings_usb_hidport);
return (hwsettings_usb_hidport < NELEMENTS(map)) ? map[hwsettings_usb_hidport] : PIOS_BOARD_IO_USB_HID_NONE;
}
PIOS_BOARD_IO_USB_VCP_Function PIOS_BOARD_IO_HWSettings_USB_VCP_Function()
{
static const PIOS_BOARD_IO_USB_VCP_Function map[] = {
[HWSETTINGS_USB_VCPPORT_USBTELEMETRY] = PIOS_BOARD_IO_USB_VCP_TELEMETRY,
[HWSETTINGS_USB_VCPPORT_COMBRIDGE] = PIOS_BOARD_IO_USB_VCP_COMBRIDGE,
[HWSETTINGS_USB_VCPPORT_DEBUGCONSOLE] = PIOS_BOARD_IO_USB_VCP_DEBUGCONSOLE,
[HWSETTINGS_USB_VCPPORT_MAVLINK] = PIOS_BOARD_IO_USB_VCP_MAVLINK,
};
uint8_t hwsettings_usb_vcpport;
HwSettingsUSB_VCPPortGet(&hwsettings_usb_vcpport);
return (hwsettings_usb_vcpport < NELEMENTS(map)) ? map[hwsettings_usb_vcpport] : PIOS_BOARD_IO_USB_VCP_NONE;
}
void PIOS_BOARD_IO_Configure_USB()
{
PIOS_BOARD_IO_Configure_USB_Function(PIOS_BOARD_IO_HWSettings_USB_HID_Function(),
PIOS_BOARD_IO_HWSettings_USB_VCP_Function());
}
void PIOS_BOARD_IO_Configure_USB_Function(PIOS_BOARD_IO_USB_HID_Function hid_function, __attribute__((unused)) PIOS_BOARD_IO_USB_VCP_Function vcp_function)
{
/* Initialize board specific USB data */
PIOS_USB_BOARD_DATA_Init();
uint8_t hwsettings_usb_hidport;
HwSettingsUSB_HIDPortGet(&hwsettings_usb_hidport);
#if defined(PIOS_INCLUDE_USB_CDC)
uint8_t hwsettings_usb_vcpport;
HwSettingsUSB_VCPPortGet(&hwsettings_usb_vcpport);
if (PIOS_USB_DESC_HID_CDC_Init()) {
PIOS_Assert(0);
}
@ -182,21 +215,21 @@ void PIOS_BOARD_IO_Configure_USB()
PIOS_USB_Init(&pios_usb_id, PIOS_BOARD_HW_DEFS_GetUsbCfg(pios_board_info_blob.board_rev));
#if defined(PIOS_INCLUDE_USB_CDC)
switch (hwsettings_usb_vcpport) {
case HWSETTINGS_USB_VCPPORT_DISABLED:
switch (vcp_function) {
case PIOS_BOARD_IO_USB_VCP_NONE:
break;
case HWSETTINGS_USB_VCPPORT_USBTELEMETRY:
case PIOS_BOARD_IO_USB_VCP_TELEMETRY:
PIOS_BOARD_IO_VCP_Init(&pios_com_telem_usb_id, PIOS_COM_TELEM_USB_RX_BUF_LEN, PIOS_COM_TELEM_USB_TX_BUF_LEN, pios_usb_id);
break;
case HWSETTINGS_USB_VCPPORT_COMBRIDGE:
case PIOS_BOARD_IO_USB_VCP_COMBRIDGE:
PIOS_BOARD_IO_VCP_Init(&pios_com_vcp_id, PIOS_COM_BRIDGE_RX_BUF_LEN, PIOS_COM_BRIDGE_TX_BUF_LEN, pios_usb_id);
break;
case HWSETTINGS_USB_VCPPORT_DEBUGCONSOLE:
case PIOS_BOARD_IO_USB_VCP_DEBUGCONSOLE:
#if defined(PIOS_INCLUDE_DEBUG_CONSOLE)
PIOS_BOARD_IO_VCP_Init(&pios_com_debug_id, 0, PIOS_COM_BRIDGE_TX_BUF_LEN, pios_usb_id);
#endif /* PIOS_INCLUDE_DEBUG_CONSOLE */
break;
case HWSETTINGS_USB_VCPPORT_MAVLINK:
case PIOS_BOARD_IO_USB_VCP_MAVLINK:
PIOS_BOARD_IO_VCP_Init(&pios_com_mavlink_id, PIOS_COM_MAVLINK_RX_BUF_LEN, PIOS_COM_MAVLINK_TX_BUF_LEN, pios_usb_id);
break;
}
@ -205,13 +238,13 @@ void PIOS_BOARD_IO_Configure_USB()
#if defined(PIOS_INCLUDE_USB_HID)
/* Configure the usb HID port */
switch (hwsettings_usb_hidport) {
case HWSETTINGS_USB_HIDPORT_DISABLED:
switch (hid_function) {
case PIOS_BOARD_IO_USB_HID_NONE:
break;
case HWSETTINGS_USB_HIDPORT_USBTELEMETRY:
case PIOS_BOARD_IO_USB_HID_TELEMETRY:
PIOS_BOARD_IO_HID_Init(&pios_com_telem_usb_id, PIOS_COM_TELEM_USB_RX_BUF_LEN, PIOS_COM_TELEM_USB_TX_BUF_LEN, pios_usb_id);
break;
case HWSETTINGS_USB_HIDPORT_RCTRANSMITTER:
case PIOS_BOARD_IO_USB_HID_RCTX:
#if defined(PIOS_INCLUDE_USB_RCTX)
if (PIOS_USB_RCTX_Init(&pios_usb_rctx_id, &pios_usb_rctx_cfg, pios_usb_id)) {
PIOS_Assert(0);
@ -274,9 +307,11 @@ struct uart_function {
uint32_t *com_id;
uint16_t com_rx_buf_len;
uint16_t com_tx_buf_len;
#ifdef PIOS_INCLUDE_RCVR
int32_t (*rcvr_init)(uint32_t *target, const struct pios_com_driver *driver, uint32_t lower_id);
const struct pios_rcvr_driver *rcvr_driver;
ManualControlSettingsChannelGroupsOptions rcvr_group;
#endif
};
static const struct uart_function uart_function_map[] = {
@ -297,13 +332,13 @@ static const struct uart_function uart_function_map[] = {
.com_rx_buf_len = PIOS_COM_MSP_RX_BUF_LEN,
.com_tx_buf_len = PIOS_COM_MSP_TX_BUF_LEN,
},
#ifdef PIOS_INCLUDE_GPS
[PIOS_BOARD_IO_UART_GPS] = {
.com_id = &pios_com_gps_id,
.com_rx_buf_len = PIOS_COM_GPS_RX_BUF_LEN,
.com_tx_buf_len = PIOS_COM_GPS_TX_BUF_LEN,
},
#endif
[PIOS_BOARD_IO_UART_OSDHK] = {
.com_id = &pios_com_hkosd_id,
.com_rx_buf_len = PIOS_COM_HKOSD_RX_BUF_LEN,
@ -409,7 +444,9 @@ void PIOS_BOARD_IO_Configure_UART(const struct pios_usart_cfg *hw_config, PIOS_B
0, uart_function_map[function].com_tx_buf_len)) {
PIOS_Assert(0);
}
} else if (uart_function_map[function].rcvr_init) {
}
#ifdef PIOS_INCLUDE_RCVR
else if (uart_function_map[function].rcvr_init) {
uint32_t usart_id;
if (PIOS_USART_Init(&usart_id, hw_config)) {
@ -429,6 +466,7 @@ void PIOS_BOARD_IO_Configure_UART(const struct pios_usart_cfg *hw_config, PIOS_B
pios_rcvr_group_map[uart_function_map[function].rcvr_group] = rcvr_id;
}
#endif /* PIOS_INCLUDE_RCVR */
}
#ifdef PIOS_INCLUDE_PWM
@ -513,13 +551,12 @@ void PIOS_BOARD_IO_Configure_RFM22B(PIOS_BOARD_IO_RADIOAUX_Function radioaux_fun
if (is_enabled) {
if (openlrs) {
#if defined(PIOS_INCLUDE_OPENLRS_RCVR) && defined(PIOS_INCLUDE_RCVR)
uint32_t openlrs_id;
const struct pios_openlrs_cfg *openlrs_cfg = PIOS_BOARD_HW_DEFS_GetOpenLRSCfg(pios_board_info_blob.board_rev);
PIOS_OpenLRS_Init(&openlrs_id, PIOS_SPI_RFM22B_ADAPTER, 0, openlrs_cfg);
PIOS_OpenLRS_Init(&pios_openlrs_id, PIOS_SPI_RFM22B_ADAPTER, 0, openlrs_cfg);
uint32_t openlrsrcvr_id;
PIOS_OpenLRS_Rcvr_Init(&openlrsrcvr_id, openlrs_id);
PIOS_OpenLRS_Rcvr_Init(&openlrsrcvr_id, pios_openlrs_id);
uint32_t openlrsrcvr_rcvr_id;
if (PIOS_RCVR_Init(&openlrsrcvr_rcvr_id, &pios_openlrs_rcvr_driver, openlrsrcvr_id)) {
@ -529,7 +566,7 @@ void PIOS_BOARD_IO_Configure_RFM22B(PIOS_BOARD_IO_RADIOAUX_Function radioaux_fun
#endif /* PIOS_INCLUDE_OPENLRS_RCVR && PIOS_INCLUDE_RCVR */
} else {
/* Configure the RFM22B device. */
const struct pios_rfm22b_cfg *rfm22b_cfg = PIOS_BOARD_HW_DEFS_GetRfm22Cfg(pios_board_info_blob.board_rev);
const struct pios_rfm22b_cfg *rfm22b_cfg = PIOS_BOARD_HW_DEFS_GetRfm22bCfg(pios_board_info_blob.board_rev);
if (PIOS_RFM22B_Init(&pios_rfm22b_id, PIOS_SPI_RFM22B_ADAPTER, rfm22b_cfg->slave_num, rfm22b_cfg, oplinkSettings.RFBand)) {
PIOS_Assert(0);

View File

@ -42,7 +42,7 @@
# include <pios_ms5611.h>
#endif
#if defined(PIOS_INCLUDE_ADXL345)
#ifdef PIOS_INCLUDE_ADXL345
# include <pios_adxl345.h>
#endif
@ -51,13 +51,21 @@
# include <pios_mpu9250_config.h>
#endif
#if defined(PIOS_INCLUDE_HMC5X83)
#ifdef PIOS_INCLUDE_HMC5X83
# include "pios_hmc5x83.h"
# if defined(PIOS_HMC5X83_HAS_GPIOS)
# ifdef PIOS_HMC5X83_HAS_GPIOS
pios_hmc5x83_dev_t pios_hmc5x83_internal_id;
# endif
#endif
#ifdef PIOS_INCLUDE_L3GD20
# include "pios_l3gd20.h"
#endif
#ifdef PIOS_INCLUDE_BMA180
# include "pios_bma180.h"
#endif
#ifdef PIOS_INCLUDE_ADC
# include "pios_adc_priv.h"
#endif
@ -75,10 +83,6 @@ void PIOS_BOARD_Sensors_Configure()
}
#endif /* PIOS_INCLUDE_MPU6000 */
#ifdef PIOS_INCLUDE_ADXL345
PIOS_ADXL345_Init(PIOS_SPI_ADXL345_ADAPTER, 0);
#endif
#ifdef PIOS_INCLUDE_MPU9250
const struct pios_mpu9250_cfg *mpu9250_cfg = PIOS_BOARD_HW_DEFS_GetMPU9250Cfg(pios_board_info_blob.board_rev);
if (mpu9250_cfg) {
@ -89,6 +93,27 @@ void PIOS_BOARD_Sensors_Configure()
}
#endif /* PIOS_INCLUDE_MPU9250 */
#ifdef PIOS_INCLUDE_ADXL345
if (PIOS_BOARD_HW_DEFS_GetADXL345Cfg(pios_board_info_blob.board_rev)) {
PIOS_ADXL345_Init(PIOS_SPI_ADXL345_ADAPTER, 0);
}
#endif
#if defined(PIOS_INCLUDE_L3GD20)
const struct pios_l3gd20_cfg *l3gd20_cfg = PIOS_BOARD_HW_DEFS_GetL3GD20Cfg(pios_board_info_blob.board_rev);
if (l3gd20_cfg) {
PIOS_Assert(0); // L3gd20 has not been ported to Sensor framework!!!
PIOS_L3GD20_Init(PIOS_SPI_L3GD20_ADAPTER, 0, l3gd20_cfg);
PIOS_Assert(PIOS_L3GD20_Test() == 0);
}
#endif
#if defined(PIOS_INCLUDE_BMA180)
const struct pios_bma180_cfg *bma180_cfg = PIOS_BOARD_HW_DEFS_GetBMA180Cfg(pios_board_info_blob.board_rev);
if (bma180_cfg) {
PIOS_Assert(0); // BMA180 has not been ported to Sensor framework!!!
PIOS_BMA180_Init(PIOS_SPI_BMA180_ADAPTER, 0, bma180_cfg);
PIOS_Assert(PIOS_BMA180_Test() == 0);
}
#endif
// internal HMC5x83 mag
# ifdef PIOS_INCLUDE_HMC5X83_INTERNAL

View File

@ -33,7 +33,7 @@ const struct pios_gpio_cfg *PIOS_BOARD_HW_DEFS_GetLedCfg(uint32_t board_revision
const struct pios_usb_cfg *PIOS_BOARD_HW_DEFS_GetUsbCfg(uint32_t board_revision);
#endif
#ifdef PIOS_INCLUDE_RFM22B
const struct pios_rfm22b_cfg *PIOS_BOARD_HW_DEFS_GetRfm22Cfg(uint32_t board_revision);
const struct pios_rfm22b_cfg *PIOS_BOARD_HW_DEFS_GetRfm22bCfg(uint32_t board_revision);
#endif
#ifdef PIOS_INCLUDE_OPENLRS
const struct pios_openlrs_cfg *PIOS_BOARD_HW_DEFS_GetOpenLRSCfg(uint32_t board_revision);
@ -59,4 +59,13 @@ const struct pios_mpu6000_cfg *PIOS_BOARD_HW_DEFS_GetMPU6000Cfg(uint32_t board_r
#ifdef PIOS_INCLUDE_MPU9250
const struct pios_mpu9250_cfg *PIOS_BOARD_HW_DEFS_GetMPU9250Cfg(uint32_t board_revision);
#endif
#ifdef PIOS_INCLUDE_ADXL345
bool PIOS_BOARD_HW_DEFS_GetADXL345Cfg(uint32_t board_revision);
#endif
#ifdef PIOS_INCLUDE_L3GD20
const struct pios_l3gd20_cfg *PIOS_BOARD_HW_DEFS_GetL3GD20Cfg(uint32_t board_revision);
#endif
#ifdef PIOS_INCLUDE_BMA180
const struct pios_bma180_cfg *PIOS_BOARD_HW_DEFS_GetBMA180Cfg(uint32_t board_revision);
#endif
#endif /* PIOS_BOARD_HW_H */

View File

@ -95,7 +95,6 @@ extern uint32_t pios_com_telem_rf_id;
# define PIOS_COM_TELEM_RF_TX_BUF_LEN 512
#endif
/* RFM22B telemetry */
#ifdef PIOS_INCLUDE_RFM22B
extern uint32_t pios_rfm22b_id; /* RFM22B handle */
@ -109,6 +108,10 @@ extern uint32_t pios_com_rf_id; /* oplink telemetry */
# endif
#endif
#ifdef PIOS_INCLUDE_OPENLRS
extern uint32_t pios_openlrs_id; /* openlrs handle */
#endif
/* HK OSD ?? */
extern uint32_t pios_com_hkosd_id;
@ -175,7 +178,7 @@ extern pios_hmc5x83_dev_t pios_hmc5x83_internal_id;
#endif
typedef enum {
PIOS_BOARD_IO_UART_NONE,
PIOS_BOARD_IO_UART_NONE = 0,
PIOS_BOARD_IO_UART_TELEMETRY, /* com */
PIOS_BOARD_IO_UART_MAVLINK, /* com */
PIOS_BOARD_IO_UART_MSP, /* com */
@ -197,7 +200,7 @@ typedef enum {
} PIOS_BOARD_IO_UART_Function;
typedef enum {
PIOS_BOARD_IO_RADIOAUX_NONE,
PIOS_BOARD_IO_RADIOAUX_NONE = 0,
PIOS_BOARD_IO_RADIOAUX_MAVLINK,
PIOS_BOARD_IO_RADIOAUX_COMBRIDGE,
PIOS_BOARD_IO_RADIOAUX_DEBUGCONSOLE,
@ -206,11 +209,23 @@ typedef enum {
#ifdef PIOS_INCLUDE_USB
void PIOS_BOARD_IO_Configure_USB();
// # if defined(PIOS_INCLUDE_USB_HID)
// # include <pios_usb_hid_priv.h>
// extern const struct pios_usb_hid_cfg pios_usb_hid_cfg;
// # endif /* PIOS_INCLUDE_USB_HID */
#endif /* PIOS_INCLUDE_USB */
typedef enum {
PIOS_BOARD_IO_USB_HID_NONE = 0,
PIOS_BOARD_IO_USB_HID_TELEMETRY,
PIOS_BOARD_IO_USB_HID_RCTX,
} PIOS_BOARD_IO_USB_HID_Function;
typedef enum {
PIOS_BOARD_IO_USB_VCP_NONE = 0,
PIOS_BOARD_IO_USB_VCP_TELEMETRY,
PIOS_BOARD_IO_USB_VCP_COMBRIDGE,
PIOS_BOARD_IO_USB_VCP_DEBUGCONSOLE,
PIOS_BOARD_IO_USB_VCP_MAVLINK,
} PIOS_BOARD_IO_USB_VCP_Function;
void PIOS_BOARD_IO_Configure_USB_Function(PIOS_BOARD_IO_USB_HID_Function hid_function, PIOS_BOARD_IO_USB_VCP_Function vcp_function);
#endif
#ifdef PIOS_INCLUDE_PWM
void PIOS_BOARD_IO_Configure_PWM(const struct pios_pwm_cfg *pwm_cfg);
#endif

View File

@ -486,9 +486,9 @@ void PIOS_ADC_handler()
PIOS_ADC_DMA_Handler();
}
const struct pios_adc_cfg *PIOS_BOARD_HW_DEFS_GetAdcCfg(__attribute__((unused)) uint32_t board_revision)
const struct pios_adc_cfg *PIOS_BOARD_HW_DEFS_GetAdcCfg(uint32_t board_revision)
{
return &pios_adc_cfg;
return (board_revision == BOARD_REVISION_CC) ? &pios_adc_cfg : 0;
}
#endif /* if defined(PIOS_INCLUDE_ADC) */
@ -1044,6 +1044,13 @@ static const struct pios_mpu6000_cfg pios_mpu6000_cfg = {
const struct pios_mpu6000_cfg *PIOS_BOARD_HW_DEFS_GetMPU6000Cfg(__attribute__((unused)) uint32_t board_revision)
{
return &pios_mpu6000_cfg;
return (board_revision == BOARD_REVISION_CC3D) ? &pios_mpu6000_cfg : 0;
}
#endif /* PIOS_INCLUDE_MPU6000 */
#ifdef PIOS_INCLUDE_ADXL345
bool PIOS_BOARD_HW_DEFS_GetADXL345Cfg(uint32_t board_revision)
{
return board_revision == BOARD_REVISION_CC;
}
#endif

View File

@ -49,13 +49,6 @@ uint32_t pios_com_telem_usb_id;
*/
static bool board_init_complete = false;
#if defined(PIOS_INCLUDE_USART)
static int32_t PIOS_BOARD_USART_Ioctl(__attribute__((unused)) uint32_t usart_id, __attribute__((unused)) uint32_t ctl, __attribute__((unused)) void *param)
{
return -1;
}
#endif
void PIOS_Board_Init(void)
{
if (board_init_complete) {

View File

@ -537,7 +537,7 @@ const struct pios_rfm22b_cfg pios_rfm22b_rm2_cfg = {
.gpio_direction = GPIO0_TX_GPIO1_RX,
};
const struct pios_rfm22b_cfg *PIOS_BOARD_HW_DEFS_GetRfm22Cfg(uint32_t board_revision)
const struct pios_rfm22b_cfg *PIOS_BOARD_HW_DEFS_GetRfm22bCfg(uint32_t board_revision)
{
switch (board_revision) {
case 2:
@ -600,6 +600,7 @@ static const struct flashfs_logfs_cfg flashfs_internal_user_cfg = {
};
#endif /* PIOS_INCLUDE_FLASH */
#ifdef PIOS_INCLUDE_USART
#include <pios_usart_priv.h>
/*
@ -708,6 +709,7 @@ static const struct pios_usart_cfg pios_usart_flexiio_cfg = {
.pin_source = GPIO_PinSource7,
}
};
#endif /* PIOS_INCLUDE_USART */
#if defined(PIOS_INCLUDE_COM)

View File

@ -40,11 +40,6 @@ 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) {

View File

@ -268,7 +268,7 @@ static const struct pios_hmc5x83_cfg pios_mag_cfg = {
static const struct pios_usart_cfg pios_usart_generic_main_cfg = {
.regs = USART1,
.remap = GPIO_AF_1,
.rx = {
.rx = {
.gpio = GPIOA,
.init = {
.GPIO_Pin = GPIO_Pin_10,

View File

@ -307,7 +307,7 @@ struct pios_rfm22b_cfg pios_rfm22b_cfg = {
};
// ! Compatibility layer for various hardware revisions
const struct pios_rfm22b_cfg *PIOS_BOARD_HW_DEFS_GetRfm22Cfg(__attribute__((unused)) uint32_t board_revision)
const struct pios_rfm22b_cfg *PIOS_BOARD_HW_DEFS_GetRfm22bCfg(__attribute__((unused)) uint32_t board_revision)
{
return &pios_rfm22b_cfg;
}
@ -795,6 +795,11 @@ static const struct pios_usb_cfg pios_usb_main_cfg = {
.vsense_active_low = false
};
const struct pios_usb_cfg *PIOS_BOARD_HW_DEFS_GetUsbCfg(__attribute__((unused)) uint32_t board_revision)
{
return &pios_usb_main_cfg;
}
#include "pios_usb_board_data_priv.h"
#include "pios_usb_desc_hid_cdc_priv.h"
#include "pios_usb_desc_hid_only_priv.h"

View File

@ -34,6 +34,7 @@
#include <fifo_buffer.h>
#include <pios_com_msg.h>
#include <pios_board_init.h>
#include <pios_board_io.h>
extern void FLASH_Download();
#define BSL_HOLD_STATE ((PIOS_USB_DETECT_GPIO_PORT->IDR & PIOS_USB_DETECT_GPIO_PIN) ? 0 : 1)

View File

@ -76,7 +76,7 @@ void PIOS_Board_Init(void)
}
#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)) {

View File

@ -159,12 +159,13 @@ extern uint32_t pios_i2c_flexi_adapter_id;
// PIOS_SPI
// See also pios_board.c
// ------------------------
#define PIOS_SPI_MAX_DEVS 1
#define PIOS_SPI_MAX_DEVS 1
#define PIOS_SPI_RFM22B_ADAPTER (pios_spi_rfm22b_id)
// -------------------------
// PIOS_USART
// -------------------------
#define PIOS_USART_MAX_DEVS 3
#define PIOS_USART_MAX_DEVS 3
// -------------------------
// PIOS_COM

View File

@ -233,24 +233,7 @@ void PIOS_SPI_sdcard_irq_handler(void)
static const struct pios_usart_cfg pios_usart_gps_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_LOW,
.NVIC_IRQChannelSubPriority = 0,
.NVIC_IRQChannelCmd = ENABLE,
},
},
.rx = {
.rx = {
.gpio = GPIOA,
.init = {
.GPIO_Pin = GPIO_Pin_10,
@ -260,7 +243,7 @@ static const struct pios_usart_cfg pios_usart_gps_cfg = {
.GPIO_PuPd = GPIO_PuPd_UP
},
},
.tx = {
.tx = {
.gpio = GPIOA,
.init = {
.GPIO_Pin = GPIO_Pin_9,
@ -280,24 +263,7 @@ static const struct pios_usart_cfg pios_usart_gps_cfg = {
static const struct pios_usart_cfg pios_usart_aux_cfg = {
.regs = USART2,
.remap = GPIO_AF_USART2,
.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 = USART2_IRQn,
.NVIC_IRQChannelPreemptionPriority = PIOS_IRQ_PRIO_MID,
.NVIC_IRQChannelSubPriority = 0,
.NVIC_IRQChannelCmd = ENABLE,
},
},
.rx = {
.rx = {
.gpio = GPIOA,
.init = {
.GPIO_Pin = GPIO_Pin_3,
@ -307,7 +273,7 @@ static const struct pios_usart_cfg pios_usart_aux_cfg = {
.GPIO_PuPd = GPIO_PuPd_UP
},
},
.tx = {
.tx = {
.gpio = GPIOA,
.init = {
.GPIO_Pin = GPIO_Pin_2,
@ -328,24 +294,7 @@ static const struct pios_usart_cfg pios_usart_aux_cfg = {
static const struct pios_usart_cfg pios_usart_telem_main_cfg = {
.regs = UART4,
.remap = GPIO_AF_UART4,
.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 = UART4_IRQn,
.NVIC_IRQChannelPreemptionPriority = PIOS_IRQ_PRIO_MID,
.NVIC_IRQChannelSubPriority = 0,
.NVIC_IRQChannelCmd = ENABLE,
},
},
.rx = {
.rx = {
.gpio = GPIOA,
.init = {
.GPIO_Pin = GPIO_Pin_1,
@ -355,7 +304,7 @@ static const struct pios_usart_cfg pios_usart_telem_main_cfg = {
.GPIO_PuPd = GPIO_PuPd_UP
},
},
.tx = {
.tx = {
.gpio = GPIOA,
.init = {
.GPIO_Pin = GPIO_Pin_0,
@ -509,41 +458,12 @@ static const struct pios_usb_cfg pios_usb_main_cfg = {
.vsense_active_low = false
};
#include "pios_usb_board_data_priv.h"
#include "pios_usb_desc_hid_cdc_priv.h"
#include "pios_usb_desc_hid_only_priv.h"
#include "pios_usbhook.h"
const struct pios_usb_cfg *PIOS_BOARD_HW_DEFS_GetUsbCfg(__attribute__((unused)) uint32_t board_revision)
{
return &pios_usb_main_cfg;
}
#endif /* PIOS_INCLUDE_USB */
#if defined(PIOS_INCLUDE_COM_MSG)
#include <pios_com_msg_priv.h>
#endif /* PIOS_INCLUDE_COM_MSG */
#if defined(PIOS_INCLUDE_USB_HID)
#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 */
#if 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,
};
#endif /* PIOS_INCLUDE_USB_CDC */
#if defined(PIOS_INCLUDE_VIDEO)

View File

@ -26,6 +26,15 @@
#include <pios.h>
#include <pios_board_info.h>
#include "pios_usb_board_data_priv.h"
#include "pios_usb_desc_hid_cdc_priv.h"
#include "pios_usb_desc_hid_only_priv.h"
#include "pios_usbhook.h"
#include <pios_com_msg_priv.h>
/*
* Pull in the board-specific static HW definitions.
* Including .c files is a bit ugly but this allows all of
@ -64,7 +73,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)) {

View File

@ -31,6 +31,8 @@
#include <gcsreceiver.h>
#include <taskinfo.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
@ -84,25 +86,10 @@ void PIOS_ADC_DMC_irq_handler(void)
static void Clock(uint32_t spektrum_id);
#define PIOS_COM_TELEM_RF_RX_BUF_LEN 128
#define PIOS_COM_TELEM_RF_TX_BUF_LEN 128
#define PIOS_COM_AUX_RX_BUF_LEN 512
#define PIOS_COM_AUX_TX_BUF_LEN 512
#define PIOS_COM_GPS_RX_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_AUX_RX_BUF_LEN 512
#define PIOS_COM_AUX_TX_BUF_LEN 512
uint32_t pios_com_aux_id;
uint32_t pios_com_gps_id;
uint32_t pios_com_telem_usb_id;
uint32_t pios_com_telem_rf_id;
uintptr_t pios_uavo_settings_fs_id;
uintptr_t pios_user_fs_id = 0;
@ -216,125 +203,9 @@ void PIOS_Board_Init(void)
#endif
#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;
PIOS_BOARD_IO_Configure_USB();
#endif
uint32_t pios_usb_id;
PIOS_USB_Init(&pios_usb_id, &pios_usb_main_cfg);
#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;
}
switch (hwsettings_usb_vcpport) {
case HWSETTINGS_USB_VCPPORT_DISABLED:
break;
case HWSETTINGS_USB_VCPPORT_USBTELEMETRY:
#if defined(PIOS_INCLUDE_COM)
{
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);
}
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)
{
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);
}
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;
}
#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)
{
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);
}
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 */
#if defined(PIOS_INCLUDE_COM)
#if defined(PIOS_INCLUDE_GPS)

View File

@ -657,7 +657,7 @@ const struct pios_rfm22b_cfg pios_rfm22b_rm2_cfg = {
.gpio_direction = GPIO0_TX_GPIO1_RX,
};
const struct pios_rfm22b_cfg *PIOS_BOARD_HW_DEFS_GetRfm22Cfg(uint32_t board_revision)
const struct pios_rfm22b_cfg *PIOS_BOARD_HW_DEFS_GetRfm22bCfg(uint32_t board_revision)
{
switch (board_revision) {
case 2:
@ -787,6 +787,7 @@ static const struct flashfs_logfs_cfg flashfs_internal_cfg = {
#endif /* PIOS_INCLUDE_FLASH */
#ifdef PIOS_INCLUDE_USART
#include <pios_usart_priv.h>
/*
@ -896,6 +897,7 @@ static const struct pios_usart_cfg pios_usart_flexiio_cfg = {
.pin_source = GPIO_PinSource7,
}
};
#endif /* PIOS_INCLUDE_USART */
#if defined(PIOS_INCLUDE_COM)
@ -1447,20 +1449,8 @@ const struct pios_usb_cfg *PIOS_BOARD_HW_DEFS_GetUsbCfg(uint32_t board_revision)
}
return NULL;
}
#include "pios_usb_board_data_priv.h"
#include "pios_usb_desc_hid_cdc_priv.h"
#include "pios_usb_desc_hid_only_priv.h"
#include "pios_usbhook.h"
#endif /* PIOS_INCLUDE_USB */
#if defined(PIOS_INCLUDE_COM_MSG)
#include <pios_com_msg_priv.h>
#endif /* PIOS_INCLUDE_COM_MSG */
#ifdef PIOS_INCLUDE_WS2811
#include <pios_ws2811_cfg.h>
#include <hwsettings.h>

View File

@ -27,6 +27,14 @@
#include <pios_board_info.h>
#include <pios_board_io.h>
#include "pios_usb_board_data_priv.h"
#include "pios_usb_desc_hid_cdc_priv.h"
#include "pios_usb_desc_hid_only_priv.h"
#include "pios_usbhook.h"
#include <pios_com_msg_priv.h>
/*
* Pull in the board-specific static HW definitions.
* Including .c files is a bit ugly but this allows all of
@ -41,11 +49,6 @@ 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) {

View File

@ -238,6 +238,7 @@ void PIOS_SPI_gyro_irq_handler(void)
#endif /* PIOS_INCLUDE_SPI */
#ifdef PIOS_INCLUDE_USART
#include <pios_usart_priv.h>
/*
@ -308,6 +309,7 @@ static const struct pios_usart_cfg pios_usart_flexi_cfg = {
// },
// },
};
#endif /* PIOS_INCLUDE_USART */
#if defined(PIOS_INCLUDE_COM)

View File

@ -41,11 +41,6 @@ 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) {

View File

@ -195,7 +195,7 @@ static const struct pios_spi_cfg pios_spi_accel_cfg = {
}
};
static uint32_t pios_spi_accel_id;
uint32_t pios_spi_accel_id;
void PIOS_SPI_accel_irq_handler(void)
{
/* Call into the generic code to handle the IRQ for this specific device */
@ -612,7 +612,6 @@ void PIOS_OVERO_irq_handler(void)
#endif /* PIOS_OVERO_SPI */
#include <pios_usart_priv.h>
#ifdef PIOS_INCLUDE_COM_TELEM
@ -622,24 +621,7 @@ void PIOS_OVERO_irq_handler(void)
static const struct pios_usart_cfg pios_usart_telem_cfg = {
.regs = USART2,
.remap = GPIO_AF_USART2,
.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 = USART2_IRQn,
.NVIC_IRQChannelPreemptionPriority = PIOS_IRQ_PRIO_MID,
.NVIC_IRQChannelSubPriority = 0,
.NVIC_IRQChannelCmd = ENABLE,
},
},
.rx = {
.rx = {
.gpio = GPIOD,
.init = {
.GPIO_Pin = GPIO_Pin_6,
@ -649,7 +631,7 @@ static const struct pios_usart_cfg pios_usart_telem_cfg = {
.GPIO_PuPd = GPIO_PuPd_UP
},
},
.tx = {
.tx = {
.gpio = GPIOD,
.init = {
.GPIO_Pin = GPIO_Pin_5,
@ -670,24 +652,7 @@ static const struct pios_usart_cfg pios_usart_telem_cfg = {
static const struct pios_usart_cfg pios_usart_gps_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 = {
.rx = {
.gpio = GPIOA,
.init = {
.GPIO_Pin = GPIO_Pin_10,
@ -697,7 +662,7 @@ static const struct pios_usart_cfg pios_usart_gps_cfg = {
.GPIO_PuPd = GPIO_PuPd_UP
},
},
.tx = {
.tx = {
.gpio = GPIOA,
.init = {
.GPIO_Pin = GPIO_Pin_9,
@ -718,24 +683,7 @@ static const struct pios_usart_cfg pios_usart_gps_cfg = {
static const struct pios_usart_cfg pios_usart_aux_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,
},
},
.rx = {
.rx = {
.gpio = GPIOC,
.init = {
.GPIO_Pin = GPIO_Pin_7,
@ -745,7 +693,7 @@ static const struct pios_usart_cfg pios_usart_aux_cfg = {
.GPIO_PuPd = GPIO_PuPd_UP
},
},
.tx = {
.tx = {
.gpio = GPIOC,
.init = {
.GPIO_Pin = GPIO_Pin_6,
@ -763,27 +711,19 @@ static const struct pios_usart_cfg pios_usart_aux_cfg = {
/*
* AUX USART SBUS ( UART/ S Bus label on rev2)
*/
// Inverter for SBUS handling
#define MAIN_USART_INVERTER_GPIO GPIOC
#define MAIN_USART_INVERTER_PIN GPIO_Pin_3
#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_auxsbus_cfg = {
.regs = UART4,
.remap = GPIO_AF_UART4,
.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 = UART4_IRQn,
.NVIC_IRQChannelPreemptionPriority = PIOS_IRQ_PRIO_MID,
.NVIC_IRQChannelSubPriority = 0,
.NVIC_IRQChannelCmd = ENABLE,
},
},
.rx = {
.rx = {
.gpio = GPIOA,
.init = {
.GPIO_Pin = GPIO_Pin_1,
@ -793,7 +733,7 @@ static const struct pios_usart_cfg pios_usart_auxsbus_cfg = {
.GPIO_PuPd = GPIO_PuPd_UP
},
},
.tx = {
.tx = {
.gpio = GPIOA,
.init = {
.GPIO_Pin = GPIO_Pin_0,
@ -803,6 +743,7 @@ static const struct pios_usart_cfg pios_usart_auxsbus_cfg = {
.GPIO_PuPd = GPIO_PuPd_UP
},
},
.ioctl = PIOS_BOARD_USART_Ioctl,
};
#endif /* PIOS_INCLUDE_COM_AUXSBUS */
@ -814,24 +755,7 @@ static const struct pios_usart_cfg pios_usart_auxsbus_cfg = {
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 = {
.rx = {
.gpio = GPIOB,
.init = {
.GPIO_Pin = GPIO_Pin_10,
@ -841,7 +765,7 @@ static const struct pios_usart_cfg pios_usart_flexi_cfg = {
.GPIO_PuPd = GPIO_PuPd_UP
},
},
.tx = {
.tx = {
.gpio = GPIOB,
.init = {
.GPIO_Pin = GPIO_Pin_11,
@ -855,327 +779,6 @@ static const struct pios_usart_cfg pios_usart_flexi_cfg = {
#endif /* PIOS_INCLUDE_COM_FLEXI */
#if defined(PIOS_INCLUDE_DSM)
/*
* Spektrum/JR DSM USART
*/
#include <pios_dsm_priv.h>
static const struct pios_usart_cfg pios_usart_dsm_aux_cfg = {
.regs = USART6,
.remap = GPIO_AF_USART6,
.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 = USART6_IRQn,
.NVIC_IRQChannelPreemptionPriority = PIOS_IRQ_PRIO_HIGH,
.NVIC_IRQChannelSubPriority = 0,
.NVIC_IRQChannelCmd = ENABLE,
},
},
.rx = {
.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
},
},
.tx = {
.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
},
},
};
static const struct pios_dsm_cfg pios_dsm_aux_cfg = {
.bind = {
.gpio = GPIOC,
.init = {
.GPIO_Pin = GPIO_Pin_7,
.GPIO_Speed = GPIO_Speed_2MHz,
.GPIO_Mode = GPIO_Mode_OUT,
.GPIO_OType = GPIO_OType_PP,
.GPIO_PuPd = GPIO_PuPd_NOPULL
},
},
};
static const struct pios_usart_cfg pios_usart_dsm_auxsbus_cfg = {
.regs = UART4,
.remap = GPIO_AF_UART4,
.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 = UART4_IRQn,
.NVIC_IRQChannelPreemptionPriority = PIOS_IRQ_PRIO_MID,
.NVIC_IRQChannelSubPriority = 0,
.NVIC_IRQChannelCmd = ENABLE,
},
},
.rx = {
.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
},
},
.tx = {
.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
},
},
};
static const struct pios_dsm_cfg pios_dsm_auxsbus_cfg = {
.bind = {
.gpio = GPIOA,
.init = {
.GPIO_Pin = GPIO_Pin_1,
.GPIO_Speed = GPIO_Speed_2MHz,
.GPIO_Mode = GPIO_Mode_OUT,
.GPIO_OType = GPIO_OType_PP,
.GPIO_PuPd = GPIO_PuPd_NOPULL
},
},
};
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 */
#if defined(PIOS_INCLUDE_SBUS)
/*
* S.Bus USART
*/
#include <pios_sbus_priv.h>
static const struct pios_usart_cfg pios_usart_sbus_auxsbus_cfg = {
.regs = UART4,
.remap = GPIO_AF_UART4,
.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 = UART4_IRQn,
.NVIC_IRQChannelPreemptionPriority = PIOS_IRQ_PRIO_HIGH,
.NVIC_IRQChannelSubPriority = 0,
.NVIC_IRQChannelCmd = ENABLE,
},
},
.rx = {
.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
},
},
.tx = {
.gpio = GPIOA,
.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_NOPULL
},
},
};
static const struct pios_sbus_cfg pios_sbus_cfg = {
/* Inverter configuration */
.inv = {
.gpio = GPIOC,
.init = {
.GPIO_Pin = GPIO_Pin_3,
.GPIO_Mode = GPIO_Mode_OUT,
.GPIO_OType = GPIO_OType_PP,
.GPIO_Speed = GPIO_Speed_2MHz,
},
},
.gpio_inv_enable = Bit_SET,
.gpio_inv_disable = Bit_RESET,
.gpio_clk_func = RCC_AHB1PeriphClockCmd,
.gpio_clk_periph = RCC_AHB1Periph_GPIOC,
};
#endif /* PIOS_INCLUDE_SBUS */
/*
* HK OSD
*/
static const struct pios_usart_cfg pios_usart_hkosd_auxsbus_cfg = {
.regs = UART4,
.remap = GPIO_AF_UART4,
.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 = UART4_IRQn,
.NVIC_IRQChannelPreemptionPriority = PIOS_IRQ_PRIO_MID,
.NVIC_IRQChannelSubPriority = 0,
.NVIC_IRQChannelCmd = ENABLE,
},
},
.rx = {
.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
},
},
.tx = {
.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
},
},
};
static const struct pios_usart_cfg pios_usart_hkosd_aux_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,
},
},
.rx = {
.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
},
},
.tx = {
.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
},
},
};
#if defined(PIOS_INCLUDE_COM)
#include <pios_com_priv.h>
@ -2031,47 +1634,297 @@ static const struct pios_usb_cfg pios_usb_main_cfg = {
},
.vsense_active_low = false
};
#include "pios_usb_board_data_priv.h"
#include "pios_usb_desc_hid_cdc_priv.h"
#include "pios_usb_desc_hid_only_priv.h"
#include "pios_usbhook.h"
const struct pios_usb_cfg *PIOS_BOARD_HW_DEFS_GetUsbCfg(__attribute__((unused)) uint32_t board_revision)
{
return &pios_usb_main_cfg;
}
#endif /* PIOS_INCLUDE_USB */
#if defined(PIOS_INCLUDE_COM_MSG)
#include <pios_com_msg_priv.h>
/**
* Sensor configurations
*/
#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,
#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,
};
#endif /* PIOS_INCLUDE_USB_HID && !PIOS_INCLUDE_USB_CDC */
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_USB_HID) && defined(PIOS_INCLUDE_USB_CDC)
#include <pios_usb_cdc_priv.h>
#if defined(PIOS_INCLUDE_HMC5X83)
#include "pios_hmc5x83.h"
const struct pios_usb_cdc_cfg pios_usb_cdc_cfg = {
.ctrl_if = 1,
.ctrl_tx_ep = 2,
#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_Line5,
.pin = {
.gpio = GPIOB,
.init = {
.GPIO_Pin = GPIO_Pin_5,
.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_Line5, // matches above GPIO pin
.EXTI_Mode = EXTI_Mode_Interrupt,
.EXTI_Trigger = EXTI_Trigger_Rising,
.EXTI_LineCmd = ENABLE,
},
},
};
#endif /* PIOS_HMC5X83_HAS_GPIOS */
.data_if = 2,
.data_rx_ep = 3,
.data_tx_ep = 3,
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,
};
#include <pios_usb_hid_priv.h>
const struct pios_hmc5x83_cfg *PIOS_BOARD_HW_DEFS_GetInternalHMC5x83Cfg(__attribute__((unused)) uint32_t board_revision)
{
return &pios_hmc5x83_internal_cfg;
}
const struct pios_usb_hid_cfg pios_usb_hid_cfg = {
.data_if = 2,
.data_rx_ep = 1,
.data_tx_ep = 1,
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,
};
#endif /* PIOS_INCLUDE_USB_HID && PIOS_INCLUDE_USB_CDC */
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_4096,
};
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 BMA180 chip
*/
#if defined(PIOS_INCLUDE_BMA180)
#include "pios_bma180.h"
static const struct pios_exti_cfg pios_exti_bma180_cfg __exti_config = {
.vector = PIOS_BMA180_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_LOW,
.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_bma180_cfg pios_bma180_cfg = {
.exti_cfg = &pios_exti_bma180_cfg,
.bandwidth = BMA_BW_600HZ,
.range = BMA_RANGE_8G,
};
const struct pios_bma180_cfg *PIOS_BOARD_HW_DEFS_GetBMA180Cfg(uint32_t board_revision)
{
return (board_revision == 0x01) ? &pios_bma180_cfg : 0;
}
#endif /* PIOS_INCLUDE_BMA180 */
/**
* Configuration for the MPU6000 chip
*/
#if defined(PIOS_INCLUDE_MPU6000)
#include "pios_mpu6000.h"
static const struct pios_exti_cfg pios_exti_mpu6000_cfg __exti_config = {
.vector = PIOS_MPU6000_IRQHandler,
.line = EXTI_Line8,
.pin = {
.gpio = GPIOD,
.init = {
.GPIO_Pin = GPIO_Pin_8,
.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_HIGH,
.NVIC_IRQChannelSubPriority = 0,
.NVIC_IRQChannelCmd = ENABLE,
},
},
.exti = {
.init = {
.EXTI_Line = EXTI_Line8, // 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
.Smpl_rate_div_no_dlp = 0,
// with dlp on output rate is 1000Hz
.Smpl_rate_div_dlp = 0,
.interrupt_cfg = PIOS_MPU6000_INT_CLR_ANYRD,
.interrupt_en = PIOS_MPU6000_INTEN_DATA_RDY,
.User_ctl = 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_0DEG,
.fast_prescaler = PIOS_SPI_PRESCALER_4,
.std_prescaler = PIOS_SPI_PRESCALER_64,
.max_downsample = 16,
};
const struct pios_mpu6000_cfg *PIOS_BOARD_HW_DEFS_GetMPU6000Cfg(uint32_t board_revision)
{
return (board_revision == 0x02) ? &pios_mpu6000_cfg : 0;
}
#endif /* PIOS_INCLUDE_MPU6000 */
/**
* Configuration for L3GD20 chip
*/
#if defined(PIOS_INCLUDE_L3GD20)
#include "pios_l3gd20.h"
static const struct pios_exti_cfg pios_exti_l3gd20_cfg __exti_config = {
.vector = PIOS_L3GD20_IRQHandler,
.line = EXTI_Line8,
.pin = {
.gpio = GPIOD,
.init = {
.GPIO_Pin = GPIO_Pin_8,
.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_HIGH,
.NVIC_IRQChannelSubPriority = 0,
.NVIC_IRQChannelCmd = ENABLE,
},
},
.exti = {
.init = {
.EXTI_Line = EXTI_Line8, // matches above GPIO pin
.EXTI_Mode = EXTI_Mode_Interrupt,
.EXTI_Trigger = EXTI_Trigger_Rising,
.EXTI_LineCmd = ENABLE,
},
},
};
static const struct pios_l3gd20_cfg pios_l3gd20_cfg = {
.exti_cfg = &pios_exti_l3gd20_cfg,
.range = PIOS_L3GD20_SCALE_500_DEG,
};
const struct pios_l3gd20_cfg *PIOS_BOARD_HW_DEFS_GetL3GD20Cfg(uint32_t board_revision)
{
return (board_revision == 0x01) ? &pios_l3gd20_cfg : 0;
}
#endif /* PIOS_INCLUDE_L3GD20 */

View File

@ -35,6 +35,7 @@
#include <pios_usbhook.h> /* PIOS_USBHOOK_* */
#include <stdbool.h>
#include <pios_board_init.h>
#include <pios_board_io.h>
extern void FLASH_Download();
void check_bor();

View File

@ -26,6 +26,13 @@
#include <pios.h>
#include <pios_board_info.h>
#include "pios_usb_board_data_priv.h"
#include "pios_usb_desc_hid_cdc_priv.h"
#include "pios_usb_desc_hid_only_priv.h"
#include "pios_usbhook.h"
#include <pios_com_msg_priv.h>
/*
* Pull in the board-specific static HW definitions.
* Including .c files is a bit ugly but this allows all of
@ -64,7 +71,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)) {

View File

@ -31,7 +31,9 @@
#include <hwsettings.h>
#include <manualcontrolsettings.h>
#include <taskinfo.h>
#include <auxmagsettings.h>
#include <pios_board_io.h>
#include <pios_board_sensors.h>
/*
* Pull in the board-specific static HW definitions.
@ -43,365 +45,9 @@
*/
#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;
#ifdef PIOS_HMC5X83_HAS_GPIOS
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_Line5,
.pin = {
.gpio = GPIOB,
.init = {
.GPIO_Pin = GPIO_Pin_5,
.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_Line5, // 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,
};
#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_4096,
};
#endif /* PIOS_INCLUDE_MS5611 */
/**
* Configuration for the BMA180 chip
*/
#if defined(PIOS_INCLUDE_BMA180)
#include "pios_bma180.h"
static const struct pios_exti_cfg pios_exti_bma180_cfg __exti_config = {
.vector = PIOS_BMA180_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_LOW,
.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_bma180_cfg pios_bma180_cfg = {
.exti_cfg = &pios_exti_bma180_cfg,
.bandwidth = BMA_BW_600HZ,
.range = BMA_RANGE_8G,
};
#endif /* PIOS_INCLUDE_BMA180 */
/**
* 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_Line8,
.pin = {
.gpio = GPIOD,
.init = {
.GPIO_Pin = GPIO_Pin_8,
.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_HIGH,
.NVIC_IRQChannelSubPriority = 0,
.NVIC_IRQChannelCmd = ENABLE,
},
},
.exti = {
.init = {
.EXTI_Line = EXTI_Line8, // 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
.Smpl_rate_div_no_dlp = 0,
// with dlp on output rate is 1000Hz
.Smpl_rate_div_dlp = 0,
.interrupt_cfg = PIOS_MPU6000_INT_CLR_ANYRD,
.interrupt_en = PIOS_MPU6000_INTEN_DATA_RDY,
.User_ctl = 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_0DEG,
.fast_prescaler = PIOS_SPI_PRESCALER_4,
.std_prescaler = PIOS_SPI_PRESCALER_64,
.max_downsample = 16,
};
#endif /* PIOS_INCLUDE_MPU6000 */
/**
* Configuration for L3GD20 chip
*/
#if defined(PIOS_INCLUDE_L3GD20)
#include "pios_l3gd20.h"
static const struct pios_exti_cfg pios_exti_l3gd20_cfg __exti_config = {
.vector = PIOS_L3GD20_IRQHandler,
.line = EXTI_Line8,
.pin = {
.gpio = GPIOD,
.init = {
.GPIO_Pin = GPIO_Pin_8,
.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_HIGH,
.NVIC_IRQChannelSubPriority = 0,
.NVIC_IRQChannelCmd = ENABLE,
},
},
.exti = {
.init = {
.EXTI_Line = EXTI_Line8, // matches above GPIO pin
.EXTI_Mode = EXTI_Mode_Interrupt,
.EXTI_Trigger = EXTI_Trigger_Rising,
.EXTI_LineCmd = ENABLE,
},
},
};
static const struct pios_l3gd20_cfg pios_l3gd20_cfg = {
.exti_cfg = &pios_exti_l3gd20_cfg,
.range = PIOS_L3GD20_SCALE_500_DEG,
};
#endif /* PIOS_INCLUDE_L3GD20 */
/* 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 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_AUX_RX_BUF_LEN 512
#define PIOS_COM_AUX_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
uint32_t pios_com_aux_id = 0;
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;
uintptr_t pios_uavo_settings_fs_id;
uintptr_t pios_user_fs_id;
uint32_t pios_com_vcp_id = 0;
/*
* Setup a com port based on the passed cfg, driver and buffer sizes. tx size = 0 make the port rx only
*/
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)
{
uint32_t pios_usart_id;
if (PIOS_USART_Init(&pios_usart_id, usart_port_cfg)) {
PIOS_Assert(0);
}
uint8_t *rx_buffer = (uint8_t *)pios_malloc(rx_buf_len);
PIOS_Assert(rx_buffer);
if (tx_buf_len > 0) { // this is the case for rx/tx ports
uint8_t *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);
}
} else { // rx only port
if (PIOS_COM_Init(pios_com_id, com_driver, pios_usart_id,
rx_buffer, rx_buf_len,
NULL, 0)) {
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;
}
/**
* PIOS_Board_Init()
* initializes all the core subsystems on this specific hardware
@ -410,10 +56,27 @@ static void PIOS_Board_configure_dsm(const struct pios_usart_cfg *pios_usart_dsm
#include <pios_board_info.h>
int32_t PIOS_BOARD_USART_Ioctl(uint32_t usart_id, uint32_t ctl, void *param)
{
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_auxsbus_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;
}
return -1;
}
void PIOS_Board_Init(void)
{
const struct pios_board_info *bdinfo = &pios_board_info_blob;
/* Delay system */
PIOS_DELAY_Init();
@ -516,293 +179,117 @@ void PIOS_Board_Init(void)
// PIOS_IAP_Init();
/* Configure USB */
#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;
PIOS_BOARD_IO_Configure_USB();
#endif
uint32_t pios_usb_id;
PIOS_USB_Init(&pios_usb_id, &pios_usb_main_cfg);
/* 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
};
#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;
GPIO_Init(MAIN_USART_INVERTER_GPIO, &inverterGPIOInit);
GPIO_WriteBit(MAIN_USART_INVERTER_GPIO,
MAIN_USART_INVERTER_PIN,
MAIN_USART_INVERTER_DISABLE);
}
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 Telemetry port */
static const PIOS_BOARD_IO_UART_Function usart_telem_function_map[] = {
[HWSETTINGS_RV_TELEMETRYPORT_TELEMETRY] = PIOS_BOARD_IO_UART_TELEMETRY,
// [HWSETTINGS_RV_TELEMETRYPORT_COMAUX] = ?? &pios_com_aux_id // UNUSED
[HWSETTINGS_RV_TELEMETRYPORT_COMBRIDGE] = PIOS_BOARD_IO_UART_COMBRIDGE,
[HWSETTINGS_RV_TELEMETRYPORT_MSP] = PIOS_BOARD_IO_UART_MSP,
[HWSETTINGS_RV_TELEMETRYPORT_MAVLINK] = PIOS_BOARD_IO_UART_MAVLINK
};
uint8_t hwsettings_rv_telemetryport;
HwSettingsRV_TelemetryPortGet(&hwsettings_rv_telemetryport);
switch (hwsettings_rv_telemetryport) {
case HWSETTINGS_RV_TELEMETRYPORT_DISABLED:
break;
case HWSETTINGS_RV_TELEMETRYPORT_TELEMETRY:
PIOS_Board_configure_com(&pios_usart_telem_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_RV_TELEMETRYPORT_COMAUX:
PIOS_Board_configure_com(&pios_usart_telem_cfg, PIOS_COM_AUX_RX_BUF_LEN, PIOS_COM_AUX_TX_BUF_LEN, &pios_usart_com_driver, &pios_com_aux_id);
break;
case HWSETTINGS_RV_TELEMETRYPORT_COMBRIDGE:
PIOS_Board_configure_com(&pios_usart_telem_cfg, PIOS_COM_BRIDGE_RX_BUF_LEN, PIOS_COM_BRIDGE_TX_BUF_LEN, &pios_usart_com_driver, &pios_com_bridge_id);
break;
case HWSETTINGS_RV_TELEMETRYPORT_MSP:
PIOS_Board_configure_com(&pios_usart_telem_cfg, PIOS_COM_MSP_RX_BUF_LEN, PIOS_COM_MSP_TX_BUF_LEN, &pios_usart_com_driver, &pios_com_msp_id);
break;
case HWSETTINGS_RV_TELEMETRYPORT_MAVLINK:
PIOS_Board_configure_com(&pios_usart_telem_cfg, 0, PIOS_COM_MAVLINK_TX_BUF_LEN, &pios_usart_com_driver, &pios_com_mavlink_id);
break;
} /* hwsettings_rv_telemetryport */
if (hwsettings_rv_telemetryport < NELEMENTS(usart_telem_function_map)) {
PIOS_BOARD_IO_Configure_UART(&pios_usart_telem_cfg, usart_telem_function_map[hwsettings_rv_telemetryport]);
}
/* Configure GPS port */
static const PIOS_BOARD_IO_UART_Function usart_gps_function_map[] = {
[HWSETTINGS_RV_GPSPORT_TELEMETRY] = PIOS_BOARD_IO_UART_TELEMETRY,
[HWSETTINGS_RV_GPSPORT_GPS] = PIOS_BOARD_IO_UART_GPS,
// [HWSETTINGS_RV_GPSPORT_COMAUX] =
[HWSETTINGS_RV_GPSPORT_COMBRIDGE] = PIOS_BOARD_IO_UART_COMBRIDGE,
[HWSETTINGS_RV_GPSPORT_MSP] = PIOS_BOARD_IO_UART_MSP,
[HWSETTINGS_RV_GPSPORT_MAVLINK] = PIOS_BOARD_IO_UART_MAVLINK,
};
uint8_t hwsettings_rv_gpsport;
HwSettingsRV_GPSPortGet(&hwsettings_rv_gpsport);
switch (hwsettings_rv_gpsport) {
case HWSETTINGS_RV_GPSPORT_DISABLED:
break;
case HWSETTINGS_RV_GPSPORT_TELEMETRY:
PIOS_Board_configure_com(&pios_usart_gps_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_RV_GPSPORT_GPS:
PIOS_Board_configure_com(&pios_usart_gps_cfg, PIOS_COM_GPS_RX_BUF_LEN, 0, &pios_usart_com_driver, &pios_com_gps_id);
break;
case HWSETTINGS_RV_GPSPORT_COMAUX:
PIOS_Board_configure_com(&pios_usart_gps_cfg, PIOS_COM_AUX_RX_BUF_LEN, PIOS_COM_AUX_TX_BUF_LEN, &pios_usart_com_driver, &pios_com_aux_id);
break;
case HWSETTINGS_RV_GPSPORT_COMBRIDGE:
PIOS_Board_configure_com(&pios_usart_gps_cfg, PIOS_COM_BRIDGE_RX_BUF_LEN, PIOS_COM_BRIDGE_TX_BUF_LEN, &pios_usart_com_driver, &pios_com_bridge_id);
break;
case HWSETTINGS_RV_GPSPORT_MSP:
PIOS_Board_configure_com(&pios_usart_gps_cfg, PIOS_COM_MSP_RX_BUF_LEN, PIOS_COM_MSP_TX_BUF_LEN, &pios_usart_com_driver, &pios_com_msp_id);
break;
case HWSETTINGS_RV_GPSPORT_MAVLINK:
PIOS_Board_configure_com(&pios_usart_gps_cfg, 0, PIOS_COM_MAVLINK_TX_BUF_LEN, &pios_usart_com_driver, &pios_com_mavlink_id);
break;
} /* hwsettings_rv_gpsport */
if (hwsettings_rv_gpsport < NELEMENTS(usart_gps_function_map)) {
PIOS_BOARD_IO_Configure_UART(&pios_usart_gps_cfg, usart_gps_function_map[hwsettings_rv_gpsport]);
}
/* Configure AUXPort */
static const PIOS_BOARD_IO_UART_Function usart_aux_function_map[] = {
[HWSETTINGS_RV_AUXPORT_TELEMETRY] = PIOS_BOARD_IO_UART_TELEMETRY,
[HWSETTINGS_RV_AUXPORT_DSM] = PIOS_BOARD_IO_UART_DSM_MAIN,
// [HWSETTINGS_RV_AUXPORT_COMAUX] =
[HWSETTINGS_RV_AUXPORT_COMBRIDGE] = PIOS_BOARD_IO_UART_COMBRIDGE,
[HWSETTINGS_RV_AUXPORT_MSP] = PIOS_BOARD_IO_UART_MSP,
[HWSETTINGS_RV_AUXPORT_MAVLINK] = PIOS_BOARD_IO_UART_MAVLINK,
[HWSETTINGS_RV_AUXPORT_OSDHK] = PIOS_BOARD_IO_UART_OSDHK,
};
uint8_t hwsettings_rv_auxport;
HwSettingsRV_AuxPortGet(&hwsettings_rv_auxport);
switch (hwsettings_rv_auxport) {
case HWSETTINGS_RV_AUXPORT_DISABLED:
break;
if (hwsettings_rv_auxport < NELEMENTS(usart_aux_function_map)) {
PIOS_BOARD_IO_Configure_UART(&pios_usart_aux_cfg, usart_aux_function_map[hwsettings_rv_auxport]);
}
case HWSETTINGS_RV_AUXPORT_TELEMETRY:
PIOS_Board_configure_com(&pios_usart_aux_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;
/* Configure AUXSbusPort */
static const PIOS_BOARD_IO_UART_Function usart_auxsbus_function_map[] = {
[HWSETTINGS_RV_AUXSBUSPORT_SBUS] = PIOS_BOARD_IO_UART_SBUS,
[HWSETTINGS_RV_AUXSBUSPORT_DSM] = PIOS_BOARD_IO_UART_DSM_MAIN, /* MAIN group, same as usart_aux! */
// [HWSETTINGS_RV_AUXSBUSPORT_COMAUX] =
[HWSETTINGS_RV_AUXSBUSPORT_COMBRIDGE] = PIOS_BOARD_IO_UART_COMBRIDGE,
[HWSETTINGS_RV_AUXSBUSPORT_MSP] = PIOS_BOARD_IO_UART_MSP,
[HWSETTINGS_RV_AUXSBUSPORT_MAVLINK] = PIOS_BOARD_IO_UART_MAVLINK,
[HWSETTINGS_RV_AUXSBUSPORT_OSDHK] = PIOS_BOARD_IO_UART_OSDHK,
};
case HWSETTINGS_RV_AUXPORT_DSM:
// TODO: Define the various Channelgroup for Revo dsm inputs and handle here
PIOS_Board_configure_dsm(&pios_usart_dsm_aux_cfg, &pios_dsm_aux_cfg,
&pios_usart_com_driver, MANUALCONTROLSETTINGS_CHANNELGROUPS_DSMMAINPORT, &hwsettings_DSMxBind);
break;
case HWSETTINGS_RV_AUXPORT_COMAUX:
PIOS_Board_configure_com(&pios_usart_aux_cfg, PIOS_COM_AUX_RX_BUF_LEN, PIOS_COM_AUX_TX_BUF_LEN, &pios_usart_com_driver, &pios_com_aux_id);
break;
case HWSETTINGS_RV_AUXPORT_COMBRIDGE:
PIOS_Board_configure_com(&pios_usart_aux_cfg, PIOS_COM_BRIDGE_RX_BUF_LEN, PIOS_COM_BRIDGE_TX_BUF_LEN, &pios_usart_com_driver, &pios_com_bridge_id);
break;
case HWSETTINGS_RV_AUXPORT_MSP:
PIOS_Board_configure_com(&pios_usart_aux_cfg, PIOS_COM_MSP_RX_BUF_LEN, PIOS_COM_MSP_TX_BUF_LEN, &pios_usart_com_driver, &pios_com_msp_id);
break;
case HWSETTINGS_RV_AUXPORT_MAVLINK:
PIOS_Board_configure_com(&pios_usart_aux_cfg, 0, PIOS_COM_MAVLINK_TX_BUF_LEN, &pios_usart_com_driver, &pios_com_mavlink_id);
break;
case HWSETTINGS_RV_AUXPORT_OSDHK:
PIOS_Board_configure_com(&pios_usart_hkosd_aux_cfg, PIOS_COM_HKOSD_RX_BUF_LEN, PIOS_COM_HKOSD_TX_BUF_LEN, &pios_usart_com_driver, &pios_com_hkosd_id);
break;
} /* hwsettings_rv_auxport */
/* Configure AUXSbusPort */
// TODO: ensure that the serial invertion pin is setted correctly
uint8_t hwsettings_rv_auxsbusport;
HwSettingsRV_AuxSBusPortGet(&hwsettings_rv_auxsbusport);
switch (hwsettings_rv_auxsbusport) {
case HWSETTINGS_RV_AUXSBUSPORT_DISABLED:
break;
case HWSETTINGS_RV_AUXSBUSPORT_SBUS:
#ifdef PIOS_INCLUDE_SBUS
{
uint32_t pios_usart_sbus_id;
if (PIOS_USART_Init(&pios_usart_sbus_id, &pios_usart_sbus_auxsbus_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 /* PIOS_INCLUDE_SBUS */
break;
case HWSETTINGS_RV_AUXSBUSPORT_DSM:
// TODO: Define the various Channelgroup for Revo dsm inputs and handle here
PIOS_Board_configure_dsm(&pios_usart_dsm_auxsbus_cfg, &pios_dsm_auxsbus_cfg,
&pios_usart_com_driver, MANUALCONTROLSETTINGS_CHANNELGROUPS_DSMMAINPORT, &hwsettings_DSMxBind);
break;
case HWSETTINGS_RV_AUXSBUSPORT_COMAUX:
PIOS_Board_configure_com(&pios_usart_auxsbus_cfg, PIOS_COM_AUX_RX_BUF_LEN, PIOS_COM_AUX_TX_BUF_LEN, &pios_usart_com_driver, &pios_com_aux_id);
break;
case HWSETTINGS_RV_AUXSBUSPORT_COMBRIDGE:
PIOS_Board_configure_com(&pios_usart_auxsbus_cfg, PIOS_COM_BRIDGE_RX_BUF_LEN, PIOS_COM_BRIDGE_TX_BUF_LEN, &pios_usart_com_driver, &pios_com_bridge_id);
break;
case HWSETTINGS_RV_AUXSBUSPORT_MSP:
PIOS_Board_configure_com(&pios_usart_auxsbus_cfg, PIOS_COM_MSP_RX_BUF_LEN, PIOS_COM_MSP_TX_BUF_LEN, &pios_usart_com_driver, &pios_com_msp_id);
break;
case HWSETTINGS_RV_AUXSBUSPORT_MAVLINK:
PIOS_Board_configure_com(&pios_usart_auxsbus_cfg, 0, PIOS_COM_MAVLINK_TX_BUF_LEN, &pios_usart_com_driver, &pios_com_mavlink_id);
break;
case HWSETTINGS_RV_AUXSBUSPORT_OSDHK:
PIOS_Board_configure_com(&pios_usart_hkosd_auxsbus_cfg, PIOS_COM_HKOSD_RX_BUF_LEN, PIOS_COM_HKOSD_TX_BUF_LEN, &pios_usart_com_driver, &pios_com_hkosd_id);
break;
} /* hwsettings_rv_auxport */
if (hwsettings_rv_auxsbusport < NELEMENTS(usart_auxsbus_function_map)) {
PIOS_BOARD_IO_Configure_UART(&pios_usart_auxsbus_cfg, usart_auxsbus_function_map[hwsettings_rv_auxsbusport]);
}
/* Configure FlexiPort */
static const PIOS_BOARD_IO_UART_Function usart_flexi_function_map[] = {
[HWSETTINGS_RV_FLEXIPORT_DSM] = PIOS_BOARD_IO_UART_DSM_FLEXI,
// [HWSETTINGS_RV_FLEXIPORT_COMAUX] =
[HWSETTINGS_RV_FLEXIPORT_COMBRIDGE] = PIOS_BOARD_IO_UART_COMBRIDGE,
[HWSETTINGS_RV_FLEXIPORT_MSP] = PIOS_BOARD_IO_UART_MSP,
[HWSETTINGS_RV_FLEXIPORT_MAVLINK] = PIOS_BOARD_IO_UART_MAVLINK,
};
uint8_t hwsettings_rv_flexiport;
HwSettingsRV_FlexiPortGet(&hwsettings_rv_flexiport);
switch (hwsettings_rv_flexiport) {
case HWSETTINGS_RV_FLEXIPORT_DISABLED:
break;
case HWSETTINGS_RV_FLEXIPORT_I2C:
if (hwsettings_rv_flexiport < NELEMENTS(usart_flexi_function_map)) {
PIOS_BOARD_IO_Configure_UART(&pios_usart_flexi_cfg, usart_flexi_function_map[hwsettings_rv_flexiport]);
}
#if defined(PIOS_INCLUDE_I2C)
if (hwsettings_rv_flexiport == HWSETTINGS_RV_FLEXIPORT_I2C) {
if (PIOS_I2C_Init(&pios_i2c_flexiport_adapter_id, &pios_i2c_flexiport_adapter_cfg)) {
PIOS_Assert(0);
}
@ -814,47 +301,8 @@ void PIOS_Board_Init(void)
// 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
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_RV_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_DSMMAINPORT, &hwsettings_DSMxBind);
break;
case HWSETTINGS_RV_FLEXIPORT_COMAUX:
PIOS_Board_configure_com(&pios_usart_flexi_cfg, PIOS_COM_AUX_RX_BUF_LEN, PIOS_COM_AUX_TX_BUF_LEN, &pios_usart_com_driver, &pios_com_aux_id);
break;
case HWSETTINGS_RV_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_RV_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_RV_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;
} /* hwsettings_rv_flexiport */
/* Configure the receiver port*/
uint8_t hwsettings_rcvrport;
@ -865,32 +313,13 @@ void PIOS_Board_Init(void)
break;
case HWSETTINGS_RV_RCVRPORT_PWM:
#if defined(PIOS_INCLUDE_PWM)
{
/* Set up the receiver port. Later this should be optional */
uint32_t pios_pwm_id;
PIOS_PWM_Init(&pios_pwm_id, &pios_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;
}
PIOS_BOARD_IO_Configure_PWM(&pios_pwm_cfg);
#endif /* PIOS_INCLUDE_PWM */
break;
case HWSETTINGS_RV_RCVRPORT_PPM:
case HWSETTINGS_RV_RCVRPORT_PPMOUTPUTS:
#if defined(PIOS_INCLUDE_PPM)
{
uint32_t pios_ppm_id;
PIOS_PPM_Init(&pios_ppm_id, &pios_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;
}
PIOS_BOARD_IO_Configure_PPM(&pios_ppm_cfg);
#endif /* PIOS_INCLUDE_PPM */
case HWSETTINGS_RV_RCVRPORT_OUTPUTS:
@ -929,17 +358,9 @@ void PIOS_Board_Init(void)
}
#endif
#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 */
#ifdef PIOS_INCLUDE_GCSRCVR
PIOS_BOARD_IO_Configure_GCSRCVR();
#endif
#ifndef PIOS_ENABLE_DEBUG_PINS
switch (hwsettings_rcvrport) {
@ -972,69 +393,7 @@ void PIOS_Board_Init(void)
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_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_pressure_adapter_id);
PIOS_MS5611_Register();
#endif
switch (bdinfo->board_rev) {
case 0x01:
#if defined(PIOS_INCLUDE_L3GD20)
PIOS_Assert(0); // L3gd20 has not been ported to Sensor framework!!!
PIOS_L3GD20_Init(pios_spi_gyro_id, 0, &pios_l3gd20_cfg);
PIOS_Assert(PIOS_L3GD20_Test() == 0);
#endif
#if defined(PIOS_INCLUDE_BMA180)
PIOS_Assert(0); // BMA180 has not been ported to Sensor framework!!!
PIOS_BMA180_Init(pios_spi_accel_id, 0, &pios_bma180_cfg);
PIOS_Assert(PIOS_BMA180_Test() == 0);
#endif
break;
case 0x02:
#if defined(PIOS_INCLUDE_MPU6000)
PIOS_MPU6000_Init(pios_spi_gyro_id, 0, &pios_mpu6000_cfg);
PIOS_MPU6000_CONFIG_Configure();
PIOS_MPU6000_Register();
#endif
break;
default:
PIOS_DEBUG_Assert(0);
}
#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);
}
}
}
#endif // PIOS_INCLUDE_ADC
PIOS_BOARD_Sensors_Configure();
}
/**

View File

@ -81,30 +81,41 @@
// PIOS_SPI
// See also pios_board.c
// ------------------------
#define PIOS_SPI_MAX_DEVS 3
#define PIOS_SPI_MAX_DEVS 3
extern uint32_t pios_spi_gyro_id;
extern uint32_t pios_spi_accel_id;
#define PIOS_SPI_L3GD20_ADAPTER (pios_spi_gyro_id)
#define PIOS_SPI_BMA180_ADAPTER (pios_spi_accel_id)
#define PIOS_SPI_MPU6000_ADAPTER (pios_spi_gyro_id)
// ------------------------
// PIOS_WDG
// ------------------------
#define PIOS_WATCHDOG_TIMEOUT 250
#define PIOS_WDG_REGISTER RTC_BKP_DR4
#define PIOS_WDG_ACTUATOR 0x0001
#define PIOS_WDG_STABILIZATION 0x0002
#define PIOS_WDG_ATTITUDE 0x0004
#define PIOS_WDG_MANUAL 0x0008
#define PIOS_WDG_SENSORS 0x0010
#define PIOS_WDG_AUTOTUNE 0x0020
#define PIOS_WATCHDOG_TIMEOUT 250
#define PIOS_WDG_REGISTER RTC_BKP_DR4
#define PIOS_WDG_ACTUATOR 0x0001
#define PIOS_WDG_STABILIZATION 0x0002
#define PIOS_WDG_ATTITUDE 0x0004
#define PIOS_WDG_MANUAL 0x0008
#define PIOS_WDG_SENSORS 0x0010
#define PIOS_WDG_AUTOTUNE 0x0020
// ------------------------
// PIOS_I2C
// See also pios_board.c
// ------------------------
#define PIOS_I2C_MAX_DEVS 3
#define PIOS_I2C_MAX_DEVS 3
extern uint32_t pios_i2c_mag_adapter_id;
#define PIOS_I2C_MAIN_ADAPTER (pios_i2c_mag_adapter_id)
extern uint32_t pios_i2c_pressure_adapter_id;
#define PIOS_I2C_MS5611_INTERNAL_ADAPTER (pios_i2c_pressure_adapter_id)
#define PIOS_I2C_HMC5X83_INTERNAL_ADAPTER (pios_i2c_mag_adapter_id)
extern uint32_t pios_i2c_flexiport_adapter_id;
#define PIOS_I2C_FLEXI_ADAPTER (pios_i2c_flexiport_adapter_id)
#define PIOS_I2C_ETASV3_ADAPTER (PIOS_I2C_FLEXI_ADAPTER)
#define PIOS_I2C_FLEXI_ADAPTER (pios_i2c_flexiport_adapter_id)
#define PIOS_I2C_ETASV3_ADAPTER (PIOS_I2C_FLEXI_ADAPTER)
#define PIOS_I2C_EXTERNAL_ADAPTER (pios_i2c_flexiport_adapter_id)
// -------------------------
// PIOS_USART
@ -119,26 +130,26 @@ extern uint32_t pios_i2c_flexiport_adapter_id;
// See also pios_board.c
// -------------------------
#define PIOS_COM_MAX_DEVS 4
extern uint32_t pios_com_telem_rf_id;
extern uint32_t pios_com_gps_id;
extern uint32_t pios_com_aux_id;
extern uint32_t pios_com_telem_usb_id;
extern uint32_t pios_com_bridge_id;
extern uint32_t pios_com_vcp_id;
extern uint32_t pios_com_hkosd_id;
extern uint32_t pios_com_msp_id;
extern uint32_t pios_com_mavlink_id;
#define PIOS_COM_AUX (pios_com_aux_id)
#define PIOS_COM_GPS (pios_com_gps_id)
#define PIOS_COM_TELEM_USB (pios_com_telem_usb_id)
#define PIOS_COM_TELEM_RF (pios_com_telem_rf_id)
#define PIOS_COM_BRIDGE (pios_com_bridge_id)
#define PIOS_COM_VCP (pios_com_vcp_id)
#define PIOS_COM_DEBUG PIOS_COM_AUX
#define PIOS_COM_OSDHK (pios_com_hkosd_id)
#define PIOS_COM_MSP (pios_com_msp_id)
#define PIOS_COM_MAVLINK (pios_com_mavlink_id)
// extern uint32_t pios_com_telem_rf_id;
// extern uint32_t pios_com_gps_id;
// extern uint32_t pios_com_aux_id;
// extern uint32_t pios_com_telem_usb_id;
// extern uint32_t pios_com_bridge_id;
// extern uint32_t pios_com_vcp_id;
// extern uint32_t pios_com_hkosd_id;
// extern uint32_t pios_com_msp_id;
// extern uint32_t pios_com_mavlink_id;
//
// #define PIOS_COM_AUX (pios_com_aux_id)
// #define PIOS_COM_GPS (pios_com_gps_id)
// #define PIOS_COM_TELEM_USB (pios_com_telem_usb_id)
// #define PIOS_COM_TELEM_RF (pios_com_telem_rf_id)
// #define PIOS_COM_BRIDGE (pios_com_bridge_id)
// #define PIOS_COM_VCP (pios_com_vcp_id)
// #define PIOS_COM_DEBUG PIOS_COM_AUX
// #define PIOS_COM_OSDHK (pios_com_hkosd_id)
// #define PIOS_COM_MSP (pios_com_msp_id)
// #define PIOS_COM_MAVLINK (pios_com_mavlink_id)
// ------------------------
// TELEMETRY

View File

@ -439,7 +439,7 @@ const struct pios_rfm22b_cfg pios_rfm22b_cfg = {
.gpio_direction = GPIO0_TX_GPIO1_RX,
};
const struct pios_rfm22b_cfg *PIOS_BOARD_HW_DEFS_GetRfm22Cfg(__attribute__((unused)) uint32_t board_revision)
const struct pios_rfm22b_cfg *PIOS_BOARD_HW_DEFS_GetRfm22bCfg(__attribute__((unused)) uint32_t board_revision)
{
return &pios_rfm22b_cfg;
}
@ -540,6 +540,7 @@ static const struct flashfs_logfs_cfg flashfs_internal_cfg = {
#endif /* PIOS_INCLUDE_FLASH */
#ifdef PIOS_INCLUDE_USART
#include <pios_usart_priv.h>
/*
@ -628,6 +629,7 @@ static const struct pios_usart_cfg pios_usart_rcvr_cfg = {
},
.ioctl = PIOS_BOARD_USART_Ioctl,
};
#endif /* PIOS_INCLUDE_USART */
#if defined(PIOS_INCLUDE_COM)

View File

@ -36,6 +36,7 @@
#include <pios_usbhook.h> /* PIOS_USBHOOK_* */
#include <stdbool.h>
#include <pios_board_init.h>
#include <pios_board_io.h>
extern void FLASH_Download();
void check_bor();

View File

@ -25,7 +25,6 @@
#include <pios.h>
#include <pios_board_info.h>
/*
* Pull in the board-specific static HW definitions.
* Including .c files is a bit ugly but this allows all of
@ -40,11 +39,6 @@ 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) {