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

Merged in mindnever/librepilot/LP-480_pios_board_com_port_setup_refactoring (pull request #418)

LP-480 pios board com port setup refactoring

Approved-by: Philippe Renon <philippe_renon@yahoo.fr>
Approved-by: Lalanne Laurent <f5soh@free.fr>
Approved-by: Brian Webb <webbbn@gmail.com>
Approved-by: Vladimir Zidar <mr_w@mindnever.org>
Approved-by: Alessio Morale <alessiomorale@gmail.com>
This commit is contained in:
Vladimir Zidar 2017-05-15 18:59:06 +00:00 committed by Philippe Renon
commit 1a28929206
86 changed files with 4108 additions and 10446 deletions

View File

@ -89,6 +89,7 @@ SRC += $(PIOSCOMMON)/pios_wavplay.c
SRC += $(PIOSCOMMON)/pios_rfm22b.c
SRC += $(PIOSCOMMON)/pios_rfm22b_com.c
SRC += $(PIOSCOMMON)/pios_rcvr.c
SRC += $(PIOSCOMMON)/pios_dsm.c
SRC += $(PIOSCOMMON)/pios_sbus.c
SRC += $(PIOSCOMMON)/pios_hott.c
SRC += $(PIOSCOMMON)/pios_srxl.c
@ -99,6 +100,8 @@ SRC += $(PIOSCOMMON)/pios_sensors.c
SRC += $(PIOSCOMMON)/pios_servo.c
SRC += $(PIOSCOMMON)/pios_openlrs.c
SRC += $(PIOSCOMMON)/pios_openlrs_rcvr.c
SRC += $(PIOSCOMMON)/pios_board_io.c
SRC += $(PIOSCOMMON)/pios_board_sensors.c
## Misc library functions
SRC += $(FLIGHTLIB)/sanitycheck.c

View File

@ -36,6 +36,8 @@
#include <stdbool.h>
#include <pios_board_io.h>
// ****************
// Private functions

View File

@ -45,6 +45,7 @@
#include "WorldMagModel.h"
#include "CoordinateConversions.h"
#include <pios_com.h>
#include <pios_board_io.h>
#include "GPS.h"
#include "NMEA.h"

View File

@ -43,6 +43,8 @@
#include "hwsettings.h"
#include "flightstatus.h"
#include <pios_board_io.h>
static bool osdoutputEnabled;
enum osd_hk_sync {
@ -284,6 +286,11 @@ static int32_t osdoutputInitialize(void)
osdoutputEnabled = 0;
}
#endif
if (osdoutputEnabled && osd_hk_com_id) {
PIOS_COM_ChangeBaud(osd_hk_com_id, 57600);
}
return 0;
}
MODULE_INITCALL(osdoutputInitialize, osdoutputStart);

View File

@ -41,8 +41,9 @@
#include <uavtalk_priv.h>
#include <pios_rfm22b.h>
#include <ecc.h>
#include <pios_board_io.h>
#include <stdbool.h>
#include <manualcontrolsettings.h>
// ****************
// Private constants
@ -57,6 +58,7 @@
#define SERIAL_RX_BUF_LEN 100
#define PPM_INPUT_TIMEOUT 100
#define PIOS_PPM_RECEIVER pios_rcvr_group_map[MANUALCONTROLSETTINGS_CHANNELGROUPS_PPM]
// ****************
// Private types

View File

@ -62,7 +62,7 @@
#include <pios_notify.h>
#include <pios_task_monitor.h>
#include <pios_board_init.h>
#include <pios_board_io.h>
#ifdef PIOS_INCLUDE_INSTRUMENTATION
#include <instrumentation.h>

View File

@ -69,6 +69,8 @@
#include "hwsettings.h"
#include "taskinfo.h"
#include <pios_board_io.h>
// Private constants
#define MAX_QUEUE_SIZE TELEM_QUEUE_SIZE
// Three different stack size parameter are accepted for Telemetry(RX PIOS_TELEM_RX_STACK_SIZE)

View File

@ -55,6 +55,8 @@
#include "pios_sensors.h"
#include "uavohottbridge.h"
#include "pios_board_io.h"
#if defined(PIOS_INCLUDE_HOTT_BRIDGE)
#if defined(PIOS_HoTT_STACK_SIZE)
@ -121,7 +123,8 @@ static int32_t uavoHoTTBridgeInitialize(void)
// HoTT telemetry baudrate is fixed to 19200
PIOS_COM_ChangeBaud(PIOS_COM_HOTT, 19200);
PIOS_COM_SetHalfDuplex(PIOS_COM_HOTT, true);
bool param = true;
PIOS_COM_Ioctl(PIOS_COM_HOTT, PIOS_IOCTL_USART_SET_HALFDUPLEX, &param);
HoTTBridgeSettingsInitialize();
HoTTBridgeStatusInitialize();

View File

@ -68,6 +68,8 @@
#include "pios_sensors.h"
#include <pios_board_io.h>
#define PIOS_INCLUDE_MSP_BRIDGE

View File

@ -58,6 +58,9 @@
#include "custom_types.h"
#include <pios_board_io.h>
#define OPLINK_LOW_RSSI -110
#define OPLINK_HIGH_RSSI -10

View File

@ -0,0 +1,686 @@
/**
******************************************************************************
*
* @file pios_board_io.c
* @author The LibrePilot Project, http://www.librepilot.org Copyright (C) 2017.
* @brief board io setup
* --
* @see The GNU Public License (GPL) Version 3
*
*****************************************************************************/
/*
* This program is free software; you can redistribute it and/or modify
* it under the terms of the GNU General Public License as published by
* the Free Software Foundation; either version 3 of the License, or
* (at your option) any later version.
*
* This program is distributed in the hope that it will be useful, but
* WITHOUT ANY WARRANTY; without even the implied warranty of MERCHANTABILITY
* or FITNESS FOR A PARTICULAR PURPOSE. See the GNU General Public License
* for more details.
*
* You should have received a copy of the GNU General Public License along
* with this program; if not, write to the Free Software Foundation, Inc.,
* 59 Temple Place, Suite 330, Boston, MA 02111-1307 USA
*/
#include <pios_board_io.h>
#include <pios_board_hw.h>
#include <pios_board_info.h>
#include "uavobjectmanager.h"
#include <alarms.h>
#ifdef PIOS_INCLUDE_RCVR
# ifdef PIOS_INCLUDE_HOTT
# include <pios_hott_priv.h>
# endif
# ifdef PIOS_INCLUDE_DSM
# include <pios_dsm_priv.h>
# endif
# ifdef PIOS_INCLUDE_SBUS
# include <pios_sbus_priv.h>
# endif
# ifdef PIOS_INCLUDE_IBUS
# include <pios_ibus_priv.h>
# endif
# ifdef PIOS_INCLUDE_EXBUS
# include <pios_exbus_priv.h>
# endif
# ifdef PIOS_INCLUDE_SRXL
# include <pios_srxl_priv.h>
# endif
# include <pios_rcvr_priv.h>
# ifdef PIOS_INCLUDE_GCSRCVR
# include <pios_gcsrcvr_priv.h>
# endif
#endif /* PIOS_INCLUDE_RCVR */
#ifdef PIOS_INCLUDE_RFM22B
# include <oplinksettings.h>
# include <oplinkstatus.h>
# ifdef PIOS_INCLUDE_RCVR
# include <oplinkreceiver.h>
# include <pios_oplinkrcvr_priv.h>
# include <pios_openlrs.h>
# include <pios_openlrs_rcvr_priv.h>
# endif /* PIOS_INCLUDE_RCVR */
#endif /* PIOS_INCLUDE_RFM22B */
#ifdef PIOS_INCLUDE_RCVR
# include "manualcontrolsettings.h"
uint32_t pios_rcvr_group_map[MANUALCONTROLSETTINGS_CHANNELGROUPS_NONE]; /* Receivers */
#endif /* PIOS_INCLUDE_RCVR */
#include "hwsettings.h"
#include "gcsreceiver.h"
#ifdef PIOS_INCLUDE_GPS
uint32_t pios_com_gps_id; /* GPS */
#endif /* PIOS_INCLUDE_GPS */
uint32_t pios_com_bridge_id; /* ComUsbBridge */
uint32_t pios_com_telem_rf_id; /* Serial port telemetry */
#ifdef PIOS_INCLUDE_RFM22B
uint32_t pios_rfm22b_id; /* RFM22B handle */
uint32_t pios_com_pri_radio_id; /* oplink primary com stream */
uint32_t pios_com_aux_radio_id; /* oplink aux com stream */
#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 */
uint32_t pios_com_vcp_id; /* USB VCP */
#ifdef PIOS_INCLUDE_DEBUG_CONSOLE
uint32_t pios_com_debug_id; /* DebugConsole */
#endif /* PIOS_INCLUDE_DEBUG_CONSOLE */
#ifdef PIOS_INCLUDE_HOTT_BRIDGE
uint32_t pios_com_hott_id;
#endif
#ifdef PIOS_INCLUDE_USB
uint32_t pios_com_telem_usb_id; /* USB telemetry */
#ifdef PIOS_INCLUDE_USB_RCTX
# include "pios_usb_rctx_priv.h"
uint32_t pios_usb_rctx_id;
#endif
#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"
#if defined(PIOS_INCLUDE_COM_MSG)
/* for bootloader? */
#include <pios_com_msg_priv.h>
#endif /* PIOS_INCLUDE_COM_MSG */
#if defined(PIOS_INCLUDE_USB_CDC)
static void PIOS_BOARD_IO_VCP_Init(uint32_t *com_id, uint16_t rx_buf_len, uint16_t tx_buf_len, uint32_t pios_usb_id)
{
#if defined(PIOS_INCLUDE_COM)
uint32_t pios_usb_cdc_id = 0;
if (PIOS_USB_CDC_Init(&pios_usb_cdc_id, &pios_usb_cdc_cfg, pios_usb_id)) {
PIOS_Assert(0);
}
if (PIOS_COM_Init(com_id, &pios_usb_cdc_com_driver, pios_usb_cdc_id,
0, rx_buf_len, /* Let Init() allocate this buffer */
0, tx_buf_len)) { /* Let Init() allocate this buffer */
PIOS_Assert(0);
}
#endif /* PIOS_INCLUDE_COM */
}
#endif
static void PIOS_BOARD_IO_HID_Init(uint32_t *com_id, uint16_t rx_buf_len, uint16_t tx_buf_len, uint32_t pios_usb_id)
{
#ifdef PIOS_INCLUDE_USB_CDC
const struct pios_usb_hid_cfg *hid_cfg = &pios_usb_hid_cfg;
#else
const struct pios_usb_hid_cfg *hid_cfg = &pios_usb_hid_only_cfg;
#endif
uint32_t pios_usb_hid_id;
if (PIOS_USB_HID_Init(&pios_usb_hid_id, hid_cfg, pios_usb_id)) {
PIOS_Assert(0);
}
if (PIOS_COM_Init(com_id, &pios_usb_hid_com_driver, pios_usb_hid_id,
0, rx_buf_len, /* Let Init() allocate this buffer */
0, tx_buf_len)) { /* Let Init() allocate this buffer */
PIOS_Assert(0);
}
}
void PIOS_BOARD_IO_Configure_USB()
{
uint8_t hwsettings_usb_hidport;
uint8_t hwsettings_usb_vcpport;
HwSettingsUSB_HIDPortGet(&hwsettings_usb_hidport);
HwSettingsUSB_VCPPortGet(&hwsettings_usb_vcpport);
PIOS_BOARD_IO_Configure_USB_Function((PIOS_BOARD_IO_USB_HID_Function)hwsettings_usb_hidport, (PIOS_BOARD_IO_USB_VCP_Function)hwsettings_usb_vcpport);
}
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();
#if defined(PIOS_INCLUDE_USB_CDC)
if (PIOS_USB_DESC_HID_CDC_Init()) {
PIOS_Assert(0);
}
#else
if (PIOS_USB_DESC_HID_ONLY_Init()) {
PIOS_Assert(0);
}
#endif
uint32_t pios_usb_id;
PIOS_USB_Init(&pios_usb_id, PIOS_BOARD_HW_DEFS_GetUsbCfg(pios_board_info_blob.board_rev));
#if defined(PIOS_INCLUDE_USB_CDC)
switch (vcp_function) {
case PIOS_BOARD_IO_USB_VCP_NONE:
break;
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 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 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 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;
}
#endif /* PIOS_INCLUDE_USB_CDC */
#if defined(PIOS_INCLUDE_USB_HID)
/* Configure the usb HID port */
switch (hid_function) {
case PIOS_BOARD_IO_USB_HID_NONE:
break;
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 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);
}
#endif /* PIOS_INCLUDE_USB_RCTX */
break;
}
#endif /* PIOS_INCLUDE_USB_HID */
#ifndef STM32F10X
PIOS_USBHOOK_Activate();
#endif
}
#endif /* PIOS_INCLUDE_USB */
#ifdef PIOS_INCLUDE_RCVR
# ifdef PIOS_INCLUDE_HOTT
static int32_t PIOS_HOTT_Init_SUMD(uint32_t *id, const struct pios_com_driver *driver, uint32_t lower_id)
{
return PIOS_HOTT_Init(id, driver, lower_id, PIOS_HOTT_PROTO_SUMD);
}
static int32_t PIOS_HOTT_Init_SUMH(uint32_t *id, const struct pios_com_driver *driver, uint32_t lower_id)
{
return PIOS_HOTT_Init(id, driver, lower_id, PIOS_HOTT_PROTO_SUMH);
}
# endif /* PIOS_INCLUDE_HOTT */
# ifdef PIOS_INCLUDE_DSM
static int32_t PIOS_DSM_Init_Helper(uint32_t *id, const struct pios_com_driver *driver, uint32_t lower_id)
{
// DSM Bind stuff
uint8_t hwsettings_DSMxBind;
HwSettingsDSMxBindGet(&hwsettings_DSMxBind);
return PIOS_DSM_Init(id, driver, lower_id, hwsettings_DSMxBind);
}
# endif
# ifdef PIOS_INCLUDE_SBUS
static int32_t PIOS_SBus_Init_Helper(uint32_t *id, const struct pios_com_driver *driver, uint32_t lower_id)
{
// sbus-noninverted
HwSettingsSBusModeOptions hwsettings_SBusMode;
HwSettingsSBusModeGet(&hwsettings_SBusMode);
struct pios_sbus_cfg sbus_cfg = {
.non_inverted = (hwsettings_SBusMode == HWSETTINGS_SBUSMODE_NONINVERTED),
};
return PIOS_SBus_Init(id, &sbus_cfg, driver, lower_id);
}
# endif
#endif /* ifdef PIOS_INCLUDE_RCVR */
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[] = {
[PIOS_BOARD_IO_UART_TELEMETRY] = {
.com_id = &pios_com_telem_rf_id,
.com_rx_buf_len = PIOS_COM_TELEM_RF_RX_BUF_LEN,
.com_tx_buf_len = PIOS_COM_TELEM_RF_TX_BUF_LEN,
},
[PIOS_BOARD_IO_UART_MAVLINK] = {
.com_id = &pios_com_mavlink_id,
.com_rx_buf_len = PIOS_COM_MAVLINK_RX_BUF_LEN,
.com_tx_buf_len = PIOS_COM_MAVLINK_TX_BUF_LEN,
},
[PIOS_BOARD_IO_UART_MSP] = {
.com_id = &pios_com_msp_id,
.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,
.com_tx_buf_len = PIOS_COM_HKOSD_TX_BUF_LEN,
},
#ifdef PIOS_INCLUDE_HOTT_BRIDGE
[PIOS_BOARD_IO_UART_HOTT_BRIDGE] = {
.com_id = &pios_com_hott_id,
.com_rx_buf_len = PIOS_COM_HOTT_BRIDGE_RX_BUF_LEN,
.com_tx_buf_len = PIOS_COM_HOTT_BRIDGE_TX_BUF_LEN,
},
#endif
#ifdef PIOS_INCLUDE_DEBUG_CONSOLE
[PIOS_BOARD_IO_UART_DEBUGCONSOLE] = {
.com_id = &pios_com_debug_id,
.com_tx_buf_len = PIOS_COM_DEBUGCONSOLE_TX_BUF_LEN,
},
#endif
[PIOS_BOARD_IO_UART_COMBRIDGE] = {
.com_id = &pios_com_bridge_id,
.com_rx_buf_len = PIOS_COM_BRIDGE_RX_BUF_LEN,
.com_tx_buf_len = PIOS_COM_BRIDGE_TX_BUF_LEN,
},
#ifdef PIOS_INCLUDE_RCVR
# ifdef PIOS_INCLUDE_IBUS
[PIOS_BOARD_IO_UART_IBUS] = {
.rcvr_init = &PIOS_IBUS_Init,
.rcvr_driver = &pios_ibus_rcvr_driver,
.rcvr_group = MANUALCONTROLSETTINGS_CHANNELGROUPS_IBUS,
},
# endif /* PIOS_INCLUDE_IBUS */
# ifdef PIOS_INCLUDE_EXBUS
[PIOS_BOARD_IO_UART_EXBUS] = {
.rcvr_init = &PIOS_EXBUS_Init,
.rcvr_driver = &pios_exbus_rcvr_driver,
.rcvr_group = MANUALCONTROLSETTINGS_CHANNELGROUPS_EXBUS,
},
# endif /* PIOS_INCLUDE_EXBUS */
# ifdef PIOS_INCLUDE_SRXL
[PIOS_BOARD_IO_UART_SRXL] = {
.rcvr_init = &PIOS_SRXL_Init,
.rcvr_driver = &pios_srxl_rcvr_driver,
.rcvr_group = MANUALCONTROLSETTINGS_CHANNELGROUPS_SRXL,
},
# endif /* PIOS_INCLUDE_SRXL */
# ifdef PIOS_INCLUDE_HOTT
[PIOS_BOARD_IO_UART_HOTT_SUMD] = {
.rcvr_init = &PIOS_HOTT_Init_SUMD,
.rcvr_driver = &pios_hott_rcvr_driver,
.rcvr_group = MANUALCONTROLSETTINGS_CHANNELGROUPS_HOTT,
},
[PIOS_BOARD_IO_UART_HOTT_SUMH] = {
.rcvr_init = &PIOS_HOTT_Init_SUMH,
.rcvr_driver = &pios_hott_rcvr_driver,
.rcvr_group = MANUALCONTROLSETTINGS_CHANNELGROUPS_HOTT,
},
# endif /* PIOS_INCLUDE_HOTT */
# ifdef PIOS_INCLUDE_DSM
[PIOS_BOARD_IO_UART_DSM_MAIN] = {
.rcvr_init = &PIOS_DSM_Init_Helper,
.rcvr_driver = &pios_dsm_rcvr_driver,
.rcvr_group = MANUALCONTROLSETTINGS_CHANNELGROUPS_DSMMAINPORT,
},
[PIOS_BOARD_IO_UART_DSM_FLEXI] = {
.rcvr_init = &PIOS_DSM_Init_Helper,
.rcvr_driver = &pios_dsm_rcvr_driver,
.rcvr_group = MANUALCONTROLSETTINGS_CHANNELGROUPS_DSMFLEXIPORT,
},
[PIOS_BOARD_IO_UART_DSM_RCVR] = {
.rcvr_init = &PIOS_DSM_Init_Helper,
.rcvr_driver = &pios_dsm_rcvr_driver,
.rcvr_group = MANUALCONTROLSETTINGS_CHANNELGROUPS_DSMRCVRPORT,
},
# endif /* PIOS_INCLUDE_DSM */
# ifdef PIOS_INCLUDE_SBUS
[PIOS_BOARD_IO_UART_SBUS] = {
.rcvr_init = &PIOS_SBus_Init_Helper,
.rcvr_driver = &pios_sbus_rcvr_driver,
.rcvr_group = MANUALCONTROLSETTINGS_CHANNELGROUPS_SBUS,
},
# endif /* PIOS_INCLUDE_SBUS */
#endif /* PIOS_INCLUDE_RCVR */
};
void PIOS_BOARD_IO_Configure_UART_COM(const struct pios_usart_cfg *hw_config,
uint16_t rx_buf_len,
uint16_t tx_buf_len,
uint32_t *com_id)
{
uint32_t usart_id;
if (PIOS_USART_Init(&usart_id, hw_config)) {
PIOS_Assert(0);
}
if (PIOS_COM_Init(com_id, &pios_usart_com_driver, usart_id,
0, rx_buf_len,
0, tx_buf_len)) {
PIOS_Assert(0);
}
}
void PIOS_BOARD_IO_Configure_UART(const struct pios_usart_cfg *hw_config, PIOS_BOARD_IO_UART_Function function)
{
if (function >= NELEMENTS(uart_function_map)) {
return;
}
if (uart_function_map[function].com_id) {
PIOS_BOARD_IO_Configure_UART_COM(hw_config,
uart_function_map[function].com_rx_buf_len,
uart_function_map[function].com_tx_buf_len,
uart_function_map[function].com_id);
}
#ifdef PIOS_INCLUDE_RCVR
else if (uart_function_map[function].rcvr_init) {
uint32_t usart_id;
if (PIOS_USART_Init(&usart_id, hw_config)) {
PIOS_Assert(0);
}
uint32_t rcvr_driver_id;
if (uart_function_map[function].rcvr_init(&rcvr_driver_id, &pios_usart_com_driver, usart_id)) {
PIOS_Assert(0);
}
uint32_t rcvr_id;
if (PIOS_RCVR_Init(&rcvr_id, uart_function_map[function].rcvr_driver, rcvr_driver_id)) {
PIOS_Assert(0);
}
pios_rcvr_group_map[uart_function_map[function].rcvr_group] = rcvr_id;
}
#endif /* PIOS_INCLUDE_RCVR */
}
#ifdef PIOS_INCLUDE_PWM
void PIOS_BOARD_IO_Configure_PWM_RCVR(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;
}
#endif /* PIOS_INCLUDE_PWM */
#ifdef PIOS_INCLUDE_PPM
void PIOS_BOARD_IO_Configure_PPM_RCVR(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;
}
#endif /* PIOS_INCLUDE_PPM */
#ifdef PIOS_INCLUDE_GCSRCVR
void PIOS_BOARD_IO_Configure_GCS_RCVR()
{
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_RFM22B
void PIOS_BOARD_IO_Configure_RFM22B()
{
#if defined(PIOS_INCLUDE_RFM22B)
OPLinkSettingsInitialize();
OPLinkStatusInitialize();
#endif /* PIOS_INCLUDE_RFM22B */
#if defined(PIOS_INCLUDE_OPLINKRCVR) && defined(PIOS_INCLUDE_RCVR)
OPLinkReceiverInitialize();
#endif
/* Initialize the RFM22B radio COM device. */
/* Fetch the OPLinkSettings object. */
OPLinkSettingsData oplinkSettings;
OPLinkSettingsGet(&oplinkSettings);
// Initialize out status object.
OPLinkStatusData oplinkStatus;
OPLinkStatusGet(&oplinkStatus);
oplinkStatus.BoardType = pios_board_info_blob.board_type;
PIOS_BL_HELPER_FLASH_Read_Description(oplinkStatus.Description, OPLINKSTATUS_DESCRIPTION_NUMELEM);
PIOS_SYS_SerialNumberGetBinary(oplinkStatus.CPUSerial);
oplinkStatus.BoardRevision = pios_board_info_blob.board_rev;
/* Is the radio turned on? */
bool is_coordinator = (oplinkSettings.Protocol == OPLINKSETTINGS_PROTOCOL_OPLINKCOORDINATOR);
bool openlrs = (oplinkSettings.Protocol == OPLINKSETTINGS_PROTOCOL_OPENLRS);
bool data_mode = ((oplinkSettings.LinkType == OPLINKSETTINGS_LINKTYPE_DATA) ||
(oplinkSettings.LinkType == OPLINKSETTINGS_LINKTYPE_DATAANDCONTROL));
bool ppm_mode = ((oplinkSettings.LinkType == OPLINKSETTINGS_LINKTYPE_CONTROL) ||
(oplinkSettings.LinkType == OPLINKSETTINGS_LINKTYPE_DATAANDCONTROL));
bool is_enabled = ((oplinkSettings.Protocol != OPLINKSETTINGS_PROTOCOL_DISABLED) &&
((oplinkSettings.MaxRFPower != OPLINKSETTINGS_MAXRFPOWER_0) || openlrs));
if (is_enabled) {
if (openlrs) {
#if defined(PIOS_INCLUDE_OPENLRS_RCVR) && defined(PIOS_INCLUDE_RCVR)
const struct pios_openlrs_cfg *openlrs_cfg = PIOS_BOARD_HW_DEFS_GetOpenLRSCfg(pios_board_info_blob.board_rev);
PIOS_OpenLRS_Init(&pios_openlrs_id, PIOS_SPI_RFM22B_ADAPTER, 0, openlrs_cfg);
uint32_t openlrsrcvr_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)) {
PIOS_Assert(0);
}
pios_rcvr_group_map[MANUALCONTROLSETTINGS_CHANNELGROUPS_OPENLRS] = openlrsrcvr_rcvr_id;
#endif /* PIOS_INCLUDE_OPENLRS_RCVR && PIOS_INCLUDE_RCVR */
} else {
/* Configure the RFM22B device. */
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);
}
#if defined(PIOS_INCLUDE_OPLINKRCVR) && defined(PIOS_INCLUDE_RCVR)
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 && PIOS_INCLUDE_RCVR */
/* Configure the radio com interface */
if (PIOS_COM_Init(&pios_com_pri_radio_id, &pios_rfm22b_com_driver, pios_rfm22b_id,
0, PIOS_COM_PRI_RADIO_RX_BUF_LEN,
0, PIOS_COM_PRI_RADIO_TX_BUF_LEN)) {
PIOS_Assert(0);
}
// Initialize the aux radio com interface
if (PIOS_COM_Init(&pios_com_aux_radio_id, &pios_rfm22b_aux_com_driver, pios_rfm22b_id,
0, PIOS_COM_AUX_RADIO_RX_BUF_LEN,
0, PIOS_COM_AUX_RADIO_TX_BUF_LEN)) {
PIOS_Assert(0);
}
oplinkStatus.LinkState = OPLINKSTATUS_LINKSTATE_ENABLED;
// Set the modem (over the air) datarate.
enum rfm22b_datarate datarate = RFM22_datarate_64000;
switch (oplinkSettings.AirDataRate) {
case OPLINKSETTINGS_AIRDATARATE_9600:
datarate = RFM22_datarate_9600;
break;
case OPLINKSETTINGS_AIRDATARATE_19200:
datarate = RFM22_datarate_19200;
break;
case OPLINKSETTINGS_AIRDATARATE_32000:
datarate = RFM22_datarate_32000;
break;
case OPLINKSETTINGS_AIRDATARATE_57600:
datarate = RFM22_datarate_57600;
break;
case OPLINKSETTINGS_AIRDATARATE_64000:
datarate = RFM22_datarate_64000;
break;
case OPLINKSETTINGS_AIRDATARATE_100000:
datarate = RFM22_datarate_100000;
break;
case OPLINKSETTINGS_AIRDATARATE_128000:
datarate = RFM22_datarate_128000;
break;
case OPLINKSETTINGS_AIRDATARATE_192000:
datarate = RFM22_datarate_192000;
break;
case OPLINKSETTINGS_AIRDATARATE_256000:
datarate = RFM22_datarate_256000;
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;
}
OPLinkStatusSet(&oplinkStatus);
}
void PIOS_BOARD_IO_Configure_RadioAuxStream(HwSettingsRadioAuxStreamOptions radioaux)
{
switch (radioaux) {
case HWSETTINGS_RADIOAUXSTREAM_DEBUGCONSOLE:
#ifdef PIOS_INCLUDE_DEBUG_CONSOLE
pios_com_debug_id = pios_com_aux_radio_id;
#endif
break;
case HWSETTINGS_RADIOAUXSTREAM_MAVLINK:
pios_com_mavlink_id = pios_com_aux_radio_id;
break;
case HWSETTINGS_RADIOAUXSTREAM_COMBRIDGE:
pios_com_bridge_id = pios_com_aux_radio_id;
break;
case HWSETTINGS_RADIOAUXSTREAM_DISABLED:
break;
}
}
#endif /* ifdef PIOS_INCLUDE_RFM22B */

View File

@ -0,0 +1,215 @@
/**
******************************************************************************
*
* @file pios_board_sensors.c
* @author The LibrePilot Project, http://www.librepilot.org Copyright (C) 2017.
* @brief board sensors setup
* --
* @see The GNU Public License (GPL) Version 3
*
*****************************************************************************/
/*
* This program is free software; you can redistribute it and/or modify
* it under the terms of the GNU General Public License as published by
* the Free Software Foundation; either version 3 of the License, or
* (at your option) any later version.
*
* This program is distributed in the hope that it will be useful, but
* WITHOUT ANY WARRANTY; without even the implied warranty of MERCHANTABILITY
* or FITNESS FOR A PARTICULAR PURPOSE. See the GNU General Public License
* for more details.
*
* You should have received a copy of the GNU General Public License along
* with this program; if not, write to the Free Software Foundation, Inc.,
* 59 Temple Place, Suite 330, Boston, MA 02111-1307 USA
*/
#include "pios_board_info.h"
#include "pios_board_sensors.h"
#include "pios_board_hw.h"
#include "uavobjectmanager.h"
#include "auxmagsettings.h"
#include "hwsettings.h"
#include <alarms.h>
#ifdef PIOS_INCLUDE_MPU6000
# include <pios_mpu6000.h>
# include <pios_mpu6000_config.h>
#endif
#ifdef PIOS_INCLUDE_MS5611
# include <pios_ms5611.h>
#endif
#ifdef PIOS_INCLUDE_ADXL345
# include <pios_adxl345.h>
#endif
#ifdef PIOS_INCLUDE_MPU9250
# include <pios_mpu9250.h>
# include <pios_mpu9250_config.h>
#endif
#ifdef PIOS_INCLUDE_HMC5X83
# include "pios_hmc5x83.h"
# 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
void PIOS_BOARD_Sensors_Configure()
{
#ifdef PIOS_INCLUDE_MPU6000
const struct pios_mpu6000_cfg *mpu6000_cfg = PIOS_BOARD_HW_DEFS_GetMPU6000Cfg(pios_board_info_blob.board_rev);
if (mpu6000_cfg) {
PIOS_MPU6000_Init(PIOS_SPI_MPU6000_ADAPTER, 0, mpu6000_cfg);
PIOS_MPU6000_CONFIG_Configure();
#ifndef PIOS_EXCLUDE_ADVANCED_FEATURES
PIOS_MPU6000_Register();
#endif
}
#endif /* PIOS_INCLUDE_MPU6000 */
#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) {
PIOS_MPU9250_Init(PIOS_SPI_MPU9250_ADAPTER, 0, mpu9250_cfg);
PIOS_MPU9250_CONFIG_Configure();
PIOS_MPU9250_MainRegister();
PIOS_MPU9250_MagRegister();
}
#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
const struct pios_hmc5x83_cfg *hmc5x83_internal_cfg = PIOS_BOARD_HW_DEFS_GetInternalHMC5x83Cfg(pios_board_info_blob.board_rev);
if (hmc5x83_internal_cfg) {
// attach the 5x83 mag to internal i2c bus
pios_hmc5x83_dev_t internal_mag = PIOS_HMC5x83_Init(hmc5x83_internal_cfg, PIOS_I2C_HMC5X83_INTERNAL_ADAPTER, 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(internal_mag, PIOS_SENSORS_TYPE_3AXIS_MAG);
}
# endif /* PIOS_INCLUDE_HMC5X83_INTERNAL */
# ifdef PIOS_INCLUDE_HMC5X83
AuxMagSettingsInitialize();
AuxMagSettingsTypeOptions option;
AuxMagSettingsTypeGet(&option);
const struct pios_hmc5x83_cfg *hmc5x83_external_cfg = PIOS_BOARD_HW_DEFS_GetExternalHMC5x83Cfg(pios_board_info_blob.board_rev);
if (hmc5x83_external_cfg) {
uint32_t i2c_id = 0;
if (option == AUXMAGSETTINGS_TYPE_FLEXI) {
// i2c_external
i2c_id = PIOS_I2C_EXTERNAL_ADAPTER;
} else if (option == AUXMAGSETTINGS_TYPE_I2C) {
// i2c_internal (or Sparky2/F3 dedicated I2C port)
i2c_id = PIOS_I2C_FLEXI_ADAPTER;
}
if (i2c_id) {
uint32_t external_mag = PIOS_HMC5x83_Init(hmc5x83_external_cfg, i2c_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 */
// internal ms5611 baro
#if defined(PIOS_INCLUDE_MS5611)
const struct pios_ms5611_cfg *ms5611_cfg = PIOS_BOARD_HW_DEFS_GetMS5611Cfg(pios_board_info_blob.board_rev);
if (ms5611_cfg) {
PIOS_MS5611_Init(ms5611_cfg, PIOS_I2C_MS5611_INTERNAL_ADAPTER);
PIOS_MS5611_Register();
}
#endif
#ifdef PIOS_INCLUDE_ADC
const struct pios_adc_cfg *adc_cfg = PIOS_BOARD_HW_DEFS_GetAdcCfg(pios_board_info_blob.board_rev);
if (adc_cfg) {
PIOS_ADC_Init(adc_cfg);
# ifndef PIOS_EXCLUDE_ADVANCED_FEATURES
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
}
#endif /* PIOS_INCLUDE_ADC */
// internal bmp280 baro
// internal MPU6000 imu (i2c)
// external ETASV3 Eagletree Airspeed v3
// external MS4525D PixHawk Airpeed based on MS4525DO
// BMA180 accelerometer?
// bmp085/bmp180 baro
// hmc5843 mag
// i2c esc (?)
// UBX DCC
}

View File

@ -118,8 +118,22 @@ int32_t PIOS_COM_Init(uint32_t *com_id, const struct pios_com_driver *driver, ui
PIOS_Assert(com_id);
PIOS_Assert(driver);
bool has_rx = (rx_buffer && rx_buffer_len > 0);
bool has_tx = (tx_buffer && tx_buffer_len > 0);
if ((rx_buffer_len > 0) && !rx_buffer) {
#if defined(PIOS_INCLUDE_FREERTOS)
rx_buffer = (uint8_t *)pios_malloc(rx_buffer_len);
#endif
PIOS_Assert(rx_buffer);
}
if ((tx_buffer_len > 0) && !tx_buffer) {
#if defined(PIOS_INCLUDE_FREERTOS)
tx_buffer = (uint8_t *)pios_malloc(tx_buffer_len);
#endif
PIOS_Assert(tx_buffer);
}
bool has_rx = (rx_buffer_len > 0);
bool has_tx = (tx_buffer_len > 0);
PIOS_Assert(driver->bind_tx_cb || !has_tx);
PIOS_Assert(driver->bind_rx_cb || !has_rx);
@ -282,31 +296,7 @@ int32_t PIOS_COM_ChangeBaud(uint32_t com_id, uint32_t baud)
return 0;
}
/**
* Change the port type to halfduplex (shared rx/tx medium)
* \param[in] port COM port
* \param[in] halfduplex enabled
* \return -1 if port not available
* \return 0 on success
*/
int32_t PIOS_COM_SetHalfDuplex(uint32_t com_id, bool halfduplex)
{
struct pios_com_dev *com_dev = (struct pios_com_dev *)com_id;
if (!PIOS_COM_validate(com_dev)) {
/* Undefined COM port for this board (see pios_board.c) */
return -1;
}
/* Invoke the driver function if it exists */
if (com_dev->driver->set_halfduplex) {
com_dev->driver->set_halfduplex(com_dev->lower_id, halfduplex);
}
return 0;
}
int32_t PIOS_COM_ChangeConfig(uint32_t com_id, enum PIOS_COM_Word_Length word_len, enum PIOS_COM_StopBits stop_bits, enum PIOS_COM_Parity parity, uint32_t baud_rate, enum PIOS_COM_Mode mode)
int32_t PIOS_COM_ChangeConfig(uint32_t com_id, enum PIOS_COM_Word_Length word_len, enum PIOS_COM_Parity parity, enum PIOS_COM_StopBits stop_bits, uint32_t baud_rate)
{
struct pios_com_dev *com_dev = (struct pios_com_dev *)com_id;
@ -317,7 +307,7 @@ int32_t PIOS_COM_ChangeConfig(uint32_t com_id, enum PIOS_COM_Word_Length word_le
/* Invoke the driver function if it exists */
if (com_dev->driver->set_config) {
com_dev->driver->set_config(com_dev->lower_id, word_len, stop_bits, parity, baud_rate, mode);
com_dev->driver->set_config(com_dev->lower_id, word_len, parity, stop_bits, baud_rate);
}
return 0;
@ -846,6 +836,29 @@ void PIOS_COM_LinkComPair(uint32_t com1_id, uint32_t com2_id, bool link_ctrl_lin
}
}
/*
* Invoke driver specific control functions
* \param[in] port COM port
* \param[in] ctl control function number
* \param[inout] control function parameter
* \return 0 on success
*/
int32_t PIOS_COM_Ioctl(uint32_t com_id, uint32_t ctl, void *param)
{
struct pios_com_dev *com_dev = (struct pios_com_dev *)com_id;
if (!PIOS_COM_validate(com_dev)) {
/* Undefined COM port for this board (see pios_board.c) */
return -1;
}
if (!com_dev->driver->ioctl) {
return -1;
}
return com_dev->driver->ioctl(com_dev->lower_id, ctl, param);
}
#endif /* PIOS_INCLUDE_COM */
/**

View File

@ -78,9 +78,8 @@ struct pios_dsm_state {
#define DSM_FL_WEIGHTED_AVE 18
struct pios_dsm_dev {
enum pios_dsm_dev_magic magic;
const struct pios_dsm_cfg *cfg;
struct pios_dsm_state state;
enum pios_dsm_dev_magic magic;
struct pios_dsm_state state;
};
/* Allocate DSM device descriptor */
@ -122,39 +121,46 @@ static bool PIOS_DSM_Validate(struct pios_dsm_dev *dsm_dev)
}
/* Try to bind DSMx satellite using specified number of pulses */
static void PIOS_DSM_Bind(struct pios_dsm_dev *dsm_dev, uint8_t bind)
static void PIOS_DSM_Bind(struct stm32_gpio *rxpin, uint8_t bind)
{
const struct pios_dsm_cfg *cfg = dsm_dev->cfg;
GPIO_InitTypeDef bindInit = {
.GPIO_Pin = rxpin->init.GPIO_Pin,
.GPIO_Speed = GPIO_Speed_2MHz,
#ifdef STM32F10X
.GPIO_Mode = GPIO_Mode_Out_PP,
#else
.GPIO_Mode = GPIO_Mode_OUT,
.GPIO_OType = GPIO_OType_PP,
.GPIO_PuPd = GPIO_PuPd_NOPULL
#endif
};
GPIO_InitTypeDef GPIO_InitStructure = cfg->bind.init;
GPIO_InitStructure.GPIO_PuPd = GPIO_PuPd_UP;
/* just to limit bind pulses */
if (bind > 10) {
bind = 10;
}
GPIO_Init(cfg->bind.gpio, &cfg->bind.init);
GPIO_Init(rxpin->gpio, &bindInit);
/* RX line, set high */
GPIO_SetBits(cfg->bind.gpio, cfg->bind.init.GPIO_Pin);
GPIO_SetBits(rxpin->gpio, rxpin->init.GPIO_Pin);
/* Wait until the bind window opens. */
while (PIOS_DELAY_GetuS() < DSM_BIND_MIN_DELAY_US) {
;
}
/* just to limit bind pulses */
if (bind > 10) {
bind = 10;
}
for (int i = 0; i < bind; i++) {
/* RX line, drive low for 120us */
GPIO_ResetBits(cfg->bind.gpio, cfg->bind.init.GPIO_Pin);
GPIO_ResetBits(rxpin->gpio, rxpin->init.GPIO_Pin);
PIOS_DELAY_WaituS(120);
/* RX line, drive high for 120us */
GPIO_SetBits(cfg->bind.gpio, cfg->bind.init.GPIO_Pin);
GPIO_SetBits(rxpin->gpio, rxpin->init.GPIO_Pin);
PIOS_DELAY_WaituS(120);
}
/* RX line, set input and wait for data */
GPIO_Init(cfg->bind.gpio, &GPIO_InitStructure);
GPIO_Init(rxpin->gpio, (GPIO_InitTypeDef *)&rxpin->init);
}
/* Reset channels in case of lost signal or explicit failsafe receiver flag */
@ -292,13 +298,11 @@ static void PIOS_DSM_UpdateState(struct pios_dsm_dev *dsm_dev, uint8_t byte)
/* Initialise DSM receiver interface */
int32_t PIOS_DSM_Init(uint32_t *dsm_id,
const struct pios_dsm_cfg *cfg,
const struct pios_com_driver *driver,
uint32_t lower_id,
uint8_t bind)
{
PIOS_DEBUG_Assert(dsm_id);
PIOS_DEBUG_Assert(cfg);
PIOS_DEBUG_Assert(driver);
struct pios_dsm_dev *dsm_dev;
@ -308,20 +312,34 @@ int32_t PIOS_DSM_Init(uint32_t *dsm_id,
return -1;
}
/* Bind the configuration to the device instance */
dsm_dev->cfg = cfg;
/* Bind the receiver if requested */
if (bind) {
PIOS_DSM_Bind(dsm_dev, bind);
struct stm32_gpio rxpin;
PIOS_DEBUG_Assert(driver->ioctl);
if ((driver->ioctl)(lower_id, PIOS_IOCTL_USART_GET_DSMBIND, &rxpin) == 0) {
PIOS_DSM_Bind(&rxpin, bind);
}
}
PIOS_DSM_ResetState(dsm_dev);
*dsm_id = (uint32_t)dsm_dev;
/* Set comm driver parameters */
PIOS_DEBUG_Assert(driver->set_config);
driver->set_config(lower_id, PIOS_COM_Word_length_8b, PIOS_COM_Parity_No, PIOS_COM_StopBits_1, 115200);
/* Set irq priority */
if (driver->ioctl) {
uint8_t irq_prio = PIOS_IRQ_PRIO_HIGH;
driver->ioctl(lower_id, PIOS_IOCTL_USART_SET_IRQ_PRIO, &irq_prio);
}
/* Set comm driver callback */
(driver->bind_rx_cb)(lower_id, PIOS_DSM_RxInCallback, *dsm_id);
driver->bind_rx_cb(lower_id, PIOS_DSM_RxInCallback, *dsm_id);
if (!PIOS_RTC_RegisterTickCallback(PIOS_DSM_Supervisor, *dsm_id)) {
PIOS_DEBUG_Assert(0);

View File

@ -307,8 +307,18 @@ int32_t PIOS_EXBUS_Init(uint32_t *exbus_id,
*exbus_id = (uint32_t)exbus_dev;
/* Set comm driver parameters */
PIOS_DEBUG_Assert(driver->set_config);
driver->set_config(lower_id, PIOS_COM_Word_length_8b, PIOS_COM_Parity_No, PIOS_COM_StopBits_1, 125000);
/* Set irq priority */
if (driver->ioctl) {
uint8_t irq_prio = PIOS_IRQ_PRIO_HIGH;
driver->ioctl(lower_id, PIOS_IOCTL_USART_SET_IRQ_PRIO, &irq_prio);
}
/* Set comm driver callback */
(driver->bind_rx_cb)(lower_id, PIOS_EXBUS_RxInCallback, *exbus_id);
driver->bind_rx_cb(lower_id, PIOS_EXBUS_RxInCallback, *exbus_id);
if (!PIOS_RTC_RegisterTickCallback(PIOS_EXBUS_Supervisor, *exbus_id)) {
PIOS_DEBUG_Assert(0);

View File

@ -325,6 +325,16 @@ int32_t PIOS_HOTT_Init(uint32_t *hott_id,
*hott_id = (uint32_t)hott_dev;
/* Set comm driver parameters */
PIOS_DEBUG_Assert(driver->set_config);
driver->set_config(lower_id, PIOS_COM_Word_length_8b, PIOS_COM_Parity_No, PIOS_COM_StopBits_1, 115200);
/* Set irq priority */
if (driver->ioctl) {
uint8_t irq_prio = PIOS_IRQ_PRIO_HIGH;
driver->ioctl(lower_id, PIOS_IOCTL_USART_SET_IRQ_PRIO, &irq_prio);
}
/* Set comm driver callback */
(driver->bind_rx_cb)(lower_id, PIOS_HOTT_RxInCallback, *hott_id);

View File

@ -174,7 +174,17 @@ int32_t PIOS_IBUS_Init(uint32_t *ibus_id, const struct pios_com_driver *driver,
PIOS_Assert(0);
}
(driver->bind_rx_cb)(lower_id, PIOS_IBUS_Receive, *ibus_id);
/* Set comm driver parameters */
PIOS_DEBUG_Assert(driver->set_config);
driver->set_config(lower_id, PIOS_COM_Word_length_8b, PIOS_COM_Parity_No, PIOS_COM_StopBits_1, 115200);
/* Set irq priority */
if (driver->ioctl) {
uint8_t irq_prio = PIOS_IRQ_PRIO_HIGH;
driver->ioctl(lower_id, PIOS_IOCTL_USART_SET_IRQ_PRIO, &irq_prio);
}
driver->bind_rx_cb(lower_id, PIOS_IBUS_Receive, *ibus_id);
return 0;
}

View File

@ -783,8 +783,8 @@ bool PIOS_RFM22B_TransmitPacket(uint32_t rfm22b_id, uint8_t *p, uint8_t len)
return false;
}
rfm22b_dev->tx_packet_handle = p;
rfm22b_dev->packet_start_time = pios_rfm22_time_ms();
rfm22b_dev->tx_packet_handle = p;
rfm22b_dev->packet_start_time = pios_rfm22_time_ms();
if (rfm22b_dev->packet_start_time == 0) {
rfm22b_dev->packet_start_time = 1;
}

View File

@ -35,6 +35,10 @@
// Define to report number of frames since last dropped instead of weighted ave
#undef SBUS_GOOD_FRAME_COUNT
#ifndef PIOS_SBUS_BAUD_RATE
#define PIOS_SBUS_BAUD_RATE 100000
#endif
#include <uavobjectmanager.h>
#include "pios_sbus_priv.h"
@ -166,13 +170,22 @@ int32_t PIOS_SBus_Init(uint32_t *sbus_id,
*sbus_id = (uint32_t)sbus_dev;
/* Enable inverter clock and enable the inverter */
(*cfg->gpio_clk_func)(cfg->gpio_clk_periph, ENABLE);
GPIO_Init(cfg->inv.gpio, &cfg->inv.init);
GPIO_WriteBit(cfg->inv.gpio, cfg->inv.init.GPIO_Pin, cfg->gpio_inv_enable);
/* Set rest of the parameters */
if (driver->set_config) {
driver->set_config(lower_id, PIOS_COM_Word_length_8b, PIOS_COM_Parity_Even, PIOS_COM_StopBits_2, PIOS_SBUS_BAUD_RATE);
}
/* Set inverted UART and IRQ priority */
if (driver->ioctl) {
enum PIOS_USART_Inverted param = cfg->non_inverted ? 0 : PIOS_USART_Inverted_Rx;
driver->ioctl(lower_id, PIOS_IOCTL_USART_SET_INVERTED, &param);
uint8_t irq_prio = PIOS_IRQ_PRIO_HIGH;
driver->ioctl(lower_id, PIOS_IOCTL_USART_SET_IRQ_PRIO, &irq_prio);
}
/* Set comm driver callback */
(driver->bind_rx_cb)(lower_id, PIOS_SBus_RxInCallback, *sbus_id);
driver->bind_rx_cb(lower_id, PIOS_SBus_RxInCallback, *sbus_id);
if (!PIOS_RTC_RegisterTickCallback(PIOS_SBus_Supervisor, *sbus_id)) {
PIOS_DEBUG_Assert(0);

View File

@ -156,8 +156,18 @@ int32_t PIOS_SRXL_Init(uint32_t *srxl_id,
*srxl_id = (uint32_t)srxl_dev;
/* Set comm driver parameters */
PIOS_DEBUG_Assert(driver->set_config);
driver->set_config(lower_id, PIOS_COM_Word_length_8b, PIOS_COM_Parity_No, PIOS_COM_StopBits_1, 115200);
/* Set irq priority */
if (driver->ioctl) {
uint8_t irq_prio = PIOS_IRQ_PRIO_HIGH;
driver->ioctl(lower_id, PIOS_IOCTL_USART_SET_IRQ_PRIO, &irq_prio);
}
/* Set comm driver callback */
(driver->bind_rx_cb)(lower_id, PIOS_SRXL_RxInCallback, *srxl_id);
driver->bind_rx_cb(lower_id, PIOS_SRXL_RxInCallback, *srxl_id);
if (!PIOS_RTC_RegisterTickCallback(PIOS_SRXL_Supervisor, *srxl_id)) {
PIOS_DEBUG_Assert(0);

View File

@ -317,6 +317,27 @@ static const struct usb_config_hid_cdc config_hid_cdc = {
},
};
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,
};
const struct pios_usb_hid_cfg pios_usb_hid_cfg = {
.data_if = 2,
.data_rx_ep = 1,
.data_tx_ep = 1,
};
#ifdef PIOS_INCLUDE_USB_RCTX
const struct pios_usb_rctx_cfg pios_usb_rctx_cfg = {
.data_if = 2,
.data_tx_ep = 1,
};
#endif
int32_t PIOS_USB_DESC_HID_CDC_Init(void)
{
PIOS_USBHOOK_RegisterConfig(1, (uint8_t *)&config_hid_cdc, sizeof(config_hid_cdc));

View File

@ -156,6 +156,12 @@ const struct usb_config_hid_only config_hid_only = {
},
};
const struct pios_usb_hid_cfg pios_usb_hid_only_cfg = {
.data_if = 0,
.data_rx_ep = 1,
.data_tx_ep = 1,
};
int32_t PIOS_USB_DESC_HID_ONLY_Init(void)
{
PIOS_USBHOOK_RegisterConfig(1, (uint8_t *)&config_hid_only, sizeof(config_hid_only));

View File

@ -0,0 +1,71 @@
/**
******************************************************************************
*
* @file pios_board_io.h
* @author The LibrePilot Project, http://www.librepilot.org Copyright (C) 2017.
* @brief PIOS_BOARD_HW_DEFS functions
* --
* @see The GNU Public License (GPL) Version 3
*
*****************************************************************************/
/*
* This program is free software; you can redistribute it and/or modify
* it under the terms of the GNU General Public License as published by
* the Free Software Foundation; either version 3 of the License, or
* (at your option) any later version.
*
* This program is distributed in the hope that it will be useful, but
* WITHOUT ANY WARRANTY; without even the implied warranty of MERCHANTABILITY
* or FITNESS FOR A PARTICULAR PURPOSE. See the GNU General Public License
* for more details.
*
* You should have received a copy of the GNU General Public License along
* with this program; if not, write to the Free Software Foundation, Inc.,
* 59 Temple Place, Suite 330, Boston, MA 02111-1307 USA
*/
#ifndef PIOS_BOARD_HW_H
#define PIOS_BOARD_HW_H
#ifdef PIOS_INCLUDE_LED
const struct pios_gpio_cfg *PIOS_BOARD_HW_DEFS_GetLedCfg(uint32_t board_revision);
#endif
#ifdef PIOS_INCLUDE_USB
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_GetRfm22bCfg(uint32_t board_revision);
#endif
#ifdef PIOS_INCLUDE_OPENLRS
const struct pios_openlrs_cfg *PIOS_BOARD_HW_DEFS_GetOpenLRSCfg(uint32_t board_revision);
#endif
# ifdef PIOS_INCLUDE_HMC5X83_INTERNAL
const struct pios_hmc5x83_cfg *PIOS_BOARD_HW_DEFS_GetInternalHMC5x83Cfg(uint32_t board_revision);
# endif
#ifdef PIOS_INCLUDE_HMC5X83
const struct pios_hmc5x83_cfg *PIOS_BOARD_HW_DEFS_GetExternalHMC5x83Cfg(uint32_t board_revision);
#endif
#ifdef PIOS_INCLUDE_MS5611
const struct pios_ms5611_cfg *PIOS_BOARD_HW_DEFS_GetMS5611Cfg(uint32_t board_revision);
#endif
#ifdef PIOS_INCLUDE_BMP280
const struct pios_bmp280_cfg *PIOS_BOARD_HW_DEFS_GetBMP280Cfg(uint32_t board_revision);
#endif
#ifdef PIOS_INCLUDE_ADC
const struct pios_adc_cfg *PIOS_BOARD_HW_DEFS_GetAdcCfg(uint32_t board_revision);
#endif
#ifdef PIOS_INCLUDE_MPU6000
const struct pios_mpu6000_cfg *PIOS_BOARD_HW_DEFS_GetMPU6000Cfg(uint32_t board_revision);
#endif
#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

@ -0,0 +1,261 @@
/**
******************************************************************************
*
* @file pios_board_io.h
* @author The LibrePilot Project, http://www.librepilot.org Copyright (C) 2017.
* @brief board io setup
* --
* @see The GNU Public License (GPL) Version 3
*
*****************************************************************************/
/*
* This program is free software; you can redistribute it and/or modify
* it under the terms of the GNU General Public License as published by
* the Free Software Foundation; either version 3 of the License, or
* (at your option) any later version.
*
* This program is distributed in the hope that it will be useful, but
* WITHOUT ANY WARRANTY; without even the implied warranty of MERCHANTABILITY
* or FITNESS FOR A PARTICULAR PURPOSE. See the GNU General Public License
* for more details.
*
* You should have received a copy of the GNU General Public License along
* with this program; if not, write to the Free Software Foundation, Inc.,
* 59 Temple Place, Suite 330, Boston, MA 02111-1307 USA
*/
#ifndef PIOS_BOARD_IO_H
#define PIOS_BOARD_IO_H
#include "pios.h"
#ifdef PIOS_INCLUDE_USB
#include <pios_usb_priv.h>
#endif
#ifdef PIOS_INCLUDE_USART
#include <pios_usart_priv.h>
#endif
#ifdef PIOS_INCLUDE_PWM
#include <pios_pwm_priv.h>
#endif
#ifdef PIOS_INCLUDE_PPM
#include <pios_ppm_priv.h>
#endif
#ifdef PIOS_INCLUDE_OPENLRS
#include <pios_openlrs_priv.h>
#endif
#ifdef PIOS_INCLUDE_RCVR
extern uint32_t pios_rcvr_group_map[]; /* Receivers */
#endif
/* GPS */
#ifdef PIOS_INCLUDE_GPS
extern uint32_t pios_com_gps_id;
# define PIOS_COM_GPS (pios_com_gps_id)
# ifndef PIOS_COM_GPS_RX_BUF_LEN
# define PIOS_COM_GPS_RX_BUF_LEN 128
# endif
# ifndef PIOS_COM_GPS_TX_BUF_LEN
# define PIOS_COM_GPS_TX_BUF_LEN 32
# endif
#endif /* PIOS_INCLUDE_GPS */
/* ComUsbBridge */
extern uint32_t pios_com_bridge_id;
#define PIOS_COM_BRIDGE (pios_com_bridge_id)
#ifndef PIOS_COM_BRIDGE_RX_BUF_LEN
# define PIOS_COM_BRIDGE_RX_BUF_LEN 65
#endif
#ifndef PIOS_COM_BRIDGE_TX_BUF_LEN
# define PIOS_COM_BRIDGE_TX_BUF_LEN 12
#endif
/* USB telemetry */
extern uint32_t pios_com_telem_usb_id;
#define PIOS_COM_TELEM_USB (pios_com_telem_usb_id)
#ifndef PIOS_COM_TELEM_USB_RX_BUF_LEN
# define PIOS_COM_TELEM_USB_RX_BUF_LEN 65
#endif
#ifndef PIOS_COM_TELEM_USB_TX_BUF_LEN
#define PIOS_COM_TELEM_USB_TX_BUF_LEN 65
#endif
/* Serial port telemetry */
extern uint32_t pios_com_telem_rf_id;
#define PIOS_COM_TELEM_RF (pios_com_telem_rf_id)
#ifndef PIOS_COM_TELEM_RF_RX_BUF_LEN
# define PIOS_COM_TELEM_RF_RX_BUF_LEN 128
#endif
#ifndef PIOS_COM_TELEM_RF_TX_BUF_LEN
# define PIOS_COM_TELEM_RF_TX_BUF_LEN 128
#endif
/* RFM22B telemetry */
#ifdef PIOS_INCLUDE_RFM22B
extern uint32_t pios_rfm22b_id; /* RFM22B handle */
extern uint32_t pios_com_pri_radio_id; /* oplink primary com stream */
extern uint32_t pios_com_aux_radio_id; /* oplink aux com stream */
# define PIOS_COM_RF (pios_com_pri_radio_id)
# define PIOS_COM_PRI_RADIO (pios_com_pri_radio_id)
# define PIOS_COM_AUX_RADIO (pios_com_aux_radio_id)
# ifndef PIOS_COM_PRI_RADIO_RX_BUF_LEN
# define PIOS_COM_PRI_RADIO_RX_BUF_LEN 128
# endif
# ifndef PIOS_COM_PRI_RADIO_TX_BUF_LEN
# define PIOS_COM_PRI_RADIO_TX_BUF_LEN 128
# endif
# ifndef PIOS_COM_AUX_RADIO_RX_BUF_LEN
# define PIOS_COM_AUX_RADIO_RX_BUF_LEN 128
# endif
# ifndef PIOS_COM_AUX_RADIO_TX_BUF_LEN
# define PIOS_COM_AUX_RADIO_TX_BUF_LEN 128
# endif
#endif
#ifdef PIOS_INCLUDE_OPENLRS
extern uint32_t pios_openlrs_id; /* openlrs handle */
#endif
/* HK OSD ?? */
extern uint32_t pios_com_hkosd_id;
#define PIOS_COM_OSDHK (pios_com_hkosd_id)
#ifndef PIOS_COM_HKOSD_RX_BUF_LEN
# define PIOS_COM_HKOSD_RX_BUF_LEN 22
#endif
#ifndef PIOS_COM_HKOSD_TX_BUF_LEN
# define PIOS_COM_HKOSD_TX_BUF_LEN 22
#endif
/* MSP */
extern uint32_t pios_com_msp_id;
#define PIOS_COM_MSP (pios_com_msp_id)
#ifndef PIOS_COM_MSP_TX_BUF_LEN
# define PIOS_COM_MSP_TX_BUF_LEN 128
#endif
#ifndef PIOS_COM_MSP_RX_BUF_LEN
# define PIOS_COM_MSP_RX_BUF_LEN 64
#endif
/* MAVLink */
extern uint32_t pios_com_mavlink_id;
#define PIOS_COM_MAVLINK (pios_com_mavlink_id)
#ifndef PIOS_COM_MAVLINK_TX_BUF_LEN
# define PIOS_COM_MAVLINK_TX_BUF_LEN 128
#endif
#ifndef PIOS_COM_MAVLINK_RX_BUF_LEN
# define PIOS_COM_MAVLINK_RX_BUF_LEN 128
#endif
/* HoTT Telemetry */
#ifdef PIOS_INCLUDE_HOTT_BRIDGE
# ifndef PIOS_COM_HOTT_BRIDGE_RX_BUF_LEN
# define PIOS_COM_HOTT_BRIDGE_RX_BUF_LEN 512
# endif
# ifndef PIOS_COM_HOTT_BRIDGE_TX_BUF_LEN
# define PIOS_COM_HOTT_BRIDGE_TX_BUF_LEN 512
# endif
extern uint32_t pios_com_hott_id;
# define PIOS_COM_HOTT (pios_com_hott_id)
#endif
/* USB VCP */
extern uint32_t pios_com_vcp_id;
#define PIOS_COM_VCP (pios_com_vcp_id)
#ifdef PIOS_INCLUDE_DEBUG_CONSOLE
extern uint32_t pios_com_debug_id;
#define PIOS_COM_DEBUG (pios_com_debug_id)
#ifndef PIOS_COM_DEBUGCONSOLE_TX_BUF_LEN
# define PIOS_COM_DEBUGCONSOLE_TX_BUF_LEN 40
#endif
#endif /* PIOS_INCLUDE_DEBUG_CONSOLE */
#ifdef PIOS_INCLUDE_USB_RCTX
extern uint32_t pios_usb_rctx_id;
#endif /* PIOS_INCLUDE_USB_RCTX */
#if defined(PIOS_INCLUDE_HMC5X83) && defined(PIOS_HMC5X83_HAS_GPIOS)
#include <pios_hmc5x83.h>
extern pios_hmc5x83_dev_t pios_hmc5x83_internal_id;
#endif
typedef enum {
PIOS_BOARD_IO_UART_NONE = 0,
PIOS_BOARD_IO_UART_TELEMETRY, /* com */
PIOS_BOARD_IO_UART_MAVLINK, /* com */
PIOS_BOARD_IO_UART_MSP, /* com */
PIOS_BOARD_IO_UART_GPS, /* com */
PIOS_BOARD_IO_UART_COMBRIDGE, /* com */
PIOS_BOARD_IO_UART_DEBUGCONSOLE, /* com */
PIOS_BOARD_IO_UART_OSDHK, /* com */
PIOS_BOARD_IO_UART_SBUS, /* rcvr */
PIOS_BOARD_IO_UART_DSM_MAIN, /* rcvr */
PIOS_BOARD_IO_UART_DSM_FLEXI, /* rcvr */
PIOS_BOARD_IO_UART_DSM_RCVR, /* rcvr */
PIOS_BOARD_IO_UART_HOTT_SUMD, /* rcvr */
PIOS_BOARD_IO_UART_HOTT_SUMH, /* rcvr */
PIOS_BOARD_IO_UART_SRXL, /* rcvr */
PIOS_BOARD_IO_UART_IBUS, /* rcvr */
PIOS_BOARD_IO_UART_EXBUS, /* rcvr */
// PIOS_BOARD_IO_UART_FRSKY_SPORT_TELEMETRY, /* com */
PIOS_BOARD_IO_UART_HOTT_BRIDGE, /* com */
} PIOS_BOARD_IO_UART_Function;
#ifdef PIOS_INCLUDE_USB
# ifndef BOOTLOADER
# include "uavobjectmanager.h"
# include "hwsettings.h"
void PIOS_BOARD_IO_Configure_USB();
typedef enum {
PIOS_BOARD_IO_USB_HID_NONE = HWSETTINGS_USB_HIDPORT_DISABLED,
PIOS_BOARD_IO_USB_HID_TELEMETRY = HWSETTINGS_USB_HIDPORT_USBTELEMETRY,
PIOS_BOARD_IO_USB_HID_RCTX = HWSETTINGS_USB_HIDPORT_RCTRANSMITTER,
} PIOS_BOARD_IO_USB_HID_Function;
typedef enum {
PIOS_BOARD_IO_USB_VCP_NONE = HWSETTINGS_USB_VCPPORT_DISABLED,
PIOS_BOARD_IO_USB_VCP_TELEMETRY = HWSETTINGS_USB_VCPPORT_USBTELEMETRY,
PIOS_BOARD_IO_USB_VCP_COMBRIDGE = HWSETTINGS_USB_VCPPORT_COMBRIDGE,
PIOS_BOARD_IO_USB_VCP_DEBUGCONSOLE = HWSETTINGS_USB_VCPPORT_DEBUGCONSOLE,
PIOS_BOARD_IO_USB_VCP_MAVLINK = HWSETTINGS_USB_VCPPORT_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 // ifndef BOOTLOADER
#endif // ifdef PIOS_INCLUDE_USB
#ifdef PIOS_INCLUDE_PWM
void PIOS_BOARD_IO_Configure_PWM_RCVR(const struct pios_pwm_cfg *pwm_cfg);
#endif
#ifdef PIOS_INCLUDE_PPM
void PIOS_BOARD_IO_Configure_PPM_RCVR(const struct pios_ppm_cfg *ppm_cfg);
#endif
#ifdef PIOS_INCLUDE_USART
void PIOS_BOARD_IO_Configure_UART(const struct pios_usart_cfg *usart_cfg, PIOS_BOARD_IO_UART_Function function);
void PIOS_BOARD_IO_Configure_UART_COM(const struct pios_usart_cfg *hw_config,
uint16_t rx_buf_len,
uint16_t tx_buf_len,
uint32_t *com_id);
#endif
#ifdef PIOS_INCLUDE_RFM22B
void PIOS_BOARD_IO_Configure_RFM22B();
void PIOS_BOARD_IO_Configure_RadioAuxStream(HwSettingsRadioAuxStreamOptions radioaux); /* not for OPLM */
#endif
#ifdef PIOS_INCLUDE_GCSRCVR
void PIOS_BOARD_IO_Configure_GCS_RCVR();
#endif
#endif /* PIOS_BOARD_IO_H */

View File

@ -0,0 +1,33 @@
/**
******************************************************************************
*
* @file pios_board_sensors.h
* @author The LibrePilot Project, http://www.librepilot.org Copyright (C) 2017.
* @brief board sensors setup
* --
* @see The GNU Public License (GPL) Version 3
*
*****************************************************************************/
/*
* This program is free software; you can redistribute it and/or modify
* it under the terms of the GNU General Public License as published by
* the Free Software Foundation; either version 3 of the License, or
* (at your option) any later version.
*
* This program is distributed in the hope that it will be useful, but
* WITHOUT ANY WARRANTY; without even the implied warranty of MERCHANTABILITY
* or FITNESS FOR A PARTICULAR PURPOSE. See the GNU General Public License
* for more details.
*
* You should have received a copy of the GNU General Public License along
* with this program; if not, write to the Free Software Foundation, Inc.,
* 59 Temple Place, Suite 330, Boston, MA 02111-1307 USA
*/
#ifndef PIOS_BOARD_SENSORS_H
#define PIOS_BOARD_SENSORS_H
#include "pios.h"
void PIOS_BOARD_Sensors_Configure();
#endif /* PIOS_BOARD_SENSORS_H */

View File

@ -70,10 +70,8 @@ enum PIOS_COM_Mode {
};
struct pios_com_driver {
void (*init)(uint32_t id);
void (*set_baud)(uint32_t id, uint32_t baud);
void (*set_halfduplex)(uint32_t id, bool halfduplex);
void (*set_config)(uint32_t usart_id, enum PIOS_COM_Word_Length word_len, enum PIOS_COM_StopBits stop_bits, enum PIOS_COM_Parity parity, uint32_t baud_rate, enum PIOS_COM_Mode mode);
void (*set_config)(uint32_t usart_id, enum PIOS_COM_Word_Length word_len, enum PIOS_COM_Parity parity, enum PIOS_COM_StopBits stop_bits, uint32_t baud_rate);
void (*set_ctrl_line)(uint32_t id, uint32_t mask, uint32_t state);
void (*tx_start)(uint32_t id, uint16_t tx_bytes_avail);
void (*rx_start)(uint32_t id, uint16_t rx_bytes_avail);
@ -83,6 +81,7 @@ struct pios_com_driver {
void (*bind_baud_rate_cb)(uint32_t id, pios_com_callback_baud_rate baud_rate_cb, uint32_t context);
uint32_t (*available)(uint32_t id);
void (*bind_available_cb)(uint32_t id, pios_com_callback_available available_cb, uint32_t context);
int32_t (*ioctl)(uint32_t id, uint32_t ctl, void *param);
};
/* Control line definitions */
@ -92,8 +91,7 @@ struct pios_com_driver {
/* Public Functions */
extern int32_t PIOS_COM_Init(uint32_t *com_id, const struct pios_com_driver *driver, uint32_t lower_id, uint8_t *rx_buffer, uint16_t rx_buffer_len, uint8_t *tx_buffer, uint16_t tx_buffer_len);
extern int32_t PIOS_COM_ChangeBaud(uint32_t com_id, uint32_t baud);
extern int32_t PIOS_COM_SetHalfDuplex(uint32_t com_id, bool halfduplex);
extern int32_t PIOS_COM_ChangeConfig(uint32_t com_id, enum PIOS_COM_Word_Length word_len, enum PIOS_COM_StopBits stop_bits, enum PIOS_COM_Parity parity, uint32_t baud_rate, enum PIOS_COM_Mode mode);
extern int32_t PIOS_COM_ChangeConfig(uint32_t com_id, enum PIOS_COM_Word_Length word_len, enum PIOS_COM_Parity parity, enum PIOS_COM_StopBits stop_bits, uint32_t baud_rate);
extern int32_t PIOS_COM_SetCtrlLine(uint32_t com_id, uint32_t mask, uint32_t state);
extern int32_t PIOS_COM_RegisterCtrlLineCallback(uint32_t usart_id, pios_com_callback_ctrl_line ctrl_line_cb, uint32_t context);
extern int32_t PIOS_COM_RegisterBaudRateCallback(uint32_t usart_id, pios_com_callback_baud_rate baud_rate_cb, uint32_t context);
@ -117,10 +115,38 @@ extern int32_t PIOS_COM_ASYNC_RegisterTxCallback(uint32_t id, pios_com_callback
extern void PIOS_COM_LinkComPair(uint32_t com1_id, uint32_t com2_id, bool link_ctrl_line, bool link_baud_rate);
#define COM_AVAILABLE_NONE (0)
#define COM_AVAILABLE_RX (1 << 0)
#define COM_AVAILABLE_TX (1 << 1)
#define COM_AVAILABLE_RXTX (COM_AVAILABLE_RX | COM_AVAILABLE_TX)
#define COM_AVAILABLE_NONE (0)
#define COM_AVAILABLE_RX (1 << 0)
#define COM_AVAILABLE_TX (1 << 1)
#define COM_AVAILABLE_RXTX (COM_AVAILABLE_RX | COM_AVAILABLE_TX)
/* ioctl */
extern int32_t PIOS_COM_Ioctl(uint32_t com_id, uint32_t ctl, void *param);
#define COM_IOCTL_NRBITS 16
#define COM_IOCTL_TYPEBITS 16
#define COM_IOCTL_NRMASK ((1 << COM_IOCTL_NRBITS) - 1)
#define COM_IOCTL_TYPEMASK ((1 << COM_IOCTL_TYPEBITS) - 1)
#define COM_IOCTL_NRSHIFT 0
#define COM_IOCTL_TYPESHIFT (COM_IOCTL_NRSHIFT + COM_IOCTL_NRBITS)
#define COM_IOCTL(type, nr, pt) \
(((type) << COM_IOCTL_TYPESHIFT) | \
((nr) << COM_IOCTL_NRSHIFT))
/* used to decode ioctl numbers.. */
#define COM_IOCTL_TYPE(nr) (((nr) >> COM_IOCTL_TYPESHIFT) & COM_IOCTL_TYPEMASK)
#define COM_IOCTL_NR(nr) (((nr) >> COM_IOCTL_NRSHIFT) & COM_IOCTL_NRMASK)
enum pios_com_ioctl_type {
COM_IOCTL_TYPE_USART,
COM_IOCTL_TYPE_USB_CDC,
COM_IOCTL_TYPE_SOFT_UART,
};
#define COM_IOCTL_ENOSYS (-1) /* Function not implemented */
#endif /* PIOS_COM_H */

View File

@ -109,15 +109,9 @@
*/
// #define DSM_LOST_FRAME_COUNTER
/* DSM receiver instance configuration */
struct pios_dsm_cfg {
struct stm32_gpio bind;
};
extern const struct pios_rcvr_driver pios_dsm_rcvr_driver;
extern int32_t PIOS_DSM_Init(uint32_t *dsm_id,
const struct pios_dsm_cfg *cfg,
const struct pios_com_driver *driver,
uint32_t lower_id,
uint8_t bind);

View File

@ -84,11 +84,12 @@
* S.Bus configuration programmable invertor
*/
struct pios_sbus_cfg {
struct stm32_gpio inv;
void (*gpio_clk_func)(uint32_t periph, FunctionalState state);
uint32_t gpio_clk_periph;
BitAction gpio_inv_enable;
BitAction gpio_inv_disable;
bool non_inverted;
// struct stm32_gpio inv;
// void (*gpio_clk_func)(uint32_t periph, FunctionalState state);
// uint32_t gpio_clk_periph;
// BitAction gpio_inv_enable;
// BitAction gpio_inv_disable;
};
extern const struct pios_rcvr_driver pios_sbus_rcvr_driver;

View File

@ -60,7 +60,13 @@ struct stm32_dma {
struct stm32_gpio {
GPIO_TypeDef *gpio;
GPIO_InitTypeDef init;
uint8_t pin_source;
uint8_t pin_source; /* do we really need this, or we can get it from init.GPIO_Pin ? */
};
struct stm32_gpio_action {
struct stm32_gpio pin;
BitAction on;
BitAction off;
};
/**

View File

@ -34,6 +34,28 @@
/* Global Types */
/* Public Functions */
/* USART Ioctls */
enum PIOS_USART_Inverted {
PIOS_USART_Inverted_None = 0,
PIOS_USART_Inverted_Rx = (1 << 0),
PIOS_USART_Inverted_Tx = (1 << 1),
PIOS_USART_Inverted_RxTx = (PIOS_USART_Inverted_Rx | PIOS_USART_Inverted_Tx)
};
#define PIOS_IOCTL_USART_SET_INVERTED COM_IOCTL(COM_IOCTL_TYPE_USART, 1, enum PIOS_USART_Inverted)
#define PIOS_IOCTL_USART_SET_SWAPPIN COM_IOCTL(COM_IOCTL_TYPE_USART, 2, bool)
#define PIOS_IOCTL_USART_SET_HALFDUPLEX COM_IOCTL(COM_IOCTL_TYPE_USART, 3, bool)
#define PIOS_IOCTL_USART_GET_RXGPIO COM_IOCTL(COM_IOCTL_TYPE_USART, 4, struct stm32_gpio)
#define PIOS_IOCTL_USART_GET_TXGPIO COM_IOCTL(COM_IOCTL_TYPE_USART, 5, struct stm32_gpio)
/* PIOS_IRQ_PRIO_ values */
#define PIOS_IOCTL_USART_SET_IRQ_PRIO COM_IOCTL(COM_IOCTL_TYPE_USART, 6, uint8_t)
#define PIOS_IOCTL_USART_GET_DSMBIND COM_IOCTL(COM_IOCTL_TYPE_USART, 7, struct stm32_gpio)
#endif /* PIOS_USART_H */
/**

View File

@ -41,15 +41,17 @@ extern const struct pios_com_driver pios_usart_com_driver;
struct pios_usart_cfg {
USART_TypeDef *regs;
uint32_t remap; /* GPIO_Remap_* */
USART_InitTypeDef init;
struct stm32_gpio rx;
struct stm32_gpio tx;
struct stm32_gpio dtr;
struct stm32_irq irq;
/* provide hook for board specific ioctls */
int32_t (*ioctl)(uint32_t id, uint32_t ctl, void *param);
};
extern int32_t PIOS_USART_Init(uint32_t *usart_id, const struct pios_usart_cfg *cfg);
extern const struct pios_usart_cfg *PIOS_USART_GetConfig(uint32_t usart_id);
const struct pios_usart_cfg *PIOS_USART_GetConfig(uint32_t usart_id);
#endif /* PIOS_USART_PRIV_H */

View File

@ -31,9 +31,20 @@
#define PIOS_USB_DESC_HID_CDC_PRIV_H
#include <stdint.h>
#include <pios_usb_hid_priv.h>
#include <pios_usb_cdc_priv.h>
#ifdef PIOS_INCLUDE_USB_RCTX
# include <pios_usb_rctx_priv.h>
#endif
extern int32_t PIOS_USB_DESC_HID_CDC_Init(void);
extern const struct pios_usb_cdc_cfg pios_usb_cdc_cfg;
extern const struct pios_usb_hid_cfg pios_usb_hid_cfg;
#ifdef PIOS_INCLUDE_USB_RCTX
extern const struct pios_usb_rctx_cfg pios_usb_rctx_cfg;
#endif
#endif /* PIOS_USB_DESC_HID_CDC_PRIV_H */
/**

View File

@ -31,9 +31,13 @@
#define PIOS_USB_DESC_HID_ONLY_PRIV_H
#include <stdint.h>
#include <pios_usb_hid_priv.h>
extern int32_t PIOS_USB_DESC_HID_ONLY_Init(void);
extern const struct pios_usb_hid_cfg pios_usb_hid_only_cfg;
#endif /* PIOS_USB_DESC_HID_ONLY_PRIV_H */
/**

View File

@ -38,7 +38,9 @@
#define PIOS_UART_TX_BUFFER 10
/* Provide a COM driver */
static void PIOS_USART_ChangeBaud(uint32_t usart_id, uint32_t baud);
static void PIOS_USART_ChangeConfig(uint32_t usart_id, enum PIOS_COM_Word_Length word_len, enum PIOS_COM_StopBits stop_bits, enum PIOS_COM_Parity parity, uint32_t baud_rate, enum PIOS_COM_Mode mode);
#ifndef BOOTLOADER
static void PIOS_USART_ChangeConfig(uint32_t usart_id, enum PIOS_COM_Word_Length word_len, enum PIOS_COM_Parity parity, enum PIOS_COM_StopBits stop_bits, uint32_t baud_rate);
#endif
static void PIOS_USART_RegisterRxCallback(uint32_t usart_id, pios_com_callback rx_in_cb, uint32_t context);
static void PIOS_USART_RegisterTxCallback(uint32_t usart_id, pios_com_callback tx_out_cb, uint32_t context);
static void PIOS_USART_TxStart(uint32_t usart_id, uint16_t tx_bytes_avail);
@ -46,7 +48,9 @@ static void PIOS_USART_RxStart(uint32_t usart_id, uint16_t rx_bytes_avail);
const struct pios_com_driver pios_usart_com_driver = {
.set_baud = PIOS_USART_ChangeBaud,
#ifndef BOOTLOADER
.set_config = PIOS_USART_ChangeConfig,
#endif
.tx_start = PIOS_USART_TxStart,
.rx_start = PIOS_USART_RxStart,
.bind_tx_cb = PIOS_USART_RegisterTxCallback,
@ -71,6 +75,7 @@ struct pios_usart_dev {
uint8_t tx_buffer[PIOS_UART_TX_BUFFER];
uint8_t tx_len;
uint8_t tx_pos;
uint8_t irq_channel;
};
static struct pios_usart_dev *PIOS_USART_validate(uint32_t usart_id)
@ -138,13 +143,27 @@ static void PIOS_USART_2_irq_handler(void)
{
PIOS_USART_generic_irq_handler(PIOS_USART_2_id);
}
#if defined(STM32F072)
static uint32_t PIOS_USART_3_id;
void USART3_IRQHandler(void) __attribute__((alias("PIOS_USART_3_irq_handler")));
static void PIOS_USART_3_irq_handler(void)
{
PIOS_USART_generic_irq_handler(PIOS_USART_3_id);
}
#endif
static int32_t PIOS_USART_SetIrqPrio(struct pios_usart_dev *usart_dev, uint8_t irq_prio)
{
NVIC_InitTypeDef init = {
.NVIC_IRQChannel = usart_dev->irq_channel,
.NVIC_IRQChannelPriority = irq_prio,
.NVIC_IRQChannelCmd = ENABLE,
};
NVIC_Init(&init);
return 0;
}
/**
* Initialise a single USART device
@ -162,52 +181,80 @@ int32_t PIOS_USART_Init(uint32_t *usart_id, const struct pios_usart_cfg *cfg)
}
/* Bind the configuration to the device instance */
usart_dev->cfg = cfg;
usart_dev->cfg = cfg;
/* Copy the comm parameter structure */
usart_dev->init = cfg->init;
/* Initialize the comm parameter structure */
USART_StructInit(&usart_dev->init); // 9600 8n1
/* Enable the USART Pins Software Remapping */
if (usart_dev->cfg->remap) {
GPIO_PinAFConfig(cfg->rx.gpio, __builtin_ctz(cfg->rx.init.GPIO_Pin), cfg->remap);
GPIO_PinAFConfig(cfg->tx.gpio, __builtin_ctz(cfg->tx.init.GPIO_Pin), cfg->remap);
}
/* Initialize the USART Rx and Tx pins */
GPIO_Init(cfg->rx.gpio, (GPIO_InitTypeDef *)&cfg->rx.init);
GPIO_Init(cfg->tx.gpio, (GPIO_InitTypeDef *)&cfg->tx.init);
/* We will set modes later, depending on installed callbacks */
usart_dev->init.USART_Mode = 0;
/* Enable USART clock */
switch ((uint32_t)cfg->regs) {
case (uint32_t)USART1:
RCC_APB2PeriphClockCmd(RCC_APB2Periph_USART1, ENABLE);
PIOS_USART_1_id = (uint32_t)usart_dev;
usart_dev->irq_channel = USART1_IRQn;
break;
case (uint32_t)USART2:
RCC_APB1PeriphClockCmd(RCC_APB1Periph_USART2, ENABLE);
PIOS_USART_2_id = (uint32_t)usart_dev;
usart_dev->irq_channel = USART2_IRQn;
break;
#if defined(STM32F072)
case (uint32_t)USART3:
RCC_APB1PeriphClockCmd(RCC_APB1Periph_USART3, ENABLE);
PIOS_USART_3_id = (uint32_t)usart_dev;
usart_dev->irq_channel = USART3_4_IRQn;
break;
#endif
}
/* Configure the USART */
USART_Init(cfg->regs, (USART_InitTypeDef *)&usart_dev->init);
*usart_id = (uint32_t)usart_dev;
NVIC_Init((NVIC_InitTypeDef *)&cfg->irq.init);
USART_ITConfig(cfg->regs, USART_IT_RXNE, ENABLE);
USART_ITConfig(cfg->regs, USART_IT_TXE, ENABLE);
USART_ITConfig(cfg->regs, USART_IT_ORE, DISABLE);
USART_ITConfig(cfg->regs, USART_IT_TC, DISABLE);
/* Enable USART */
USART_Cmd(cfg->regs, ENABLE);
PIOS_USART_SetIrqPrio(usart_dev, PIOS_IRQ_PRIO_MID);
/* Disable overrun detection */
USART_OverrunDetectionConfig(usart_dev->cfg->regs, USART_OVRDetection_Disable);
return 0;
}
static void PIOS_USART_Setup(struct pios_usart_dev *usart_dev)
{
/* Configure RX GPIO */
if ((usart_dev->init.USART_Mode & USART_Mode_Rx) && (usart_dev->cfg->rx.gpio)) {
if (usart_dev->cfg->remap) {
GPIO_PinAFConfig(usart_dev->cfg->rx.gpio,
__builtin_ctz(usart_dev->cfg->rx.init.GPIO_Pin),
usart_dev->cfg->remap);
}
GPIO_Init(usart_dev->cfg->rx.gpio, (GPIO_InitTypeDef *)&usart_dev->cfg->rx.init);
USART_ITConfig(usart_dev->cfg->regs, USART_IT_RXNE, ENABLE);
}
/* Configure TX GPIO */
if ((usart_dev->init.USART_Mode & USART_Mode_Tx) && usart_dev->cfg->tx.gpio) {
if (usart_dev->cfg->remap) {
GPIO_PinAFConfig(usart_dev->cfg->tx.gpio,
__builtin_ctz(usart_dev->cfg->tx.init.GPIO_Pin),
usart_dev->cfg->remap);
}
GPIO_Init(usart_dev->cfg->tx.gpio, (GPIO_InitTypeDef *)&usart_dev->cfg->tx.init);
}
/* Write new configuration */
USART_Init(usart_dev->cfg->regs, &usart_dev->init);
/*
* Re enable USART.
*/
USART_Cmd(usart_dev->cfg->regs, ENABLE);
}
static void PIOS_USART_RxStart(uint32_t usart_id, __attribute__((unused)) uint16_t rx_bytes_avail)
{
const struct pios_usart_dev *usart_dev = PIOS_USART_validate(usart_id);
@ -233,12 +280,9 @@ static void PIOS_USART_ChangeBaud(uint32_t usart_id, uint32_t baud)
/* Use our working copy of the usart init structure */
usart_dev->init.USART_BaudRate = baud;
/* Write back the modified configuration */
USART_Init(usart_dev->cfg->regs, &usart_dev->init);
USART_Cmd(usart_dev->cfg->regs, ENABLE);
PIOS_USART_Setup(usart_dev);
}
#ifndef BOOTLOADER
/**
* Changes configuration of the USART peripheral without re-initialising.
* \param[in] usart_id USART name (GPS, TELEM, AUX)
@ -251,10 +295,9 @@ static void PIOS_USART_ChangeBaud(uint32_t usart_id, uint32_t baud)
*/
static void PIOS_USART_ChangeConfig(uint32_t usart_id,
enum PIOS_COM_Word_Length word_len,
enum PIOS_COM_StopBits stop_bits,
enum PIOS_COM_Parity parity,
uint32_t baud_rate,
enum PIOS_COM_Mode mode)
enum PIOS_COM_StopBits stop_bits,
uint32_t baud_rate)
{
struct pios_usart_dev *usart_dev = PIOS_USART_validate(usart_id);
@ -301,28 +344,9 @@ static void PIOS_USART_ChangeConfig(uint32_t usart_id,
usart_dev->init.USART_BaudRate = baud_rate;
}
switch (mode) {
case PIOS_COM_Mode_Rx:
usart_dev->init.USART_Mode = USART_Mode_Rx;
break;
case PIOS_COM_Mode_Tx:
usart_dev->init.USART_Mode = USART_Mode_Tx;
break;
case PIOS_COM_Mode_RxTx:
usart_dev->init.USART_Mode = USART_Mode_Rx | USART_Mode_Tx;
break;
default:
break;
}
/* Write back the modified configuration */
USART_Init(usart_dev->cfg->regs, &usart_dev->init);
/*
* Re enable USART.
*/
USART_Cmd(usart_dev->cfg->regs, ENABLE);
PIOS_USART_Setup(usart_dev);
}
#endif /* BOOTLOADER */
static void PIOS_USART_RegisterRxCallback(uint32_t usart_id, pios_com_callback rx_in_cb, uint32_t context)
{
@ -332,8 +356,12 @@ static void PIOS_USART_RegisterRxCallback(uint32_t usart_id, pios_com_callback r
* Order is important in these assignments since ISR uses _cb
* field to determine if it's ok to dereference _cb and _context
*/
usart_dev->rx_in_context = context;
usart_dev->rx_in_context = context;
usart_dev->rx_in_cb = rx_in_cb;
usart_dev->init.USART_Mode |= USART_Mode_Rx;
PIOS_USART_Setup(usart_dev);
}
static void PIOS_USART_RegisterTxCallback(uint32_t usart_id, pios_com_callback tx_out_cb, uint32_t context)
@ -344,8 +372,12 @@ static void PIOS_USART_RegisterTxCallback(uint32_t usart_id, pios_com_callback t
* Order is important in these assignments since ISR uses _cb
* field to determine if it's ok to dereference _cb and _context
*/
usart_dev->tx_out_context = context;
usart_dev->tx_out_context = context;
usart_dev->tx_out_cb = tx_out_cb;
usart_dev->init.USART_Mode |= USART_Mode_Tx;
PIOS_USART_Setup(usart_dev);
}
static void PIOS_USART_generic_irq_handler(uint32_t usart_id)
@ -358,8 +390,8 @@ static void PIOS_USART_generic_irq_handler(uint32_t usart_id)
/* Check if RXNE flag is set */
bool rx_need_yield = false;
if (USART_GetITStatus(usart_dev->cfg->regs, USART_IT_RXNE) != RESET) {
uint8_t byte = USART_ReceiveData(usart_dev->cfg->regs) & 0x00FF;
if (usart_dev->cfg->regs->ISR & USART_ISR_RXNE) {
uint8_t byte = usart_dev->cfg->regs->RDR & 0xFF;
if (usart_dev->rx_in_cb) {
uint16_t rc;
rc = (usart_dev->rx_in_cb)(usart_dev->rx_in_context, &byte, 1, NULL, &rx_need_yield);
@ -372,7 +404,7 @@ static void PIOS_USART_generic_irq_handler(uint32_t usart_id)
/* Check if TXE flag is set */
bool tx_need_yield = false;
if (USART_GetITStatus(usart_dev->cfg->regs, USART_IT_TXE) != RESET) {
if (usart_dev->cfg->regs->ISR & USART_ISR_TXE) {
if (usart_dev->tx_out_cb) {
if (!usart_dev->tx_len) {
usart_dev->tx_len = (usart_dev->tx_out_cb)(usart_dev->tx_out_context, usart_dev->tx_buffer, PIOS_UART_TX_BUFFER, NULL, &tx_need_yield);
@ -380,19 +412,18 @@ static void PIOS_USART_generic_irq_handler(uint32_t usart_id)
}
if (usart_dev->tx_len > 0) {
/* Send the byte we've been given */
USART_SendData(usart_dev->cfg->regs, usart_dev->tx_buffer[usart_dev->tx_pos++]);
usart_dev->cfg->regs->TDR = usart_dev->tx_buffer[usart_dev->tx_pos++];
usart_dev->tx_len--;
} else {
/* No bytes to send, disable TXE interrupt */
USART_ITConfig(usart_dev->cfg->regs, USART_IT_TXE, DISABLE);
usart_dev->cfg->regs->CR1 &= ~(USART_CR1_TXEIE);
}
} else {
/* No bytes to send, disable TXE interrupt */
USART_ITConfig(usart_dev->cfg->regs, USART_IT_TXE, DISABLE);
usart_dev->cfg->regs->CR1 &= ~(USART_CR1_TXEIE);
}
}
USART_ClearITPendingBit(usart_dev->cfg->regs, USART_IT_ORE);
USART_ClearITPendingBit(usart_dev->cfg->regs, USART_IT_TC);
usart_dev->cfg->regs->ICR = USART_ICR_ORECF | USART_ICR_TCCF;
#if defined(PIOS_INCLUDE_FREERTOS)
if (rx_need_yield || tx_need_yield) {
vPortYield();

View File

@ -0,0 +1,49 @@
/**
******************************************************************************
*
* @file pios_servp_config.h
* @author The LibrePilot Project, http://www.librepilot.org Copyright (C) 2017.
* @brief Architecture specific macros and definitions
* --
* @see The GNU Public License (GPL) Version 3
*
*****************************************************************************/
/*
* This program is free software; you can redistribute it and/or modify
* it under the terms of the GNU General Public License as published by
* the Free Software Foundation; either version 3 of the License, or
* (at your option) any later version.
*
* This program is distributed in the hope that it will be useful, but
* WITHOUT ANY WARRANTY; without even the implied warranty of MERCHANTABILITY
* or FITNESS FOR A PARTICULAR PURPOSE. See the GNU General Public License
* for more details.
*
* You should have received a copy of the GNU General Public License along
* with this program; if not, write to the Free Software Foundation, Inc.,
* 59 Temple Place, Suite 330, Boston, MA 02111-1307 USA
*/
#ifndef PIOS_SERVO_CONFIG_H_
#define PIOS_SERVO_CONFIG_H_
/**
* Generic servo pin configuration structure for an STM32F10x
*/
#define TIM_SERVO_CHANNEL_CONFIG(_timer, _channel, _gpio, _pin, _remap) \
{ \
.timer = _timer, \
.timer_chan = TIM_Channel_##_channel, \
.pin = { \
.gpio = GPIO##_gpio, \
.init = { \
.GPIO_Pin = GPIO_Pin_##_pin, \
.GPIO_Mode = GPIO_Mode_IPD, \
.GPIO_Speed = GPIO_Speed_2MHz, \
}, \
.pin_source = GPIO_PinSource##_pin, \
}, \
.remap = _remap, \
}
#endif /* PIOS_SERVO_CONFIG_H_ */

View File

@ -1,438 +0,0 @@
/**
******************************************************************************
* @addtogroup PIOS PIOS Core hardware abstraction layer
* @{
* @addtogroup PIOS_DSM Spektrum/JR DSMx satellite receiver functions
* @brief Code to bind and read Spektrum/JR DSMx satellite receiver serial stream
* @{
*
* @file pios_dsm.c
* @author The OpenPilot Team, http://www.openpilot.org Copyright (C) 2011.
* @brief Code bind and read Spektrum/JR DSMx satellite receiver serial stream
* @see The GNU Public License (GPL) Version 3
*
*****************************************************************************/
/*
* This program is free software; you can redistribute it and/or modify
* it under the terms of the GNU General Public License as published by
* the Free Software Foundation; either version 3 of the License, or
* (at your option) any later version.
*
* This program is distributed in the hope that it will be useful, but
* WITHOUT ANY WARRANTY; without even the implied warranty of MERCHANTABILITY
* or FITNESS FOR A PARTICULAR PURPOSE. See the GNU General Public License
* for more details.
*
* You should have received a copy of the GNU General Public License along
* with this program; if not, write to the Free Software Foundation, Inc.,
* 59 Temple Place, Suite 330, Boston, MA 02111-1307 USA
*/
#include "pios.h"
#ifdef PIOS_INCLUDE_DSM
#include "pios_dsm_priv.h"
// *** UNTESTED CODE ***
#undef DSM_LINK_QUALITY
/* Forward Declarations */
static int32_t PIOS_DSM_Get(uint32_t rcvr_id, uint8_t channel);
static uint8_t PIOS_DSM_Quality_Get(uint32_t rcvr_id);
static uint16_t PIOS_DSM_RxInCallback(uint32_t context,
uint8_t *buf,
uint16_t buf_len,
uint16_t *headroom,
bool *need_yield);
static void PIOS_DSM_Supervisor(uint32_t dsm_id);
/* Local Variables */
const struct pios_rcvr_driver pios_dsm_rcvr_driver = {
.read = PIOS_DSM_Get,
.get_quality = PIOS_DSM_Quality_Get
};
enum pios_dsm_dev_magic {
PIOS_DSM_DEV_MAGIC = 0x44534d78,
};
struct pios_dsm_state {
uint16_t channel_data[PIOS_DSM_NUM_INPUTS];
uint8_t received_data[DSM_FRAME_LENGTH];
uint8_t receive_timer;
uint8_t failsafe_timer;
uint8_t frame_found;
uint8_t byte_count;
uint8_t frames_lost_last;
float quality;
};
/* With an DSM frame rate of 11ms (90Hz) averaging over 18 samples
* gives about a 200ms response.
*/
#define DSM_FL_WEIGHTED_AVE 18
struct pios_dsm_dev {
enum pios_dsm_dev_magic magic;
const struct pios_dsm_cfg *cfg;
struct pios_dsm_state state;
};
/* Allocate DSM device descriptor */
#if defined(PIOS_INCLUDE_FREERTOS)
static struct pios_dsm_dev *PIOS_DSM_Alloc(void)
{
struct pios_dsm_dev *dsm_dev;
dsm_dev = (struct pios_dsm_dev *)pios_malloc(sizeof(*dsm_dev));
if (!dsm_dev) {
return NULL;
}
dsm_dev->magic = PIOS_DSM_DEV_MAGIC;
return dsm_dev;
}
#else
static struct pios_dsm_dev pios_dsm_devs[PIOS_DSM_MAX_DEVS];
static uint8_t pios_dsm_num_devs;
static struct pios_dsm_dev *PIOS_DSM_Alloc(void)
{
struct pios_dsm_dev *dsm_dev;
if (pios_dsm_num_devs >= PIOS_DSM_MAX_DEVS) {
return NULL;
}
dsm_dev = &pios_dsm_devs[pios_dsm_num_devs++];
dsm_dev->magic = PIOS_DSM_DEV_MAGIC;
return dsm_dev;
}
#endif /* if defined(PIOS_INCLUDE_FREERTOS) */
/* Validate DSM device descriptor */
static bool PIOS_DSM_Validate(struct pios_dsm_dev *dsm_dev)
{
return dsm_dev->magic == PIOS_DSM_DEV_MAGIC;
}
/* Try to bind DSMx satellite using specified number of pulses */
static void PIOS_DSM_Bind(struct pios_dsm_dev *dsm_dev, uint8_t bind)
{
const struct pios_dsm_cfg *cfg = dsm_dev->cfg;
GPIO_InitTypeDef GPIO_InitStructure;
GPIO_InitStructure.GPIO_Pin = cfg->bind.init.GPIO_Pin;
GPIO_InitStructure.GPIO_Speed = cfg->bind.init.GPIO_Speed;
GPIO_InitStructure.GPIO_Mode = GPIO_Mode_IPU;
/* just to limit bind pulses */
if (bind > 10) {
bind = 10;
}
GPIO_Init(cfg->bind.gpio, &cfg->bind.init);
/* RX line, set high */
GPIO_SetBits(cfg->bind.gpio, cfg->bind.init.GPIO_Pin);
/* on CC works up to 140ms, guess bind window is around 20-140ms after power up */
PIOS_DELAY_WaitmS(20);
for (int i = 0; i < bind; i++) {
/* RX line, drive low for 120us */
GPIO_ResetBits(cfg->bind.gpio, cfg->bind.init.GPIO_Pin);
PIOS_DELAY_WaituS(120);
/* RX line, drive high for 120us */
GPIO_SetBits(cfg->bind.gpio, cfg->bind.init.GPIO_Pin);
PIOS_DELAY_WaituS(120);
}
/* RX line, set input and wait for data */
GPIO_Init(cfg->bind.gpio, &GPIO_InitStructure);
}
/* Reset channels in case of lost signal or explicit failsafe receiver flag */
static void PIOS_DSM_ResetChannels(struct pios_dsm_dev *dsm_dev)
{
struct pios_dsm_state *state = &(dsm_dev->state);
for (int i = 0; i < PIOS_DSM_NUM_INPUTS; i++) {
state->channel_data[i] = PIOS_RCVR_TIMEOUT;
}
}
/* Reset DSM receiver state */
static void PIOS_DSM_ResetState(struct pios_dsm_dev *dsm_dev)
{
struct pios_dsm_state *state = &(dsm_dev->state);
state->receive_timer = 0;
state->failsafe_timer = 0;
state->frame_found = 0;
state->quality = 0.0f;
state->frames_lost_last = 0;
PIOS_DSM_ResetChannels(dsm_dev);
}
/**
* Check and unroll complete frame data.
* \output 0 frame data accepted
* \output -1 frame error found
*/
static int PIOS_DSM_UnrollChannels(struct pios_dsm_dev *dsm_dev)
{
struct pios_dsm_state *state = &(dsm_dev->state);
/* Fix resolution for detection. */
static uint8_t resolution = 11;
uint32_t channel_log = 0;
// *** UNTESTED CODE ***
#ifdef DSM_LINK_QUALITY
/* increment the lost frame counter */
uint8_t frames_lost = state->received_data[0];
/* We only get a lost frame count when the next good frame comes in */
/* Present quality as a weighted average of good frames */
/* First consider the bad frames */
for (int i = 0; i < frames_lost - state->frames_lost_last; i++) {
state->quality = (state->quality * (DSM_FL_WEIGHTED_AVE - 1)) /
DSM_FL_WEIGHTED_AVE;
}
/* And now the good frame */
state->quality = ((state->quality * (DSM_FL_WEIGHTED_AVE - 1)) +
100) / DSM_FL_WEIGHTED_AVE;
state->frames_lost_last = frames_lost;
#endif /* DSM_LINK_QUALITY */
/* unroll channels */
uint8_t *s = &(state->received_data[2]);
uint16_t mask = (resolution == 10) ? 0x03ff : 0x07ff;
for (int i = 0; i < DSM_CHANNELS_PER_FRAME; i++) {
uint16_t word = ((uint16_t)s[0] << 8) | s[1];
s += 2;
/* skip empty channel slot */
if (word == 0xffff) {
continue;
}
/* minimal data validation */
if ((i > 0) && (word & DSM_2ND_FRAME_MASK)) {
/* invalid frame data, ignore rest of the frame */
goto stream_error;
}
/* extract and save the channel value */
uint8_t channel_num = (word >> resolution) & 0x0f;
if (channel_num < PIOS_DSM_NUM_INPUTS) {
if (channel_log & (1 << channel_num)) {
/* Found duplicate. This should happen when in 11 bit */
/* mode and the data is 10 bits */
if (resolution == 10) {
return -1;
}
resolution = 10;
return PIOS_DSM_UnrollChannels(dsm_dev);
}
if ((channel_log & 0xFF) == 0x55) {
/* This pattern indicates 10 bit pattern */
if (resolution == 11) {
return -1;
}
resolution = 11;
return PIOS_DSM_UnrollChannels(dsm_dev);
}
state->channel_data[channel_num] = (word & mask);
/* keep track of this channel */
channel_log |= (1 << channel_num);
}
}
/* all channels processed */
return 0;
stream_error:
/* either DSM2 selected with DSMX stream found, or vice-versa */
return -1;
}
/* Update decoder state processing input byte from the DSMx stream */
static void PIOS_DSM_UpdateState(struct pios_dsm_dev *dsm_dev, uint8_t byte)
{
struct pios_dsm_state *state = &(dsm_dev->state);
if (state->frame_found) {
/* receiving the data frame */
if (state->byte_count < DSM_FRAME_LENGTH) {
/* store next byte */
state->received_data[state->byte_count++] = byte;
if (state->byte_count == DSM_FRAME_LENGTH) {
/* full frame received - process and wait for new one */
if (!PIOS_DSM_UnrollChannels(dsm_dev)) {
/* data looking good */
state->failsafe_timer = 0;
}
/* prepare for the next frame */
state->frame_found = 0;
}
}
}
}
/* Initialise DSM receiver interface */
int32_t PIOS_DSM_Init(uint32_t *dsm_id,
const struct pios_dsm_cfg *cfg,
const struct pios_com_driver *driver,
uint32_t lower_id,
uint8_t bind)
{
PIOS_DEBUG_Assert(dsm_id);
PIOS_DEBUG_Assert(cfg);
PIOS_DEBUG_Assert(driver);
struct pios_dsm_dev *dsm_dev;
dsm_dev = (struct pios_dsm_dev *)PIOS_DSM_Alloc();
if (!dsm_dev) {
return -1;
}
/* Bind the configuration to the device instance */
dsm_dev->cfg = cfg;
/* Bind the receiver if requested */
if (bind) {
PIOS_DSM_Bind(dsm_dev, bind);
}
PIOS_DSM_ResetState(dsm_dev);
*dsm_id = (uint32_t)dsm_dev;
/* Set comm driver callback */
(driver->bind_rx_cb)(lower_id, PIOS_DSM_RxInCallback, *dsm_id);
if (!PIOS_RTC_RegisterTickCallback(PIOS_DSM_Supervisor, *dsm_id)) {
PIOS_DEBUG_Assert(0);
}
return 0;
}
/* Comm byte received callback */
static uint16_t PIOS_DSM_RxInCallback(uint32_t context,
uint8_t *buf,
uint16_t buf_len,
uint16_t *headroom,
bool *need_yield)
{
struct pios_dsm_dev *dsm_dev = (struct pios_dsm_dev *)context;
bool valid = PIOS_DSM_Validate(dsm_dev);
PIOS_Assert(valid);
/* process byte(s) and clear receive timer */
for (uint8_t i = 0; i < buf_len; i++) {
PIOS_DSM_UpdateState(dsm_dev, buf[i]);
dsm_dev->state.receive_timer = 0;
}
/* Always signal that we can accept another byte */
if (headroom) {
*headroom = DSM_FRAME_LENGTH;
}
/* We never need a yield */
*need_yield = false;
/* Always indicate that all bytes were consumed */
return buf_len;
}
/**
* Get the value of an input channel
* \param[in] channel Number of the channel desired (zero based)
* \output PIOS_RCVR_INVALID channel not available
* \output PIOS_RCVR_TIMEOUT failsafe condition or missing receiver
* \output >=0 channel value
*/
static int32_t PIOS_DSM_Get(uint32_t rcvr_id, uint8_t channel)
{
struct pios_dsm_dev *dsm_dev = (struct pios_dsm_dev *)rcvr_id;
if (!PIOS_DSM_Validate(dsm_dev)) {
return PIOS_RCVR_INVALID;
}
/* return error if channel is not available */
if (channel >= PIOS_DSM_NUM_INPUTS) {
return PIOS_RCVR_INVALID;
}
/* may also be PIOS_RCVR_TIMEOUT set by other function */
return dsm_dev->state.channel_data[channel];
}
/**
* Input data supervisor is called periodically and provides
* two functions: frame syncing and failsafe triggering.
*
* DSM frames come at 11ms or 22ms rate at 115200bps.
* RTC timer is running at 625Hz (1.6ms). So with divider 5 it gives
* 8ms pause between frames which is good for both DSM frame rates.
*
* Data receive function must clear the receive_timer to confirm new
* data reception. If no new data received in 100ms, we must call the
* failsafe function which clears all channels.
*/
static void PIOS_DSM_Supervisor(uint32_t dsm_id)
{
struct pios_dsm_dev *dsm_dev = (struct pios_dsm_dev *)dsm_id;
bool valid = PIOS_DSM_Validate(dsm_dev);
PIOS_Assert(valid);
struct pios_dsm_state *state = &(dsm_dev->state);
/* waiting for new frame if no bytes were received in 8ms */
if (++state->receive_timer > 4) {
state->frame_found = 1;
state->byte_count = 0;
state->receive_timer = 0;
}
/* activate failsafe if no frames have arrived in 102.4ms */
if (++state->failsafe_timer > 64) {
PIOS_DSM_ResetChannels(dsm_dev);
state->failsafe_timer = 0;
}
}
static uint8_t PIOS_DSM_Quality_Get(uint32_t dsm_id)
{
struct pios_dsm_dev *dsm_dev = (struct pios_dsm_dev *)dsm_id;
bool valid = PIOS_DSM_Validate(dsm_dev);
PIOS_Assert(valid);
struct pios_dsm_state *state = &(dsm_dev->state);
return (uint8_t)(state->quality + 0.5f);
}
#endif /* PIOS_INCLUDE_DSM */
/**
* @}
* @}
*/

View File

@ -53,9 +53,63 @@ void PIOS_SYS_Init(void)
/* Init the delay system */
PIOS_DELAY_Init();
/* Enable GPIOA, GPIOB, GPIOC, GPIOD, GPIOE and AFIO clocks */
RCC_APB2PeriphClockCmd(RCC_APB2Periph_GPIOA | RCC_APB2Periph_GPIOB | RCC_APB2Periph_GPIOC | RCC_APB2Periph_GPIOD | RCC_APB2Periph_GPIOE |
RCC_APB2Periph_AFIO, ENABLE);
/*
* Turn on all the peripheral clocks.
* Micromanaging clocks makes no sense given the power situation in the system, so
* light up everything we might reasonably use here and just leave it on.
*/
RCC_AHBPeriphClockCmd(RCC_AHBPeriph_DMA1 |
RCC_AHBPeriph_DMA2,
ENABLE);
RCC_APB1PeriphClockCmd(RCC_APB1Periph_TIM2 |
RCC_APB1Periph_TIM3 |
RCC_APB1Periph_TIM4 |
RCC_APB1Periph_TIM5 |
RCC_APB1Periph_TIM6 |
RCC_APB1Periph_TIM7 |
RCC_APB1Periph_TIM12 |
RCC_APB1Periph_TIM13 |
RCC_APB1Periph_TIM14 |
RCC_APB1Periph_WWDG |
RCC_APB1Periph_SPI2 |
RCC_APB1Periph_SPI3 |
RCC_APB1Periph_USART2 |
RCC_APB1Periph_USART3 |
RCC_APB1Periph_UART4 |
RCC_APB1Periph_UART5 |
RCC_APB1Periph_I2C1 |
RCC_APB1Periph_I2C2 |
RCC_APB1Periph_USB |
// RCC_APB1Periph_CAN1 | /* bxCAN unfortunately interferes with USB */
// RCC_APB1Periph_CAN2 |
RCC_APB1Periph_BKP |
RCC_APB1Periph_PWR |
RCC_APB1Periph_DAC,
ENABLE);
RCC_APB2PeriphClockCmd(RCC_APB2Periph_GPIOA |
RCC_APB2Periph_GPIOB |
RCC_APB2Periph_GPIOC |
RCC_APB2Periph_GPIOD |
RCC_APB2Periph_GPIOE |
RCC_APB2Periph_ADC1 |
RCC_APB2Periph_ADC2 |
RCC_APB2Periph_ADC3 |
RCC_APB2Periph_TIM1 |
RCC_APB2Periph_TIM8 |
RCC_APB2Periph_TIM9 |
RCC_APB2Periph_TIM10 |
RCC_APB2Periph_TIM11 |
RCC_APB2Periph_TIM15 |
RCC_APB2Periph_TIM16 |
RCC_APB2Periph_TIM17 |
RCC_APB2Periph_SPI1 |
RCC_APB2Periph_USART1 |
RCC_APB2Periph_AFIO,
ENABLE);
#if (PIOS_USB_ENABLED)
/* Ensure that pull-up is active on detect pin */

View File

@ -37,12 +37,13 @@
#include <pios_usart.h>
/* Provide a COM driver */
static void PIOS_USART_ChangeConfig(uint32_t usart_id, enum PIOS_COM_Word_Length word_len, enum PIOS_COM_StopBits stop_bits, enum PIOS_COM_Parity parity, uint32_t baud_rate, enum PIOS_COM_Mode mode);
static void PIOS_USART_ChangeConfig(uint32_t usart_id, enum PIOS_COM_Word_Length word_len, enum PIOS_COM_Parity parity, enum PIOS_COM_StopBits stop_bits, uint32_t baud_rate);
static void PIOS_USART_ChangeBaud(uint32_t usart_id, uint32_t baud);
static void PIOS_USART_RegisterRxCallback(uint32_t usart_id, pios_com_callback rx_in_cb, uint32_t context);
static void PIOS_USART_RegisterTxCallback(uint32_t usart_id, pios_com_callback tx_out_cb, uint32_t context);
static void PIOS_USART_TxStart(uint32_t usart_id, uint16_t tx_bytes_avail);
static void PIOS_USART_RxStart(uint32_t usart_id, uint16_t rx_bytes_avail);
static int32_t PIOS_USART_Ioctl(uint32_t usart_id, uint32_t ctl, void *param);
const struct pios_com_driver pios_usart_com_driver = {
.set_baud = PIOS_USART_ChangeBaud,
@ -51,6 +52,7 @@ const struct pios_com_driver pios_usart_com_driver = {
.rx_start = PIOS_USART_RxStart,
.bind_tx_cb = PIOS_USART_RegisterTxCallback,
.bind_rx_cb = PIOS_USART_RegisterRxCallback,
.ioctl = PIOS_USART_Ioctl,
};
enum pios_usart_dev_magic {
@ -67,6 +69,7 @@ struct pios_usart_dev {
uint32_t tx_out_context;
uint32_t rx_dropped;
uint8_t irq_channel;
};
static bool PIOS_USART_validate(struct pios_usart_dev *usart_dev)
@ -74,6 +77,30 @@ static bool PIOS_USART_validate(struct pios_usart_dev *usart_dev)
return usart_dev->magic == PIOS_USART_DEV_MAGIC;
}
const struct pios_usart_cfg *PIOS_USART_GetConfig(uint32_t usart_id)
{
struct pios_usart_dev *usart_dev = (struct pios_usart_dev *)usart_id;
bool valid = PIOS_USART_validate(usart_dev);
PIOS_Assert(valid);
return usart_dev->cfg;
}
static int32_t PIOS_USART_SetIrqPrio(struct pios_usart_dev *usart_dev, uint8_t irq_prio)
{
NVIC_InitTypeDef init = {
.NVIC_IRQChannel = usart_dev->irq_channel,
.NVIC_IRQChannelPreemptionPriority = irq_prio,
.NVIC_IRQChannelCmd = ENABLE,
};
NVIC_Init(&init);
return 0;
}
#if defined(PIOS_INCLUDE_FREERTOS)
static struct pios_usart_dev *PIOS_USART_alloc(void)
{
@ -153,56 +180,51 @@ int32_t PIOS_USART_Init(uint32_t *usart_id, const struct pios_usart_cfg *cfg)
}
/* Bind the configuration to the device instance */
usart_dev->cfg = cfg;
usart_dev->cfg = cfg;
/* Copy the comm parameter structure */
usart_dev->init = cfg->init;
/* Initialize the comm parameter structure */
USART_StructInit(&usart_dev->init); // 9600 8n1
/* Enable the USART Pins Software Remapping */
if (usart_dev->cfg->remap) {
GPIO_PinRemapConfig(usart_dev->cfg->remap, ENABLE);
/* We will set modes later, depending on installed callbacks */
usart_dev->init.USART_Mode = 0;
/* DTR handling? */
#ifdef PIOS_USART_INVERTER_PORT
/* Initialize inverter gpio and set it to off */
if (usart_dev->cfg->regs == PIOS_USART_INVERTER_PORT) {
GPIO_InitTypeDef inverterGPIOInit = {
.GPIO_Pin = PIOS_USART_INVERTER_PIN,
.GPIO_Mode = GPIO_Mode_Out_PP,
.GPIO_Speed = GPIO_Speed_2MHz,
};
GPIO_Init(PIOS_USART_INVERTER_GPIO, &inverterGPIOInit);
GPIO_WriteBit(PIOS_USART_INVERTER_GPIO,
PIOS_USART_INVERTER_PIN,
PIOS_USART_INVERTER_DISABLE);
}
/* Initialize the USART Rx and Tx pins */
GPIO_Init(usart_dev->cfg->rx.gpio, &usart_dev->cfg->rx.init);
GPIO_Init(usart_dev->cfg->tx.gpio, &usart_dev->cfg->tx.init);
/* Enable USART clock */
switch ((uint32_t)usart_dev->cfg->regs) {
case (uint32_t)USART1:
RCC_APB2PeriphClockCmd(RCC_APB2Periph_USART1, ENABLE);
break;
case (uint32_t)USART2:
RCC_APB1PeriphClockCmd(RCC_APB1Periph_USART2, ENABLE);
break;
case (uint32_t)USART3:
RCC_APB1PeriphClockCmd(RCC_APB1Periph_USART3, ENABLE);
break;
}
/* Configure the USART */
USART_Init(usart_dev->cfg->regs, &usart_dev->init);
*usart_id = (uint32_t)usart_dev;
#endif
/* Configure USART Interrupts */
switch ((uint32_t)usart_dev->cfg->regs) {
case (uint32_t)USART1:
PIOS_USART_1_id = (uint32_t)usart_dev;
usart_dev->irq_channel = USART1_IRQn;
break;
case (uint32_t)USART2:
PIOS_USART_2_id = (uint32_t)usart_dev;
usart_dev->irq_channel = USART2_IRQn;
break;
case (uint32_t)USART3:
PIOS_USART_3_id = (uint32_t)usart_dev;
usart_dev->irq_channel = USART3_IRQn;
break;
}
NVIC_Init(&usart_dev->cfg->irq.init);
USART_ITConfig(usart_dev->cfg->regs, USART_IT_RXNE, ENABLE);
USART_ITConfig(usart_dev->cfg->regs, USART_IT_TXE, ENABLE);
/* Enable USART */
USART_Cmd(usart_dev->cfg->regs, ENABLE);
PIOS_USART_SetIrqPrio(usart_dev, PIOS_IRQ_PRIO_MID);
*usart_id = (uint32_t)usart_dev;
return 0;
@ -210,6 +232,38 @@ out_fail:
return -1;
}
static void PIOS_USART_Setup(struct pios_usart_dev *usart_dev)
{
/* Configure RX GPIO */
if ((usart_dev->init.USART_Mode & USART_Mode_Rx) && (usart_dev->cfg->rx.gpio)) {
if (usart_dev->cfg->remap) {
GPIO_PinRemapConfig(usart_dev->cfg->remap, ENABLE);
}
GPIO_Init(usart_dev->cfg->rx.gpio, (GPIO_InitTypeDef *)&usart_dev->cfg->rx.init);
USART_ITConfig(usart_dev->cfg->regs, USART_IT_RXNE, ENABLE);
}
/* Configure TX GPIO */
if ((usart_dev->init.USART_Mode & USART_Mode_Tx) && usart_dev->cfg->tx.gpio) {
if (usart_dev->cfg->remap) {
GPIO_PinRemapConfig(usart_dev->cfg->remap, ENABLE);
}
GPIO_Init(usart_dev->cfg->tx.gpio, (GPIO_InitTypeDef *)&usart_dev->cfg->tx.init);
}
/* Write new configuration */
USART_Init(usart_dev->cfg->regs, &usart_dev->init);
/*
* Re enable USART.
*/
USART_Cmd(usart_dev->cfg->regs, ENABLE);
}
static void PIOS_USART_RxStart(uint32_t usart_id, __attribute__((unused)) uint16_t rx_bytes_avail)
{
struct pios_usart_dev *usart_dev = (struct pios_usart_dev *)usart_id;
@ -247,8 +301,7 @@ static void PIOS_USART_ChangeBaud(uint32_t usart_id, uint32_t baud)
/* Use our working copy of the usart init structure */
usart_dev->init.USART_BaudRate = baud;
/* Write back the modified configuration */
USART_Init(usart_dev->cfg->regs, &usart_dev->init);
PIOS_USART_Setup(usart_dev);
}
/**
@ -263,10 +316,9 @@ static void PIOS_USART_ChangeBaud(uint32_t usart_id, uint32_t baud)
*/
static void PIOS_USART_ChangeConfig(uint32_t usart_id,
enum PIOS_COM_Word_Length word_len,
enum PIOS_COM_StopBits stop_bits,
enum PIOS_COM_Parity parity,
uint32_t baud_rate,
enum PIOS_COM_Mode mode)
enum PIOS_COM_StopBits stop_bits,
uint32_t baud_rate)
{
struct pios_usart_dev *usart_dev = (struct pios_usart_dev *)usart_id;
@ -320,27 +372,7 @@ static void PIOS_USART_ChangeConfig(uint32_t usart_id,
usart_dev->init.USART_BaudRate = baud_rate;
}
switch (mode) {
case PIOS_COM_Mode_Rx:
usart_dev->init.USART_Mode = USART_Mode_Rx;
break;
case PIOS_COM_Mode_Tx:
usart_dev->init.USART_Mode = USART_Mode_Tx;
break;
case PIOS_COM_Mode_RxTx:
usart_dev->init.USART_Mode = USART_Mode_Rx | USART_Mode_Tx;
break;
default:
break;
}
/* Write back the modified configuration */
USART_Init(usart_dev->cfg->regs, &usart_dev->init);
/*
* Re enable USART.
*/
USART_Cmd(usart_dev->cfg->regs, ENABLE);
PIOS_USART_Setup(usart_dev);
}
static void PIOS_USART_RegisterRxCallback(uint32_t usart_id, pios_com_callback rx_in_cb, uint32_t context)
@ -355,8 +387,12 @@ static void PIOS_USART_RegisterRxCallback(uint32_t usart_id, pios_com_callback r
* Order is important in these assignments since ISR uses _cb
* field to determine if it's ok to dereference _cb and _context
*/
usart_dev->rx_in_context = context;
usart_dev->rx_in_context = context;
usart_dev->rx_in_cb = rx_in_cb;
usart_dev->init.USART_Mode |= USART_Mode_Rx;
PIOS_USART_Setup(usart_dev);
}
static void PIOS_USART_RegisterTxCallback(uint32_t usart_id, pios_com_callback tx_out_cb, uint32_t context)
@ -371,8 +407,12 @@ static void PIOS_USART_RegisterTxCallback(uint32_t usart_id, pios_com_callback t
* Order is important in these assignments since ISR uses _cb
* field to determine if it's ok to dereference _cb and _context
*/
usart_dev->tx_out_context = context;
usart_dev->tx_out_context = context;
usart_dev->tx_out_cb = tx_out_cb;
usart_dev->init.USART_Mode |= USART_Mode_Tx;
PIOS_USART_Setup(usart_dev);
}
static void PIOS_USART_generic_irq_handler(uint32_t usart_id)
@ -430,6 +470,59 @@ static void PIOS_USART_generic_irq_handler(uint32_t usart_id)
#endif /* PIOS_INCLUDE_FREERTOS */
}
static int32_t PIOS_USART_Ioctl(uint32_t usart_id, uint32_t ctl, void *param)
{
struct pios_usart_dev *usart_dev = (struct pios_usart_dev *)usart_id;
bool valid = PIOS_USART_validate(usart_dev);
PIOS_Assert(valid);
/* First try board specific IOCTL to allow overriding default functions */
if (usart_dev->cfg->ioctl) {
int32_t ret = usart_dev->cfg->ioctl(usart_id, ctl, param);
if (ret != COM_IOCTL_ENOSYS) {
return ret;
}
}
switch (ctl) {
case PIOS_IOCTL_USART_SET_IRQ_PRIO:
return PIOS_USART_SetIrqPrio(usart_dev, *(uint8_t *)param);
#ifdef PIOS_USART_INVERTER_PORT
case PIOS_IOCTL_USART_SET_INVERTED:
if (usart_dev->cfg->regs != PIOS_USART_INVERTER_PORT) {
return COM_IOCTL_ENOSYS; /* don't know how */
}
GPIO_WriteBit(PIOS_USART_INVERTER_GPIO,
PIOS_USART_INVERTER_PIN,
(*(enum PIOS_USART_Inverted *)param & PIOS_USART_Inverted_Rx) ? PIOS_USART_INVERTER_ENABLE : PIOS_USART_INVERTER_DISABLE);
break;
#endif /* PIOS_USART_INVERTER_PORT */
case PIOS_IOCTL_USART_GET_DSMBIND:
#ifdef PIOS_USART_INVERTER_PORT
if (usart_dev->cfg->regs == PIOS_USART_INVERTER_PORT) {
return -2; /* do not allow dsm bind on port with inverter */
}
#endif /* otherwise, return RXGPIO */
case PIOS_IOCTL_USART_GET_RXGPIO:
*(struct stm32_gpio *)param = usart_dev->cfg->rx;
break;
case PIOS_IOCTL_USART_GET_TXGPIO:
*(struct stm32_gpio *)param = usart_dev->cfg->tx;
break;
case PIOS_IOCTL_USART_SET_HALFDUPLEX:
USART_HalfDuplexCmd(usart_dev->cfg->regs, *(bool *)param ? ENABLE : DISABLE);
break;
default:
return COM_IOCTL_ENOSYS; /* unknown ioctl */
}
return 0;
}
#endif /* PIOS_INCLUDE_USART */
/**

View File

@ -41,23 +41,23 @@
/* Provide a COM driver */
static void PIOS_USART_ChangeBaud(uint32_t usart_id, uint32_t baud);
static void PIOS_USART_SetHalfDuplex(uint32_t usart_id, bool halfduplex);
static void PIOS_USART_ChangeConfig(uint32_t usart_id, enum PIOS_COM_Word_Length word_len, enum PIOS_COM_StopBits stop_bits, enum PIOS_COM_Parity parity, uint32_t baud_rate, enum PIOS_COM_Mode mode);
static void PIOS_USART_ChangeConfig(uint32_t usart_id, enum PIOS_COM_Word_Length word_len, enum PIOS_COM_Parity parity, enum PIOS_COM_StopBits stop_bits, uint32_t baud_rate);
static void PIOS_USART_SetCtrlLine(uint32_t usart_id, uint32_t mask, uint32_t state);
static void PIOS_USART_RegisterRxCallback(uint32_t usart_id, pios_com_callback rx_in_cb, uint32_t context);
static void PIOS_USART_RegisterTxCallback(uint32_t usart_id, pios_com_callback tx_out_cb, uint32_t context);
static void PIOS_USART_TxStart(uint32_t usart_id, uint16_t tx_bytes_avail);
static void PIOS_USART_RxStart(uint32_t usart_id, uint16_t rx_bytes_avail);
static int32_t PIOS_USART_Ioctl(uint32_t usart_id, uint32_t ctl, void *param);
const struct pios_com_driver pios_usart_com_driver = {
.set_baud = PIOS_USART_ChangeBaud,
.set_halfduplex = PIOS_USART_SetHalfDuplex,
.set_config = PIOS_USART_ChangeConfig,
.set_ctrl_line = PIOS_USART_SetCtrlLine,
.tx_start = PIOS_USART_TxStart,
.rx_start = PIOS_USART_RxStart,
.bind_tx_cb = PIOS_USART_RegisterTxCallback,
.bind_rx_cb = PIOS_USART_RegisterRxCallback,
.set_baud = PIOS_USART_ChangeBaud,
.set_config = PIOS_USART_ChangeConfig,
.set_ctrl_line = PIOS_USART_SetCtrlLine,
.tx_start = PIOS_USART_TxStart,
.rx_start = PIOS_USART_RxStart,
.bind_tx_cb = PIOS_USART_RegisterTxCallback,
.bind_rx_cb = PIOS_USART_RegisterRxCallback,
.ioctl = PIOS_USART_Ioctl,
};
enum pios_usart_dev_magic {
@ -72,6 +72,7 @@ struct pios_usart_dev {
uint32_t rx_in_context;
pios_com_callback tx_out_cb;
uint32_t tx_out_context;
uint8_t irq_channel;
};
static bool PIOS_USART_validate(struct pios_usart_dev *usart_dev)
@ -79,6 +80,30 @@ static bool PIOS_USART_validate(struct pios_usart_dev *usart_dev)
return usart_dev->magic == PIOS_USART_DEV_MAGIC;
}
const struct pios_usart_cfg *PIOS_USART_GetConfig(uint32_t usart_id)
{
struct pios_usart_dev *usart_dev = (struct pios_usart_dev *)usart_id;
bool valid = PIOS_USART_validate(usart_dev);
PIOS_Assert(valid);
return usart_dev->cfg;
}
static int32_t PIOS_USART_SetIrqPrio(struct pios_usart_dev *usart_dev, uint8_t irq_prio)
{
NVIC_InitTypeDef init = {
.NVIC_IRQChannel = usart_dev->irq_channel,
.NVIC_IRQChannelPreemptionPriority = irq_prio,
.NVIC_IRQChannelCmd = ENABLE,
};
NVIC_Init(&init);
return 0;
}
#if defined(PIOS_INCLUDE_FREERTOS)
static struct pios_usart_dev *PIOS_USART_alloc(void)
{
@ -179,66 +204,70 @@ int32_t PIOS_USART_Init(uint32_t *usart_id, const struct pios_usart_cfg *cfg)
}
/* Bind the configuration to the device instance */
usart_dev->cfg = cfg;
usart_dev->cfg = cfg;
/* Copy the comm parameter structure */
usart_dev->init = cfg->init;
/* Initialize the comm parameter structure */
USART_StructInit(&usart_dev->init); // 9600 8n1
/* Map pins to USART function */
/* note __builtin_ctz() due to the difference between GPIO_PinX and GPIO_PinSourceX */
if (usart_dev->cfg->remap) {
GPIO_PinAFConfig(usart_dev->cfg->rx.gpio,
__builtin_ctz(usart_dev->cfg->rx.init.GPIO_Pin),
usart_dev->cfg->remap);
GPIO_PinAFConfig(usart_dev->cfg->tx.gpio,
__builtin_ctz(usart_dev->cfg->tx.init.GPIO_Pin),
usart_dev->cfg->remap);
}
/* We will set modes later, depending on installed callbacks */
usart_dev->init.USART_Mode = 0;
/* Initialize the USART Rx and Tx pins */
GPIO_Init(usart_dev->cfg->rx.gpio, (GPIO_InitTypeDef *)&usart_dev->cfg->rx.init);
GPIO_Init(usart_dev->cfg->tx.gpio, (GPIO_InitTypeDef *)&usart_dev->cfg->tx.init);
/* If a DTR line is specified, initialize it */
if (usart_dev->cfg->dtr.gpio) {
GPIO_Init(usart_dev->cfg->dtr.gpio, (GPIO_InitTypeDef *)&usart_dev->cfg->dtr.init);
PIOS_USART_SetCtrlLine((uint32_t)usart_dev, COM_CTRL_LINE_DTR_MASK, 0);
}
#ifdef PIOS_USART_INVERTER_PORT
/* Initialize inverter gpio and set it to off */
if (usart_dev->cfg->regs == PIOS_USART_INVERTER_PORT) {
GPIO_InitTypeDef inverterGPIOInit = {
.GPIO_Pin = PIOS_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(PIOS_USART_INVERTER_GPIO, &inverterGPIOInit);
/* Configure the USART */
USART_Init(usart_dev->cfg->regs, (USART_InitTypeDef *)&usart_dev->init);
*usart_id = (uint32_t)usart_dev;
GPIO_WriteBit(PIOS_USART_INVERTER_GPIO,
PIOS_USART_INVERTER_PIN,
PIOS_USART_INVERTER_DISABLE);
}
#endif
/* Configure USART Interrupts */
switch ((uint32_t)usart_dev->cfg->regs) {
case (uint32_t)USART1:
PIOS_USART_1_id = (uint32_t)usart_dev;
usart_dev->irq_channel = USART1_IRQn;
break;
case (uint32_t)USART2:
PIOS_USART_2_id = (uint32_t)usart_dev;
usart_dev->irq_channel = USART2_IRQn;
break;
#if !defined(STM32F411xE)
case (uint32_t)USART3:
PIOS_USART_3_id = (uint32_t)usart_dev;
usart_dev->irq_channel = USART3_IRQn;
break;
case (uint32_t)UART4:
PIOS_USART_4_id = (uint32_t)usart_dev;
usart_dev->irq_channel = UART4_IRQn;
break;
case (uint32_t)UART5:
PIOS_USART_5_id = (uint32_t)usart_dev;
usart_dev->irq_channel = UART5_IRQn;
break;
#endif /* STM32F411xE */
case (uint32_t)USART6:
PIOS_USART_6_id = (uint32_t)usart_dev;
usart_dev->irq_channel = USART6_IRQn;
break;
}
NVIC_Init((NVIC_InitTypeDef *)&(usart_dev->cfg->irq.init));
USART_ITConfig(usart_dev->cfg->regs, USART_IT_RXNE, ENABLE);
USART_ITConfig(usart_dev->cfg->regs, USART_IT_TXE, ENABLE);
PIOS_USART_SetIrqPrio(usart_dev, PIOS_IRQ_PRIO_MID);
// FIXME XXX Clear / reset uart here - sends NUL char else
/* Enable USART */
USART_Cmd(usart_dev->cfg->regs, ENABLE);
*usart_id = (uint32_t)usart_dev;
return 0;
@ -246,6 +275,42 @@ out_fail:
return -1;
}
static void PIOS_USART_Setup(struct pios_usart_dev *usart_dev)
{
/* Configure RX GPIO */
if ((usart_dev->init.USART_Mode & USART_Mode_Rx) && (usart_dev->cfg->rx.gpio)) {
if (usart_dev->cfg->remap) {
GPIO_PinAFConfig(usart_dev->cfg->rx.gpio,
__builtin_ctz(usart_dev->cfg->rx.init.GPIO_Pin),
usart_dev->cfg->remap);
}
GPIO_Init(usart_dev->cfg->rx.gpio, (GPIO_InitTypeDef *)&usart_dev->cfg->rx.init);
/* just enable RX right away, cause rcvr modules do not call rx_start method */
USART_ITConfig(usart_dev->cfg->regs, USART_IT_RXNE, ENABLE);
}
/* Configure TX GPIO */
if ((usart_dev->init.USART_Mode & USART_Mode_Tx) && usart_dev->cfg->tx.gpio) {
if (usart_dev->cfg->remap) {
GPIO_PinAFConfig(usart_dev->cfg->tx.gpio,
__builtin_ctz(usart_dev->cfg->tx.init.GPIO_Pin),
usart_dev->cfg->remap);
}
GPIO_Init(usart_dev->cfg->tx.gpio, (GPIO_InitTypeDef *)&usart_dev->cfg->tx.init);
}
/* Write new configuration */
USART_Init(usart_dev->cfg->regs, &usart_dev->init);
/*
* Re enable USART.
*/
USART_Cmd(usart_dev->cfg->regs, ENABLE);
}
static void PIOS_USART_RxStart(uint32_t usart_id, __attribute__((unused)) uint16_t rx_bytes_avail)
{
struct pios_usart_dev *usart_dev = (struct pios_usart_dev *)usart_id;
@ -284,24 +349,7 @@ static void PIOS_USART_ChangeBaud(uint32_t usart_id, uint32_t baud)
/* Use our working copy of the usart init structure */
usart_dev->init.USART_BaudRate = baud;
/* Write back the modified configuration */
USART_Init(usart_dev->cfg->regs, &usart_dev->init);
}
/**
* Sets the USART peripheral into half duplex mode
* \param[in] usart_id USART name (GPS, TELEM, AUX)
* \param[in] bool wether to set half duplex or not
*/
static void PIOS_USART_SetHalfDuplex(uint32_t usart_id, bool halfduplex)
{
struct pios_usart_dev *usart_dev = (struct pios_usart_dev *)usart_id;
bool valid = PIOS_USART_validate(usart_dev);
PIOS_Assert(valid);
USART_HalfDuplexCmd(usart_dev->cfg->regs, halfduplex ? ENABLE : DISABLE);
PIOS_USART_Setup(usart_dev);
}
/**
@ -316,10 +364,9 @@ static void PIOS_USART_SetHalfDuplex(uint32_t usart_id, bool halfduplex)
*/
static void PIOS_USART_ChangeConfig(uint32_t usart_id,
enum PIOS_COM_Word_Length word_len,
enum PIOS_COM_StopBits stop_bits,
enum PIOS_COM_Parity parity,
uint32_t baud_rate,
enum PIOS_COM_Mode mode)
enum PIOS_COM_StopBits stop_bits,
uint32_t baud_rate)
{
struct pios_usart_dev *usart_dev = (struct pios_usart_dev *)usart_id;
@ -373,27 +420,7 @@ static void PIOS_USART_ChangeConfig(uint32_t usart_id,
usart_dev->init.USART_BaudRate = baud_rate;
}
switch (mode) {
case PIOS_COM_Mode_Rx:
usart_dev->init.USART_Mode = USART_Mode_Rx;
break;
case PIOS_COM_Mode_Tx:
usart_dev->init.USART_Mode = USART_Mode_Tx;
break;
case PIOS_COM_Mode_RxTx:
usart_dev->init.USART_Mode = USART_Mode_Rx | USART_Mode_Tx;
break;
default:
break;
}
/* Write back the modified configuration */
USART_Init(usart_dev->cfg->regs, &usart_dev->init);
/*
* Re enable USART.
*/
USART_Cmd(usart_dev->cfg->regs, ENABLE);
PIOS_USART_Setup(usart_dev);
}
static void PIOS_USART_SetCtrlLine(uint32_t usart_id, uint32_t mask, uint32_t state)
@ -424,8 +451,12 @@ static void PIOS_USART_RegisterRxCallback(uint32_t usart_id, pios_com_callback r
* Order is important in these assignments since ISR uses _cb
* field to determine if it's ok to dereference _cb and _context
*/
usart_dev->rx_in_context = context;
usart_dev->rx_in_context = context;
usart_dev->rx_in_cb = rx_in_cb;
usart_dev->init.USART_Mode |= USART_Mode_Rx;
PIOS_USART_Setup(usart_dev);
}
static void PIOS_USART_RegisterTxCallback(uint32_t usart_id, pios_com_callback tx_out_cb, uint32_t context)
@ -440,8 +471,12 @@ static void PIOS_USART_RegisterTxCallback(uint32_t usart_id, pios_com_callback t
* Order is important in these assignments since ISR uses _cb
* field to determine if it's ok to dereference _cb and _context
*/
usart_dev->tx_out_context = context;
usart_dev->tx_out_context = context;
usart_dev->tx_out_cb = tx_out_cb;
usart_dev->init.USART_Mode |= USART_Mode_Tx;
PIOS_USART_Setup(usart_dev);
}
static void PIOS_USART_generic_irq_handler(uint32_t usart_id)
@ -494,6 +529,59 @@ static void PIOS_USART_generic_irq_handler(uint32_t usart_id)
#endif /* PIOS_INCLUDE_FREERTOS */
}
static int32_t PIOS_USART_Ioctl(uint32_t usart_id, uint32_t ctl, void *param)
{
struct pios_usart_dev *usart_dev = (struct pios_usart_dev *)usart_id;
bool valid = PIOS_USART_validate(usart_dev);
PIOS_Assert(valid);
/* First try board specific IOCTL to allow overriding default functions */
if (usart_dev->cfg->ioctl) {
int32_t ret = usart_dev->cfg->ioctl(usart_id, ctl, param);
if (ret != COM_IOCTL_ENOSYS) {
return ret;
}
}
switch (ctl) {
case PIOS_IOCTL_USART_SET_IRQ_PRIO:
return PIOS_USART_SetIrqPrio(usart_dev, *(uint8_t *)param);
#ifdef PIOS_USART_INVERTER_PORT
case PIOS_IOCTL_USART_SET_INVERTED:
if (usart_dev->cfg->regs != PIOS_USART_INVERTER_PORT) {
return COM_IOCTL_ENOSYS; /* don't know how */
}
GPIO_WriteBit(PIOS_USART_INVERTER_GPIO,
PIOS_USART_INVERTER_PIN,
(*(enum PIOS_USART_Inverted *)param & PIOS_USART_Inverted_Rx) ? PIOS_USART_INVERTER_ENABLE : PIOS_USART_INVERTER_DISABLE);
break;
#endif /* PIOS_USART_INVERTER_PORT */
case PIOS_IOCTL_USART_GET_DSMBIND:
#ifdef PIOS_USART_INVERTER_PORT
if (usart_dev->cfg->regs == PIOS_USART_INVERTER_PORT) {
return -2; /* do not allow dsm bind on port with inverter */
}
#endif /* otherwise, return RXGPIO */
case PIOS_IOCTL_USART_GET_RXGPIO:
*(struct stm32_gpio *)param = usart_dev->cfg->rx;
break;
case PIOS_IOCTL_USART_GET_TXGPIO:
*(struct stm32_gpio *)param = usart_dev->cfg->tx;
break;
case PIOS_IOCTL_USART_SET_HALFDUPLEX:
USART_HalfDuplexCmd(usart_dev->cfg->regs, *(bool *)param ? ENABLE : DISABLE);
break;
default:
return COM_IOCTL_ENOSYS; /* unknown ioctl */
}
return 0;
}
#endif /* PIOS_INCLUDE_USART */
/**

View File

@ -186,11 +186,11 @@ static const struct pios_spi_cfg pios_spi_gyro_cfg = {
},
};
static uint32_t pios_spi_gyro_id;
uint32_t pios_spi_gyro_adapter_id;
void PIOS_SPI_gyro_irq_handler(void)
{
/* Call into the generic code to handle the IRQ for this specific device */
PIOS_SPI_IRQ_Handler(pios_spi_gyro_id);
PIOS_SPI_IRQ_Handler(pios_spi_gyro_adapter_id);
}
@ -402,11 +402,11 @@ static const struct pios_spi_cfg pios_spi_flash_accel_cfg_cc = {
},
};
static uint32_t pios_spi_flash_accel_id;
uint32_t pios_spi_flash_accel_adapter_id;
void PIOS_SPI_flash_accel_irq_handler(void)
{
/* Call into the generic code to handle the IRQ for this specific device */
PIOS_SPI_IRQ_Handler(pios_spi_flash_accel_id);
PIOS_SPI_IRQ_Handler(pios_spi_flash_accel_adapter_id);
}
#endif /* PIOS_INCLUDE_SPI */
@ -485,6 +485,11 @@ void PIOS_ADC_handler()
{
PIOS_ADC_DMA_Handler();
}
const struct pios_adc_cfg *PIOS_BOARD_HW_DEFS_GetAdcCfg(uint32_t board_revision)
{
return (board_revision == BOARD_REVISION_CC) ? &pios_adc_cfg : 0;
}
#endif /* if defined(PIOS_INCLUDE_ADC) */
#include "pios_tim_priv.h"
@ -549,323 +554,52 @@ static const struct pios_tim_clock_cfg tim_4_cfg = {
},
};
#include "pios_servo_config.h"
static const struct pios_tim_channel pios_tim_rcvrport_all_channels[] = {
{
.timer = TIM4,
.timer_chan = TIM_Channel_1,
.pin = {
.gpio = GPIOB,
.init = {
.GPIO_Pin = GPIO_Pin_6,
.GPIO_Mode = GPIO_Mode_IPD,
.GPIO_Speed = GPIO_Speed_2MHz,
},
},
},
{
.timer = TIM3,
.timer_chan = TIM_Channel_2,
.pin = {
.gpio = GPIOB,
.init = {
.GPIO_Pin = GPIO_Pin_5,
.GPIO_Mode = GPIO_Mode_IPD,
.GPIO_Speed = GPIO_Speed_2MHz,
},
},
.remap = GPIO_PartialRemap_TIM3,
},
{
.timer = TIM3,
.timer_chan = TIM_Channel_3,
.pin = {
.gpio = GPIOB,
.init = {
.GPIO_Pin = GPIO_Pin_0,
.GPIO_Mode = GPIO_Mode_IPD,
.GPIO_Speed = GPIO_Speed_2MHz,
},
},
},
{
.timer = TIM3,
.timer_chan = TIM_Channel_4,
.pin = {
.gpio = GPIOB,
.init = {
.GPIO_Pin = GPIO_Pin_1,
.GPIO_Mode = GPIO_Mode_IPD,
.GPIO_Speed = GPIO_Speed_2MHz,
},
},
},
{
.timer = TIM2,
.timer_chan = TIM_Channel_1,
.pin = {
.gpio = GPIOA,
.init = {
.GPIO_Pin = GPIO_Pin_0,
.GPIO_Mode = GPIO_Mode_IPD,
.GPIO_Speed = GPIO_Speed_2MHz,
},
},
},
{
.timer = TIM2,
.timer_chan = TIM_Channel_2,
.pin = {
.gpio = GPIOA,
.init = {
.GPIO_Pin = GPIO_Pin_1,
.GPIO_Mode = GPIO_Mode_IPD,
.GPIO_Speed = GPIO_Speed_2MHz,
},
},
},
TIM_SERVO_CHANNEL_CONFIG(TIM4, 1, B, 6, 0),
TIM_SERVO_CHANNEL_CONFIG(TIM3, 2, B, 5, GPIO_PartialRemap_TIM3),
TIM_SERVO_CHANNEL_CONFIG(TIM3, 3, B, 0, 0),
TIM_SERVO_CHANNEL_CONFIG(TIM3, 4, B, 1, 0),
TIM_SERVO_CHANNEL_CONFIG(TIM2, 1, A, 0, 0),
TIM_SERVO_CHANNEL_CONFIG(TIM2, 2, A, 1, 0),
};
static const struct pios_tim_channel pios_tim_servoport_all_pins[] = {
{
.timer = TIM4,
.timer_chan = TIM_Channel_4,
.pin = {
.gpio = GPIOB,
.init = {
.GPIO_Pin = GPIO_Pin_9,
.GPIO_Mode = GPIO_Mode_AF_PP,
.GPIO_Speed = GPIO_Speed_2MHz,
},
},
},
{
.timer = TIM4,
.timer_chan = TIM_Channel_3,
.pin = {
.gpio = GPIOB,
.init = {
.GPIO_Pin = GPIO_Pin_8,
.GPIO_Mode = GPIO_Mode_AF_PP,
.GPIO_Speed = GPIO_Speed_2MHz,
},
},
},
{
.timer = TIM4,
.timer_chan = TIM_Channel_2,
.pin = {
.gpio = GPIOB,
.init = {
.GPIO_Pin = GPIO_Pin_7,
.GPIO_Mode = GPIO_Mode_AF_PP,
.GPIO_Speed = GPIO_Speed_2MHz,
},
},
},
{
.timer = TIM1,
.timer_chan = TIM_Channel_1,
.pin = {
.gpio = GPIOA,
.init = {
.GPIO_Pin = GPIO_Pin_8,
.GPIO_Mode = GPIO_Mode_AF_PP,
.GPIO_Speed = GPIO_Speed_2MHz,
},
},
},
{
.timer = TIM3,
.timer_chan = TIM_Channel_1,
.pin = {
.gpio = GPIOB,
.init = {
.GPIO_Pin = GPIO_Pin_4,
.GPIO_Mode = GPIO_Mode_AF_PP,
.GPIO_Speed = GPIO_Speed_2MHz,
},
},
.remap = GPIO_PartialRemap_TIM3,
},
{
.timer = TIM2,
.timer_chan = TIM_Channel_3,
.pin = {
.gpio = GPIOA,
.init = {
.GPIO_Pin = GPIO_Pin_2,
.GPIO_Mode = GPIO_Mode_AF_PP,
.GPIO_Speed = GPIO_Speed_2MHz,
},
},
},
TIM_SERVO_CHANNEL_CONFIG(TIM4, 4, B, 9, 0),
TIM_SERVO_CHANNEL_CONFIG(TIM4, 3, B, 8, 0),
TIM_SERVO_CHANNEL_CONFIG(TIM4, 2, B, 7, 0),
TIM_SERVO_CHANNEL_CONFIG(TIM1, 1, A, 8, 0),
TIM_SERVO_CHANNEL_CONFIG(TIM3, 1, B, 4, GPIO_PartialRemap_TIM3),
TIM_SERVO_CHANNEL_CONFIG(TIM2, 3, A, 2, 0),
};
static const struct pios_tim_channel pios_tim_servoport_rcvrport_pins[] = {
{
.timer = TIM4,
.timer_chan = TIM_Channel_4,
.pin = {
.gpio = GPIOB,
.init = {
.GPIO_Pin = GPIO_Pin_9,
.GPIO_Mode = GPIO_Mode_AF_PP,
.GPIO_Speed = GPIO_Speed_2MHz,
},
},
},
{
.timer = TIM4,
.timer_chan = TIM_Channel_3,
.pin = {
.gpio = GPIOB,
.init = {
.GPIO_Pin = GPIO_Pin_8,
.GPIO_Mode = GPIO_Mode_AF_PP,
.GPIO_Speed = GPIO_Speed_2MHz,
},
},
},
{
.timer = TIM4,
.timer_chan = TIM_Channel_2,
.pin = {
.gpio = GPIOB,
.init = {
.GPIO_Pin = GPIO_Pin_7,
.GPIO_Mode = GPIO_Mode_AF_PP,
.GPIO_Speed = GPIO_Speed_2MHz,
},
},
},
{
.timer = TIM1,
.timer_chan = TIM_Channel_1,
.pin = {
.gpio = GPIOA,
.init = {
.GPIO_Pin = GPIO_Pin_8,
.GPIO_Mode = GPIO_Mode_AF_PP,
.GPIO_Speed = GPIO_Speed_2MHz,
},
},
},
{
.timer = TIM3,
.timer_chan = TIM_Channel_1,
.pin = {
.gpio = GPIOB,
.init = {
.GPIO_Pin = GPIO_Pin_4,
.GPIO_Mode = GPIO_Mode_AF_PP,
.GPIO_Speed = GPIO_Speed_2MHz,
},
},
.remap = GPIO_PartialRemap_TIM3,
},
{
.timer = TIM2,
.timer_chan = TIM_Channel_3,
.pin = {
.gpio = GPIOA,
.init = {
.GPIO_Pin = GPIO_Pin_2,
.GPIO_Mode = GPIO_Mode_AF_PP,
.GPIO_Speed = GPIO_Speed_2MHz,
},
},
},
TIM_SERVO_CHANNEL_CONFIG(TIM4, 4, B, 9, 0),
TIM_SERVO_CHANNEL_CONFIG(TIM4, 3, B, 8, 0),
TIM_SERVO_CHANNEL_CONFIG(TIM4, 2, B, 7, 0),
TIM_SERVO_CHANNEL_CONFIG(TIM1, 1, A, 8, 0),
TIM_SERVO_CHANNEL_CONFIG(TIM3, 1, B, 4, GPIO_PartialRemap_TIM3),
TIM_SERVO_CHANNEL_CONFIG(TIM2, 3, A, 2, 0),
// Receiver port pins
// S3-S6 inputs are used as outputs in this case
{
.timer = TIM3,
.timer_chan = TIM_Channel_3,
.pin = {
.gpio = GPIOB,
.init = {
.GPIO_Pin = GPIO_Pin_0,
.GPIO_Mode = GPIO_Mode_AF_PP,
.GPIO_Speed = GPIO_Speed_2MHz,
},
},
},
{
.timer = TIM3,
.timer_chan = TIM_Channel_4,
.pin = {
.gpio = GPIOB,
.init = {
.GPIO_Pin = GPIO_Pin_1,
.GPIO_Mode = GPIO_Mode_AF_PP,
.GPIO_Speed = GPIO_Speed_2MHz,
},
},
},
{
.timer = TIM2,
.timer_chan = TIM_Channel_1,
.pin = {
.gpio = GPIOA,
.init = {
.GPIO_Pin = GPIO_Pin_0,
.GPIO_Mode = GPIO_Mode_AF_PP,
.GPIO_Speed = GPIO_Speed_2MHz,
},
},
},
{
.timer = TIM2,
.timer_chan = TIM_Channel_2,
.pin = {
.gpio = GPIOA,
.init = {
.GPIO_Pin = GPIO_Pin_1,
.GPIO_Mode = GPIO_Mode_AF_PP,
.GPIO_Speed = GPIO_Speed_2MHz,
},
},
},
TIM_SERVO_CHANNEL_CONFIG(TIM3, 3, B, 0, 0),
TIM_SERVO_CHANNEL_CONFIG(TIM3, 4, B, 1, 0),
TIM_SERVO_CHANNEL_CONFIG(TIM2, 1, A, 0, 0),
TIM_SERVO_CHANNEL_CONFIG(TIM2, 2, A, 1, 0),
};
static const struct pios_tim_channel pios_tim_ppm_flexi_port = {
.timer = TIM2,
.timer_chan = TIM_Channel_4,
.pin = {
.gpio = GPIOB,
.init = {
.GPIO_Pin = GPIO_Pin_11,
.GPIO_Mode = GPIO_Mode_IPD,
.GPIO_Speed = GPIO_Speed_2MHz,
},
},
.remap = GPIO_PartialRemap2_TIM2,
};
static const struct pios_tim_channel pios_tim_ppm_flexi_port = TIM_SERVO_CHANNEL_CONFIG(TIM2, 4, B, 11, GPIO_PartialRemap2_TIM2);
#if defined(PIOS_INCLUDE_USART)
#include "pios_usart_priv.h"
static const struct pios_usart_cfg pios_usart_generic_main_cfg = {
static const struct pios_usart_cfg pios_usart_main_cfg = {
.regs = 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,
@ -873,7 +607,7 @@ static const struct pios_usart_cfg pios_usart_generic_main_cfg = {
.GPIO_Mode = GPIO_Mode_IPU,
},
},
.tx = {
.tx = {
.gpio = GPIOA,
.init = {
.GPIO_Pin = GPIO_Pin_9,
@ -883,25 +617,9 @@ static const struct pios_usart_cfg pios_usart_generic_main_cfg = {
},
};
static const struct pios_usart_cfg pios_usart_generic_flexi_cfg = {
static const struct pios_usart_cfg pios_usart_flexi_cfg = {
.regs = 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_11,
@ -909,7 +627,7 @@ static const struct pios_usart_cfg pios_usart_generic_flexi_cfg = {
.GPIO_Mode = GPIO_Mode_IPU,
},
},
.tx = {
.tx = {
.gpio = GPIOB,
.init = {
.GPIO_Pin = GPIO_Pin_10,
@ -919,417 +637,6 @@ static const struct pios_usart_cfg pios_usart_generic_flexi_cfg = {
},
};
#if defined(PIOS_INCLUDE_DSM)
/*
* Spektrum/JR DSM USART
*/
#include <pios_dsm_priv.h>
static const struct pios_usart_cfg pios_usart_dsm_main_cfg = {
.regs = 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 = {
.GPIO_Pin = GPIO_Pin_10,
.GPIO_Speed = GPIO_Speed_2MHz,
.GPIO_Mode = GPIO_Mode_IPU,
},
},
.tx = {
.gpio = GPIOA,
.init = {
.GPIO_Pin = GPIO_Pin_9,
.GPIO_Speed = GPIO_Speed_2MHz,
.GPIO_Mode = GPIO_Mode_IN_FLOATING,
},
},
};
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_Out_PP,
},
},
};
static const struct pios_usart_cfg pios_usart_dsm_flexi_cfg = {
.regs = 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_IPU,
},
},
.tx = {
.gpio = GPIOB,
.init = {
.GPIO_Pin = GPIO_Pin_10,
.GPIO_Speed = GPIO_Speed_2MHz,
.GPIO_Mode = GPIO_Mode_IN_FLOATING,
},
},
};
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_PP,
},
},
};
#endif /* PIOS_INCLUDE_DSM */
#if defined(PIOS_INCLUDE_HOTT)
/*
* HOTT USART
*/
#include <pios_hott_priv.h>
static const struct pios_usart_cfg pios_usart_hott_flexi_cfg = {
.regs = 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_IPU,
},
},
.tx = {
.gpio = GPIOB,
.init = {
.GPIO_Pin = GPIO_Pin_10,
.GPIO_Speed = GPIO_Speed_2MHz,
.GPIO_Mode = GPIO_Mode_IN_FLOATING,
},
},
};
#endif /* PIOS_INCLUDE_HOTT */
#if defined(PIOS_INCLUDE_EXBUS)
/*
* EXBUS USART
*/
#include <pios_exbus_priv.h>
static const struct pios_usart_cfg pios_usart_exbus_flexi_cfg = {
.regs = USART3,
.init = {
.USART_BaudRate = 125000,
.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_IPU,
},
},
.tx = {
.gpio = GPIOB,
.init = {
.GPIO_Pin = GPIO_Pin_10,
.GPIO_Speed = GPIO_Speed_2MHz,
.GPIO_Mode = GPIO_Mode_IN_FLOATING,
},
},
};
#endif /* PIOS_INCLUDE_EXBUS */
#if defined(PIOS_INCLUDE_SRXL)
/*
* SRXL USART
*/
#include <pios_srxl_priv.h>
static const struct pios_usart_cfg pios_usart_srxl_flexi_cfg = {
.regs = 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_IPU,
},
},
.tx = {
.gpio = GPIOB,
.init = {
.GPIO_Pin = GPIO_Pin_10,
.GPIO_Speed = GPIO_Speed_2MHz,
.GPIO_Mode = GPIO_Mode_IN_FLOATING,
},
},
};
#endif /* PIOS_INCLUDE_SRXL */
#if defined(PIOS_INCLUDE_IBUS)
/*
* IBUS USART
*/
#include <pios_ibus_priv.h>
static const struct pios_usart_cfg pios_usart_ibus_flexi_cfg = {
.regs = 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_IPU,
},
},
.tx = {
.gpio = GPIOB,
.init = {
.GPIO_Pin = GPIO_Pin_10,
.GPIO_Speed = GPIO_Speed_2MHz,
.GPIO_Mode = GPIO_Mode_IN_FLOATING,
},
},
};
#endif /* PIOS_INCLUDE_IBUS */
#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,
.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_IPU,
},
},
.tx = {
.gpio = GPIOA,
.init = {
.GPIO_Pin = GPIO_Pin_9,
.GPIO_Speed = GPIO_Speed_2MHz,
.GPIO_Mode = GPIO_Mode_IN_FLOATING,
},
},
};
static const struct pios_sbus_cfg pios_sbus_cfg = {
/* Inverter configuration */
.inv = {
.gpio = GPIOB,
.init = {
.GPIO_Pin = GPIO_Pin_2,
.GPIO_Mode = GPIO_Mode_Out_PP,
.GPIO_Speed = GPIO_Speed_2MHz,
},
},
.gpio_clk_func = RCC_APB2PeriphClockCmd,
.gpio_clk_periph = RCC_APB2Periph_GPIOB,
.gpio_inv_enable = Bit_SET,
};
#endif /* PIOS_INCLUDE_SBUS */
/*
* HK OSD
*/
static const struct pios_usart_cfg pios_usart_hkosd_main_cfg = {
.regs = 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_IPU,
},
},
.tx = {
.gpio = GPIOA,
.init = {
.GPIO_Pin = GPIO_Pin_9,
.GPIO_Speed = GPIO_Speed_2MHz,
.GPIO_Mode = GPIO_Mode_AF_PP,
},
},
};
static const struct pios_usart_cfg pios_usart_hkosd_flexi_cfg = {
.regs = 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_IPU,
},
},
.tx = {
.gpio = GPIOB,
.init = {
.GPIO_Pin = GPIO_Pin_10,
.GPIO_Speed = GPIO_Speed_2MHz,
.GPIO_Mode = GPIO_Mode_AF_PP,
},
},
};
#endif /* PIOS_INCLUDE_USART */
#if defined(PIOS_INCLUDE_COM)
@ -1653,48 +960,88 @@ static const struct pios_usb_cfg pios_usb_main_cfg_cc3d = {
.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"
const struct pios_usb_cfg *PIOS_BOARD_HW_DEFS_GetUsbCfg(uint32_t board_revision)
{
switch (board_revision) {
case BOARD_REVISION_CC:
return &pios_usb_main_cfg_cc;
break;
case BOARD_REVISION_CC3D:
return &pios_usb_main_cfg_cc3d;
break;
default:
PIOS_DEBUG_Assert(0);
}
return NULL;
}
#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,
/**
* Configuration for 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_Line3,
.pin = {
.gpio = GPIOA,
.init = {
.GPIO_Pin = GPIO_Pin_3,
.GPIO_Speed = GPIO_Speed_10MHz,
.GPIO_Mode = GPIO_Mode_IN_FLOATING,
},
},
.irq = {
.init = {
.NVIC_IRQChannel = EXTI3_IRQn,
.NVIC_IRQChannelPreemptionPriority = PIOS_IRQ_PRIO_HIGH,
.NVIC_IRQChannelSubPriority = 0,
.NVIC_IRQChannelCmd = ENABLE,
},
},
.exti = {
.init = {
.EXTI_Line = EXTI_Line3, // matches above GPIO pin
.EXTI_Mode = EXTI_Mode_Interrupt,
.EXTI_Trigger = EXTI_Trigger_Rising,
.EXTI_LineCmd = ENABLE,
},
},
};
#endif /* PIOS_INCLUDE_USB_HID */
#if defined(PIOS_INCLUDE_USB_RCTX)
#include <pios_usb_rctx_priv.h>
const struct pios_usb_rctx_cfg pios_usb_rctx_cfg = {
.data_if = 2,
.data_tx_ep = 1,
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 8 for 1000 Hz
.Smpl_rate_div_no_dlp = 7,
// Clock at 1 khz, downsampled by 1 for 1000 Hz
.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_180DEG,
.fast_prescaler = PIOS_SPI_PRESCALER_4,
.std_prescaler = PIOS_SPI_PRESCALER_64,
.max_downsample = 2
};
#endif /* PIOS_INCLUDE_USB_RCTX */
const struct pios_mpu6000_cfg *PIOS_BOARD_HW_DEFS_GetMPU6000Cfg(__attribute__((unused)) uint32_t board_revision)
{
return (board_revision == BOARD_REVISION_CC3D) ? &pios_mpu6000_cfg : 0;
}
#endif /* PIOS_INCLUDE_MPU6000 */
#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 */
#ifdef PIOS_INCLUDE_ADXL345
bool PIOS_BOARD_HW_DEFS_GetADXL345Cfg(uint32_t board_revision)
{
return board_revision == BOARD_REVISION_CC;
}
#endif

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

@ -36,6 +36,10 @@
*/
#include "../board_hw_defs.c"
#include "pios_usb_board_data_priv.h"
#include "pios_usb_desc_hid_only_priv.h"
#include <pios_com_msg_priv.h>
uint32_t pios_com_telem_usb_id;
/**
@ -44,6 +48,7 @@ uint32_t pios_com_telem_usb_id;
* called from System/openpilot.c
*/
static bool board_init_complete = false;
void PIOS_Board_Init(void)
{
if (board_init_complete) {
@ -84,7 +89,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

@ -30,18 +30,17 @@
#include <pios_board_info.h>
#include <uavobjectsinit.h>
#include <hwsettings.h>
#include <manualcontrolsettings.h>
#include <gcsreceiver.h>
#include <taskinfo.h>
#include <sanitycheck.h>
#include <actuatorsettings.h>
#ifdef PIOS_INCLUDE_INSTRUMENTATION
#include <pios_instrumentation.h>
#endif
#if defined(PIOS_INCLUDE_ADXL345)
#include <pios_adxl345.h>
#endif
#include <pios_board_io.h>
#include <pios_board_sensors.h>
/*
* Pull in the board-specific static HW definitions.
@ -53,185 +52,39 @@
*/
#include "../board_hw_defs.c"
/* One slot per selectable receiver group.
* eg. PWM, PPM, GCS, DSMMAINPORT, DSMFLEXIPORT, SBUS
* NOTE: No slot in this map for NONE.
*/
uint32_t pios_rcvr_group_map[MANUALCONTROLSETTINGS_CHANNELGROUPS_NONE];
static SystemAlarmsExtendedAlarmStatusOptions CopterControlConfigHook();
static void ActuatorSettingsUpdatedCb(UAVObjEvent *ev);
#define PIOS_COM_TELEM_RF_RX_BUF_LEN 32
#define PIOS_COM_TELEM_RF_TX_BUF_LEN 12
#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_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_telem_rf_id;
uint32_t pios_com_telem_usb_id;
uint32_t pios_com_vcp_id;
uint32_t pios_com_gps_id;
uint32_t pios_com_bridge_id;
uint32_t pios_com_hkosd_id;
uint32_t pios_com_msp_id;
uint32_t pios_com_mavlink_id;
uint32_t pios_usb_rctx_id;
uintptr_t pios_uavo_settings_fs_id;
uintptr_t pios_user_fs_id = 0;
/*
* 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)
{
uint32_t pios_usart_id;
if (PIOS_USART_Init(&pios_usart_id, usart_port_cfg)) {
PIOS_Assert(0);
}
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_ibus(const struct pios_usart_cfg *usart_cfg)
{
uint32_t pios_usart_ibus_id;
if (PIOS_USART_Init(&pios_usart_ibus_id, usart_cfg)) {
PIOS_Assert(0);
}
uint32_t pios_ibus_id;
if (PIOS_IBUS_Init(&pios_ibus_id, &pios_usart_com_driver, pios_usart_ibus_id)) {
PIOS_Assert(0);
}
uint32_t pios_ibus_rcvr_id;
if (PIOS_RCVR_Init(&pios_ibus_rcvr_id, &pios_ibus_rcvr_driver, pios_ibus_id)) {
PIOS_Assert(0);
}
pios_rcvr_group_map[MANUALCONTROLSETTINGS_CHANNELGROUPS_IBUS] = pios_ibus_rcvr_id;
}
/**
* Configuration for 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_Line3,
.pin = {
.gpio = GPIOA,
.init = {
.GPIO_Pin = GPIO_Pin_3,
.GPIO_Speed = GPIO_Speed_10MHz,
.GPIO_Mode = GPIO_Mode_IN_FLOATING,
},
},
.irq = {
.init = {
.NVIC_IRQChannel = EXTI3_IRQn,
.NVIC_IRQChannelPreemptionPriority = PIOS_IRQ_PRIO_HIGH,
.NVIC_IRQChannelSubPriority = 0,
.NVIC_IRQChannelCmd = ENABLE,
},
},
.exti = {
.init = {
.EXTI_Line = EXTI_Line3, // matches above GPIO pin
.EXTI_Mode = EXTI_Mode_Interrupt,
.EXTI_Trigger = EXTI_Trigger_Rising,
.EXTI_LineCmd = ENABLE,
},
},
static const PIOS_BOARD_IO_UART_Function main_function_map[] = {
[HWSETTINGS_CC_MAINPORT_TELEMETRY] = PIOS_BOARD_IO_UART_TELEMETRY,
[HWSETTINGS_CC_MAINPORT_GPS] = PIOS_BOARD_IO_UART_GPS,
[HWSETTINGS_CC_MAINPORT_SBUS] = PIOS_BOARD_IO_UART_SBUS,
[HWSETTINGS_CC_MAINPORT_DSM] = PIOS_BOARD_IO_UART_DSM_MAIN,
[HWSETTINGS_CC_MAINPORT_DEBUGCONSOLE] = PIOS_BOARD_IO_UART_DEBUGCONSOLE,
[HWSETTINGS_CC_MAINPORT_COMBRIDGE] = PIOS_BOARD_IO_UART_COMBRIDGE,
[HWSETTINGS_CC_MAINPORT_OSDHK] = PIOS_BOARD_IO_UART_OSDHK,
[HWSETTINGS_CC_MAINPORT_MSP] = PIOS_BOARD_IO_UART_MSP,
[HWSETTINGS_CC_MAINPORT_MAVLINK] = PIOS_BOARD_IO_UART_MAVLINK,
};
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 8 for 1000 Hz
.Smpl_rate_div_no_dlp = 7,
// Clock at 1 khz, downsampled by 1 for 1000 Hz
.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_180DEG,
.fast_prescaler = PIOS_SPI_PRESCALER_4,
.std_prescaler = PIOS_SPI_PRESCALER_64,
.max_downsample = 2
static const PIOS_BOARD_IO_UART_Function flexi_function_map[] = {
[HWSETTINGS_CC_FLEXIPORT_TELEMETRY] = PIOS_BOARD_IO_UART_TELEMETRY,
[HWSETTINGS_CC_FLEXIPORT_GPS] = PIOS_BOARD_IO_UART_GPS,
[HWSETTINGS_CC_FLEXIPORT_DSM] = PIOS_BOARD_IO_UART_DSM_FLEXI,
[HWSETTINGS_CC_FLEXIPORT_EXBUS] = PIOS_BOARD_IO_UART_EXBUS,
[HWSETTINGS_CC_FLEXIPORT_HOTTSUMD] = PIOS_BOARD_IO_UART_HOTT_SUMD,
[HWSETTINGS_CC_FLEXIPORT_HOTTSUMH] = PIOS_BOARD_IO_UART_HOTT_SUMH,
[HWSETTINGS_CC_FLEXIPORT_SRXL] = PIOS_BOARD_IO_UART_SRXL,
[HWSETTINGS_CC_FLEXIPORT_IBUS] = PIOS_BOARD_IO_UART_IBUS,
[HWSETTINGS_CC_FLEXIPORT_DEBUGCONSOLE] = PIOS_BOARD_IO_UART_DEBUGCONSOLE,
[HWSETTINGS_CC_FLEXIPORT_COMBRIDGE] = PIOS_BOARD_IO_UART_COMBRIDGE,
[HWSETTINGS_CC_FLEXIPORT_OSDHK] = PIOS_BOARD_IO_UART_OSDHK,
[HWSETTINGS_CC_FLEXIPORT_MSP] = PIOS_BOARD_IO_UART_MSP,
[HWSETTINGS_CC_FLEXIPORT_MAVLINK] = PIOS_BOARD_IO_UART_MAVLINK,
};
#endif /* PIOS_INCLUDE_MPU6000 */
/**
* PIOS_Board_Init()
@ -258,12 +111,12 @@ void PIOS_Board_Init(void)
switch (bdinfo->board_rev) {
case BOARD_REVISION_CC:
if (PIOS_SPI_Init(&pios_spi_flash_accel_id, &pios_spi_flash_accel_cfg_cc)) {
if (PIOS_SPI_Init(&pios_spi_flash_accel_adapter_id, &pios_spi_flash_accel_cfg_cc)) {
PIOS_Assert(0);
}
break;
case BOARD_REVISION_CC3D:
if (PIOS_SPI_Init(&pios_spi_flash_accel_id, &pios_spi_flash_accel_cfg_cc3d)) {
if (PIOS_SPI_Init(&pios_spi_flash_accel_adapter_id, &pios_spi_flash_accel_cfg_cc3d)) {
PIOS_Assert(0);
}
break;
@ -276,7 +129,7 @@ void PIOS_Board_Init(void)
uintptr_t flash_id;
switch (bdinfo->board_rev) {
case BOARD_REVISION_CC:
if (PIOS_Flash_Jedec_Init(&flash_id, pios_spi_flash_accel_id, 1)) {
if (PIOS_Flash_Jedec_Init(&flash_id, pios_spi_flash_accel_adapter_id, 1)) {
PIOS_DEBUG_Assert(0);
}
if (PIOS_FLASHFS_Logfs_Init(&pios_uavo_settings_fs_id, &flashfs_w25x_cfg, &pios_jedec_flash_driver, flash_id)) {
@ -284,7 +137,7 @@ void PIOS_Board_Init(void)
}
break;
case BOARD_REVISION_CC3D:
if (PIOS_Flash_Jedec_Init(&flash_id, pios_spi_flash_accel_id, 0)) {
if (PIOS_Flash_Jedec_Init(&flash_id, pios_spi_flash_accel_adapter_id, 0)) {
PIOS_DEBUG_Assert(0);
}
if (PIOS_FLASHFS_Logfs_Init(&pios_uavo_settings_fs_id, &flashfs_m25p_cfg, &pios_jedec_flash_driver, flash_id)) {
@ -352,370 +205,40 @@ void PIOS_Board_Init(void)
PIOS_TIM_InitClock(&tim_4_cfg);
#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;
/* Configure FlexiPort */
uint8_t hwsettings_flexiport;
HwSettingsCC_FlexiPortGet(&hwsettings_flexiport);
switch (bdinfo->board_rev) {
case BOARD_REVISION_CC:
PIOS_USB_Init(&pios_usb_id, &pios_usb_main_cfg_cc);
break;
case BOARD_REVISION_CC3D:
PIOS_USB_Init(&pios_usb_id, &pios_usb_main_cfg_cc3d);
break;
default:
PIOS_Assert(0);
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_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;
case HWSETTINGS_USB_VCPPORT_DEBUGCONSOLE:
#if defined(PIOS_INCLUDE_COM)
#if defined(PIOS_INCLUDE_DEBUG_CONSOLE)
{
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 *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)
{
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;
case HWSETTINGS_USB_HIDPORT_RCTRANSMITTER:
#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);
}
}
#endif /* PIOS_INCLUDE_USB_RCTX */
break;
}
#endif /* PIOS_INCLUDE_USB_HID */
#endif /* PIOS_INCLUDE_USB */
/* Configure the main IO port */
uint8_t hwsettings_DSMxBind;
HwSettingsDSMxBindGet(&hwsettings_DSMxBind);
uint8_t hwsettings_cc_mainport;
HwSettingsCC_MainPortGet(&hwsettings_cc_mainport);
switch (hwsettings_cc_mainport) {
case HWSETTINGS_CC_MAINPORT_DISABLED:
break;
case HWSETTINGS_CC_MAINPORT_TELEMETRY:
#if defined(PIOS_INCLUDE_TELEMETRY_RF)
PIOS_Board_configure_com(&pios_usart_generic_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);
#endif /* PIOS_INCLUDE_TELEMETRY_RF */
break;
case HWSETTINGS_CC_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 /* PIOS_INCLUDE_SBUS */
break;
case HWSETTINGS_CC_MAINPORT_GPS:
#if defined(PIOS_INCLUDE_GPS)
PIOS_Board_configure_com(&pios_usart_generic_main_cfg, PIOS_COM_GPS_RX_BUF_LEN, 0, &pios_usart_com_driver, &pios_com_gps_id);
#endif /* PIOS_INCLUDE_GPS */
break;
case HWSETTINGS_CC_MAINPORT_DSM:
#if defined(PIOS_INCLUDE_DSM)
PIOS_Board_configure_dsm(&pios_usart_dsm_main_cfg, &pios_dsm_main_cfg,
&pios_usart_com_driver, MANUALCONTROLSETTINGS_CHANNELGROUPS_DSMMAINPORT, &hwsettings_DSMxBind);
#endif /* PIOS_INCLUDE_DSM */
break;
case HWSETTINGS_CC_MAINPORT_DEBUGCONSOLE:
#if defined(PIOS_INCLUDE_COM)
#if defined(PIOS_INCLUDE_DEBUG_CONSOLE)
PIOS_Board_configure_com(&pios_usart_generic_main_cfg, 0, PIOS_COM_DEBUGCONSOLE_TX_BUF_LEN, &pios_usart_com_driver, &pios_com_debug_id);
#endif /* PIOS_INCLUDE_DEBUG_CONSOLE */
#endif /* PIOS_INCLUDE_COM */
break;
case HWSETTINGS_CC_MAINPORT_COMBRIDGE:
PIOS_Board_configure_com(&pios_usart_generic_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_CC_MAINPORT_MSP:
PIOS_Board_configure_com(&pios_usart_generic_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_CC_MAINPORT_MAVLINK:
PIOS_Board_configure_com(&pios_usart_generic_main_cfg, 0, PIOS_COM_MAVLINK_TX_BUF_LEN, &pios_usart_com_driver, &pios_com_mavlink_id);
break;
case HWSETTINGS_CC_MAINPORT_OSDHK:
PIOS_Board_configure_com(&pios_usart_hkosd_main_cfg, 0, PIOS_COM_HKOSD_TX_BUF_LEN, &pios_usart_com_driver, &pios_com_hkosd_id);
break;
}
/* Configure the flexi port */
uint8_t hwsettings_cc_flexiport;
HwSettingsCC_FlexiPortGet(&hwsettings_cc_flexiport);
switch (hwsettings_cc_flexiport) {
case HWSETTINGS_CC_FLEXIPORT_DISABLED:
break;
case HWSETTINGS_CC_FLEXIPORT_TELEMETRY:
#if defined(PIOS_INCLUDE_TELEMETRY_RF)
PIOS_Board_configure_com(&pios_usart_generic_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);
#endif /* PIOS_INCLUDE_TELEMETRY_RF */
break;
case HWSETTINGS_CC_FLEXIPORT_COMBRIDGE:
PIOS_Board_configure_com(&pios_usart_generic_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_CC_FLEXIPORT_MSP:
PIOS_Board_configure_com(&pios_usart_generic_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_CC_FLEXIPORT_MAVLINK:
PIOS_Board_configure_com(&pios_usart_generic_flexi_cfg, 0, PIOS_COM_MAVLINK_TX_BUF_LEN, &pios_usart_com_driver, &pios_com_mavlink_id);
break;
case HWSETTINGS_CC_FLEXIPORT_GPS:
#if defined(PIOS_INCLUDE_GPS)
PIOS_Board_configure_com(&pios_usart_generic_flexi_cfg, PIOS_COM_GPS_RX_BUF_LEN, 0, &pios_usart_com_driver, &pios_com_gps_id);
#endif /* PIOS_INCLUDE_GPS */
break;
case HWSETTINGS_CC_FLEXIPORT_PPM:
#if defined(PIOS_INCLUDE_PPM_FLEXI)
{
uint32_t pios_ppm_id;
PIOS_PPM_Init(&pios_ppm_id, &pios_ppm_flexi_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;
}
#endif /* PIOS_INCLUDE_PPM_FLEXI */
break;
case HWSETTINGS_CC_FLEXIPORT_DSM:
#if defined(PIOS_INCLUDE_DSM)
PIOS_Board_configure_dsm(&pios_usart_dsm_flexi_cfg, &pios_dsm_flexi_cfg,
&pios_usart_com_driver, MANUALCONTROLSETTINGS_CHANNELGROUPS_DSMFLEXIPORT, &hwsettings_DSMxBind);
#endif /* PIOS_INCLUDE_DSM */
break;
case HWSETTINGS_CC_FLEXIPORT_HOTTSUMD:
case HWSETTINGS_CC_FLEXIPORT_HOTTSUMH:
#if defined(PIOS_INCLUDE_HOTT)
{
uint32_t pios_usart_hott_id;
if (PIOS_USART_Init(&pios_usart_hott_id, &pios_usart_hott_flexi_cfg)) {
PIOS_Assert(0);
}
uint32_t pios_hott_id;
if (PIOS_HOTT_Init(&pios_hott_id, &pios_usart_com_driver, pios_usart_hott_id,
hwsettings_cc_flexiport == HWSETTINGS_CC_FLEXIPORT_HOTTSUMD ? PIOS_HOTT_PROTO_SUMD : PIOS_HOTT_PROTO_SUMH)) {
PIOS_Assert(0);
}
uint32_t pios_hott_rcvr_id;
if (PIOS_RCVR_Init(&pios_hott_rcvr_id, &pios_hott_rcvr_driver, pios_hott_id)) {
PIOS_Assert(0);
}
pios_rcvr_group_map[MANUALCONTROLSETTINGS_CHANNELGROUPS_HOTT] = pios_hott_rcvr_id;
}
#endif /* PIOS_INCLUDE_HOTT */
break;
case HWSETTINGS_CC_FLEXIPORT_EXBUS:
#if defined(PIOS_INCLUDE_EXBUS)
{
uint32_t pios_usart_exbus_id;
if (PIOS_USART_Init(&pios_usart_exbus_id, &pios_usart_exbus_flexi_cfg)) {
PIOS_Assert(0);
}
uint32_t pios_exbus_id;
if (PIOS_EXBUS_Init(&pios_exbus_id, &pios_usart_com_driver, pios_usart_exbus_id)) {
PIOS_Assert(0);
}
uint32_t pios_exbus_rcvr_id;
if (PIOS_RCVR_Init(&pios_exbus_rcvr_id, &pios_exbus_rcvr_driver, pios_exbus_id)) {
PIOS_Assert(0);
}
pios_rcvr_group_map[MANUALCONTROLSETTINGS_CHANNELGROUPS_EXBUS] = pios_exbus_rcvr_id;
}
#endif /* PIOS_INCLUDE_EXBUS */
break;
case HWSETTINGS_CC_FLEXIPORT_SRXL:
#if defined(PIOS_INCLUDE_SRXL)
{
uint32_t pios_usart_srxl_id;
if (PIOS_USART_Init(&pios_usart_srxl_id, &pios_usart_srxl_flexi_cfg)) {
PIOS_Assert(0);
}
uint32_t pios_srxl_id;
if (PIOS_SRXL_Init(&pios_srxl_id, &pios_usart_com_driver, pios_usart_srxl_id)) {
PIOS_Assert(0);
}
uint32_t pios_srxl_rcvr_id;
if (PIOS_RCVR_Init(&pios_srxl_rcvr_id, &pios_srxl_rcvr_driver, pios_srxl_id)) {
PIOS_Assert(0);
}
pios_rcvr_group_map[MANUALCONTROLSETTINGS_CHANNELGROUPS_SRXL] = pios_srxl_rcvr_id;
}
#endif /* PIOS_INCLUDE_SRXL */
break;
case HWSETTINGS_CC_FLEXIPORT_IBUS:
#if defined(PIOS_INCLUDE_IBUS)
PIOS_Board_configure_ibus(&pios_usart_ibus_flexi_cfg);
#endif /* PIOS_INCLUDE_IBUS */
break;
case HWSETTINGS_CC_FLEXIPORT_DEBUGCONSOLE:
#if defined(PIOS_INCLUDE_COM)
#if defined(PIOS_INCLUDE_DEBUG_CONSOLE)
PIOS_Board_configure_com(&pios_usart_generic_flexi_cfg, 0, PIOS_COM_DEBUGCONSOLE_TX_BUF_LEN, &pios_usart_com_driver, &pios_com_debug_id);
#endif /* PIOS_INCLUDE_DEBUG_CONSOLE */
#endif /* PIOS_INCLUDE_COM */
break;
switch (hwsettings_flexiport) {
case HWSETTINGS_CC_FLEXIPORT_I2C:
#if defined(PIOS_INCLUDE_I2C)
{
if (PIOS_I2C_Init(&pios_i2c_flexi_adapter_id, &pios_i2c_flexi_adapter_cfg)) {
PIOS_Assert(0);
}
if (PIOS_I2C_Init(&pios_i2c_flexi_adapter_id, &pios_i2c_flexi_adapter_cfg)) {
PIOS_Assert(0);
}
#endif /* PIOS_INCLUDE_I2C */
break;
case HWSETTINGS_CC_FLEXIPORT_OSDHK:
PIOS_Board_configure_com(&pios_usart_hkosd_flexi_cfg, 0, PIOS_COM_HKOSD_TX_BUF_LEN, &pios_usart_com_driver, &pios_com_hkosd_id);
case HWSETTINGS_CC_FLEXIPORT_PPM:
#if defined(PIOS_INCLUDE_PPM_FLEXI)
PIOS_BOARD_IO_Configure_PPM_RCVR(&pios_ppm_flexi_cfg);
#endif /* PIOS_INCLUDE_PPM_FLEXI */
break;
}
/* Configure main USART port */
uint8_t hwsettings_mainport;
HwSettingsCC_MainPortGet(&hwsettings_mainport);
if (hwsettings_mainport < NELEMENTS(main_function_map)) {
PIOS_BOARD_IO_Configure_UART(&pios_usart_main_cfg, main_function_map[hwsettings_mainport]);
}
/* Configure the rcvr port */
uint8_t hwsettings_rcvrport;
HwSettingsCC_RcvrPortGet(&hwsettings_rcvrport);
@ -731,79 +254,32 @@ void PIOS_Board_Init(void)
break;
case HWSETTINGS_CC_RCVRPORT_PWMNOONESHOT:
#if defined(PIOS_INCLUDE_PWM)
{
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_RCVR(&pios_pwm_cfg);
#endif /* PIOS_INCLUDE_PWM */
break;
case HWSETTINGS_CC_RCVRPORT_PPMNOONESHOT:
case HWSETTINGS_CC_RCVRPORT_PPMOUTPUTSNOONESHOT:
case HWSETTINGS_CC_RCVRPORT_PPM_PIN8ONESHOT:
#if defined(PIOS_INCLUDE_PPM)
{
uint32_t pios_ppm_id;
if (hwsettings_rcvrport == HWSETTINGS_CC_RCVRPORT_PPM_PIN8ONESHOT) {
PIOS_PPM_Init(&pios_ppm_id, &pios_ppm_pin8_cfg);
} else {
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_RCVR((hwsettings_rcvrport == HWSETTINGS_CC_RCVRPORT_PPM_PIN8ONESHOT) ? &pios_ppm_pin8_cfg : &pios_ppm_cfg);
#endif /* PIOS_INCLUDE_PPM */
break;
case HWSETTINGS_CC_RCVRPORT_PPMPWMNOONESHOT:
/* This is a combination of PPM and PWM inputs */
#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_RCVR(&pios_ppm_cfg);
#endif /* PIOS_INCLUDE_PPM */
#if defined(PIOS_INCLUDE_PWM)
{
uint32_t pios_pwm_id;
PIOS_PWM_Init(&pios_pwm_id, &pios_pwm_with_ppm_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_RCVR(&pios_pwm_with_ppm_cfg);
#endif /* PIOS_INCLUDE_PWM */
break;
case HWSETTINGS_CC_RCVRPORT_OUTPUTSONESHOT:
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 */
#ifdef PIOS_INCLUDE_GCSRCVR
PIOS_BOARD_IO_Configure_GCS_RCVR();
#endif
/* Remap AFIO pin for PB4 (Servo 5 Out)*/
GPIO_PinRemapConfig(GPIO_Remap_SWJ_NoJTRST, ENABLE);
@ -828,33 +304,23 @@ void PIOS_Board_Init(void)
switch (bdinfo->board_rev) {
case BOARD_REVISION_CC:
// Revision 1 with invensense gyros, start the ADC
#if defined(PIOS_INCLUDE_ADC)
PIOS_ADC_Init(&pios_adc_cfg);
#endif
#if defined(PIOS_INCLUDE_ADXL345)
PIOS_ADXL345_Init(pios_spi_flash_accel_id, 0);
#endif
break;
case BOARD_REVISION_CC3D:
// Revision 2 with MPU6000 gyros, start a SPI interface and connect to it
GPIO_PinRemapConfig(GPIO_Remap_SWJ_JTAGDisable, ENABLE);
#if defined(PIOS_INCLUDE_MPU6000)
// Set up the SPI interface to the serial flash
if (PIOS_SPI_Init(&pios_spi_gyro_id, &pios_spi_gyro_cfg)) {
// Set up the SPI interface to the mpu6000
if (PIOS_SPI_Init(&pios_spi_gyro_adapter_id, &pios_spi_gyro_cfg)) {
PIOS_Assert(0);
}
PIOS_MPU6000_Init(pios_spi_gyro_id, 0, &pios_mpu6000_cfg);
PIOS_MPU6000_CONFIG_Configure();
init_test = !PIOS_MPU6000_Driver.test(0);
#endif /* PIOS_INCLUDE_MPU6000 */
break;
default:
PIOS_Assert(0);
}
PIOS_BOARD_Sensors_Configure();
/* Make sure we have at least one telemetry link configured or else fail initialization */
PIOS_Assert(pios_com_telem_rf_id || pios_com_telem_usb_id);

View File

@ -116,50 +116,50 @@ extern uint32_t pios_i2c_flexi_adapter_id;
//
// See also pios_board.c
// -------------------------
#define PIOS_SPI_MAX_DEVS 2
#define PIOS_SPI_MAX_DEVS 2
extern uint32_t pios_spi_gyro_adapter_id;
#define PIOS_SPI_MPU6000_ADAPTER (pios_spi_gyro_adapter_id)
extern uint32_t pios_spi_flash_accel_adapter_id;
#define PIOS_SPI_ADXL345_ADAPTER (pios_spi_flash_accel_adapter_id)
// -------------------------
// PIOS_USART
// -------------------------
#define PIOS_USART_MAX_DEVS 2
#define PIOS_USART_MAX_DEVS 2
// Inverter for SBUS handling
#define PIOS_USART_INVERTER_PORT USART1
#define PIOS_USART_INVERTER_GPIO GPIOB
#define PIOS_USART_INVERTER_PIN GPIO_Pin_2
#define PIOS_USART_INVERTER_ENABLE Bit_SET
#define PIOS_USART_INVERTER_DISABLE Bit_RESET
// -------------------------
// PIOS_COM
//
// See also pios_board.c
// -------------------------
#define PIOS_COM_MAX_DEVS 3
#define PIOS_COM_MAX_DEVS 3
extern uint32_t pios_com_telem_rf_id;
#define PIOS_COM_TELEM_RF (pios_com_telem_rf_id)
#define PIOS_COM_TELEM_RF_RX_BUF_LEN 32
#define PIOS_COM_TELEM_RF_TX_BUF_LEN 12
#if defined(PIOS_INCLUDE_GPS)
extern uint32_t pios_com_gps_id;
#define PIOS_COM_GPS (pios_com_gps_id)
#endif /* PIOS_INCLUDE_GPS */
#define PIOS_COM_GPS_RX_BUF_LEN 32
extern uint32_t pios_com_bridge_id;
#define PIOS_COM_BRIDGE (pios_com_bridge_id)
#define PIOS_COM_TELEM_USB_RX_BUF_LEN 65
#define PIOS_COM_TELEM_USB_TX_BUF_LEN 65
extern uint32_t pios_com_vcp_id;
#define PIOS_COM_VCP (pios_com_vcp_id)
#define PIOS_COM_BRIDGE_RX_BUF_LEN 65
#define PIOS_COM_BRIDGE_TX_BUF_LEN 12
extern uint32_t pios_com_telem_usb_id;
#define PIOS_COM_TELEM_USB (pios_com_telem_usb_id)
#define PIOS_COM_HKOSD_TX_BUF_LEN 22
#if defined(PIOS_INCLUDE_DEBUG_CONSOLE)
extern uint32_t pios_com_debug_id;
#define PIOS_COM_DEBUG (pios_com_debug_id)
#endif /* PIOS_INCLUDE_DEBUG_CONSOLE */
#define PIOS_COM_MSP_TX_BUF_LEN 128
#define PIOS_COM_MSP_RX_BUF_LEN 64
extern uint32_t pios_com_hkosd_id;
#define PIOS_COM_OSDHK (pios_com_hkosd_id)
#define PIOS_COM_MAVLINK_TX_BUF_LEN 128
extern uint32_t pios_com_msp_id;
#define PIOS_COM_MSP (pios_com_msp_id)
extern uint32_t pios_com_mavlink_id;
#define PIOS_COM_MAVLINK (pios_com_mavlink_id)
#define PIOS_COM_DEBUGCONSOLE_TX_BUF_LEN 40
// -------------------------
// ADC

View File

@ -343,15 +343,15 @@ static const struct pios_spi_cfg pios_spi_gyro_cfg = {
}
};
static uint32_t pios_spi_gyro_id;
uint32_t pios_spi_gyro_adapter_id;
void PIOS_SPI_gyro_irq_handler(void)
{
/* Call into the generic code to handle the IRQ for this specific device */
PIOS_SPI_IRQ_Handler(pios_spi_gyro_id);
PIOS_SPI_IRQ_Handler(pios_spi_gyro_adapter_id);
}
#if false
#ifdef PIOS_INCLUDE_RFM22B
/*
* SPI3 Interface
* Used for Flash and the RFM22B
@ -479,11 +479,11 @@ static const struct pios_spi_cfg pios_spi_telem_flash_cfg = {
},
};
uint32_t pios_spi_telem_flash_id;
uint32_t pios_spi_telem_flash_adapter_id;
void PIOS_SPI_telem_flash_irq_handler(void)
{
/* Call into the generic code to handle the IRQ for this specific device */
PIOS_SPI_IRQ_Handler(pios_spi_telem_flash_id);
PIOS_SPI_IRQ_Handler(pios_spi_telem_flash_adapter_id);
}
@ -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,33 +600,17 @@ static const struct flashfs_logfs_cfg flashfs_internal_user_cfg = {
};
#endif /* PIOS_INCLUDE_FLASH */
#ifdef PIOS_INCLUDE_USART
#include <pios_usart_priv.h>
#ifdef PIOS_INCLUDE_COM_TELEM
/*
* MAIN USART
*/
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 = {
.rx = {
.gpio = GPIOA,
.init = {
.GPIO_Pin = GPIO_Pin_10,
@ -636,52 +620,7 @@ static const struct pios_usart_cfg pios_usart_main_cfg = {
.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 = {
.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 = {
.tx = {
.gpio = GPIOA,
.init = {
.GPIO_Pin = GPIO_Pin_9,
@ -693,119 +632,13 @@ static const struct pios_usart_cfg pios_usart_dsm_main_cfg = {
},
};
// 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 = {
.rx = {
.gpio = GPIOB,
.init = {
.GPIO_Pin = GPIO_Pin_11,
@ -815,7 +648,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_10,
@ -827,173 +660,11 @@ 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 = {
.dtr = {
// FlexIO pin 9
.gpio = GPIOC,
.init = {
@ -1004,7 +675,7 @@ static const struct pios_usart_cfg pios_usart_rcvrport_cfg = {
},
},
.tx = {
.tx = {
// * 7: PC6 = TIM8 CH1, USART6 TX
.gpio = GPIOC,
.init = {
@ -1014,10 +685,10 @@ static const struct pios_usart_cfg pios_usart_rcvrport_cfg = {
.GPIO_OType = GPIO_OType_PP,
.GPIO_PuPd = GPIO_PuPd_UP
},
.pin_source = GPIO_PinSource6,
.pin_source = GPIO_PinSource6,
},
.rx = {
.rx = {
// * 8: PC7 = TIM8 CH2, USART6 RX
.gpio = GPIOC,
.init = {
@ -1027,9 +698,10 @@ static const struct pios_usart_cfg pios_usart_rcvrport_cfg = {
.GPIO_OType = GPIO_OType_PP,
.GPIO_PuPd = GPIO_PuPd_UP
},
.pin_source = GPIO_PinSource7,
.pin_source = GPIO_PinSource7,
}
};
#endif /* PIOS_INCLUDE_USART */
#if defined(PIOS_INCLUDE_COM)
@ -1385,212 +1057,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 +1132,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 +1234,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 +1300,199 @@ 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"
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
};
const struct pios_mpu6000_cfg *PIOS_BOARD_HW_DEFS_GetMPU6000Cfg(__attribute__((unused)) uint32_t board_revision)
{
return &pios_mpu6000_cfg;
}
#endif /* PIOS_INCLUDE_MPU6000 */

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

@ -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,7 @@
uint32_t pios_com_telem_usb_id;
static bool board_init_complete = false;
void PIOS_Board_Init()
{
if (board_init_complete) {
@ -68,7 +69,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

@ -86,6 +86,7 @@
// #define PIOS_MPU6000_ACCEL
/* #define PIOS_INCLUDE_HMC5843 */
#define PIOS_INCLUDE_HMC5X83
#define PIOS_INCLUDE_HMC5X83_INTERNAL
// #define PIOS_HMC5X83_HAS_GPIOS
/* #define PIOS_INCLUDE_BMP085 */
// #define PIOS_INCLUDE_MS5611

View File

@ -30,19 +30,17 @@
#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>
#include <pios_board_sensors.h>
/*
* Pull in the board-specific static HW definitions.
* Including .c files is a bit ugly but this allows all of
@ -53,327 +51,61 @@
*/
#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)
{
uint32_t pios_usart_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,
};
if (PIOS_USART_Init(&pios_usart_id, usart_port_cfg)) {
PIOS_Assert(0);
}
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,
};
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;
}
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,
};
/**
* PIOS_Board_Init()
* 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)
@ -387,17 +119,20 @@ void PIOS_Board_Init(void)
#endif
#if false
#ifdef PIOS_INCLUDE_MPU6000
/* Set up the SPI interface to the gyro/acelerometer */
if (PIOS_SPI_Init(&pios_spi_gyro_id, &pios_spi_gyro_cfg)) {
if (PIOS_SPI_Init(&pios_spi_gyro_adapter_id, &pios_spi_gyro_cfg)) {
PIOS_DEBUG_Assert(0);
}
#endif /* PIOS_INCLUDE_MPU6000 */
/* Set up the SPI interface to the flash and rfm22b */
if (PIOS_SPI_Init(&pios_spi_telem_flash_id, &pios_spi_telem_flash_cfg)) {
#ifdef PIOS_INCLUDE_RFM22B
/* Set up the SPI interface to the rfm22b */
if (PIOS_SPI_Init(&pios_spi_telem_flash_adapter_id, &pios_spi_telem_flash_cfg)) {
PIOS_DEBUG_Assert(0);
}
#endif
#endif /* PIOS_INCLUDE_RFM22B */
#if defined(PIOS_INCLUDE_FLASH)
/* Connect flash to the appropriate interface and configure it */
uintptr_t flash_id;
@ -446,12 +181,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 +207,53 @@ 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 */
PIOS_DELAY_WaitmS(50);
}
#endif
#if defined(PIOS_INCLUDE_USB)
PIOS_BOARD_IO_Configure_USB();
#endif
/* Initialize the RFM22B radio COM device. */
#if defined(PIOS_INCLUDE_RFM22B)
/* Configure main USART port */
uint8_t hwsettings_mainport;
HwSettingsRM_MainPortGet(&hwsettings_mainport);
/* 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;
if (hwsettings_mainport < NELEMENTS(main_function_map)) {
PIOS_BOARD_IO_Configure_UART(&pios_usart_main_cfg, main_function_map[hwsettings_mainport]);
}
OPLinkStatusSet(&oplinkStatus);
#if defined(PIOS_INCLUDE_RFM22B)
PIOS_BOARD_IO_Configure_RFM22B();
uint8_t hwsettings_radioaux;
HwSettingsRadioAuxStreamGet(&hwsettings_radioaux);
PIOS_BOARD_IO_Configure_RadioAuxStream(hwsettings_radioaux);
#endif /* PIOS_INCLUDE_RFM22B */
#if defined(PIOS_INCLUDE_PWM) || defined(PIOS_INCLUDE_PPM)
const struct pios_servo_cfg *pios_servo_cfg;
@ -878,14 +264,17 @@ 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:
#if defined(PIOS_INCLUDE_PWM)
/* Set up the receiver port. Later this should be optional */
PIOS_Board_configure_pwm(&pios_pwm_cfg);
PIOS_BOARD_IO_Configure_PWM_RCVR(&pios_pwm_cfg);
#endif /* PIOS_INCLUDE_PWM */
break;
case HWSETTINGS_RM_RCVRPORT_PPM:
@ -898,16 +287,16 @@ void PIOS_Board_Init(void)
case HWSETTINGS_RM_RCVRPORT_PPMMAVLINK:
case HWSETTINGS_RM_RCVRPORT_PPMGPS:
#if defined(PIOS_INCLUDE_PPM)
PIOS_BOARD_IO_Configure_PPM_RCVR(&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;
}
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);
PIOS_BOARD_IO_Configure_PWM_RCVR(&pios_pwm_ppm_cfg);
}
break;
@ -917,60 +306,9 @@ void PIOS_Board_Init(void)
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_GCS_RCVR();
#endif
#ifndef PIOS_ENABLE_DEBUG_PINS
// pios_servo_cfg points to the correct configuration based on input port settings
@ -979,6 +317,13 @@ void PIOS_Board_Init(void)
PIOS_DEBUG_Init(pios_tim_servoport_all_pins, NELEMENTS(pios_tim_servoport_all_pins));
#endif
PIOS_BOARD_Sensors_Configure();
#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 +333,6 @@ 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);
}
}
}
#endif // PIOS_INCLUDE_ADC
}

View File

@ -85,71 +85,54 @@
// PIOS_SPI
// See also pios_board.c
// ------------------------
#define PIOS_SPI_MAX_DEVS 3
#define PIOS_SPI_MAX_DEVS 3
extern uint32_t pios_spi_telem_flash_adapter_id;
#define PIOS_SPI_RFM22B_ADAPTER (pios_spi_telem_flash_adapter_id)
extern uint32_t pios_spi_gyro_adapter_id;
#define PIOS_SPI_MPU6000_ADAPTER (pios_spi_gyro_adapter_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_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
// ------------------------
// 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_pressure_adapter_id;
#define PIOS_I2C_MAIN_ADAPTER (pios_i2c_mag_pressure_adapter_id)
#define PIOS_I2C_HMC5X83_INTERNAL_ADAPTER (pios_i2c_mag_pressure_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_FLEXI_ADAPTER)
// -------------------------
// PIOS_USART
//
// See also pios_board.c
// -------------------------
#define PIOS_USART_MAX_DEVS 5
#define PIOS_USART_MAX_DEVS 5
// Inverter for SBUS handling
#define PIOS_USART_INVERTER_PORT USART1
#define PIOS_USART_INVERTER_GPIO GPIOC
#define PIOS_USART_INVERTER_PIN GPIO_Pin_0
#define PIOS_USART_INVERTER_ENABLE Bit_SET
#define PIOS_USART_INVERTER_DISABLE Bit_RESET
// -------------------------
// PIOS_COM
//
// 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_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_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_OSDHK (pios_com_hkosd_id)
#define PIOS_COM_MSP (pios_com_msp_id)
#define PIOS_COM_MAVLINK (pios_com_mavlink_id)
#if defined(PIOS_INCLUDE_DEBUG_CONSOLE)
extern uint32_t pios_com_debug_id;
#define PIOS_COM_DEBUG (pios_com_debug_id)
#endif /* PIOS_INCLUDE_DEBUG_CONSOLE */
#if defined(PIOS_INCLUDE_RFM22B)
extern uint32_t pios_rfm22b_id;
extern uint32_t pios_spi_telem_flash_id;
#define PIOS_RFM22_SPI_PORT (pios_spi_telem_flash_id)
#endif /* PIOS_INCLUDE_RFM22B */
#define PIOS_COM_MAX_DEVS 4
// -------------------------
// Packet Handler

View File

@ -268,22 +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,
.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_IRQChannelPriority = PIOS_IRQ_PRIO_MID,
.NVIC_IRQChannelCmd = ENABLE,
},
},
.rx = {
.rx = {
.gpio = GPIOA,
.init = {
.GPIO_Pin = GPIO_Pin_10,
@ -292,7 +277,7 @@ static const struct pios_usart_cfg pios_usart_generic_main_cfg = {
.GPIO_Mode = GPIO_Mode_AF,
},
},
.tx = {
.tx = {
.gpio = GPIOA,
.init = {
.GPIO_Pin = GPIO_Pin_9,

View File

@ -70,9 +70,12 @@ void setupCom()
if (PIOS_USART_Init(&pios_usart_generic_id, &pios_usart_generic_main_cfg)) {
PIOS_Assert(0);
}
if (PIOS_COM_Init(&PIOS_COM_TELEM_USB, &pios_usart_com_driver, pios_usart_generic_id,
rx_buffer, PIOS_COM_MAIN_RX_BUF_LEN,
tx_buffer, PIOS_COM_MAIN_TX_BUF_LEN)) {
PIOS_Assert(0);
}
PIOS_COM_ChangeBaud(PIOS_COM_TELEM_USB, 57600);
}

View File

@ -83,6 +83,7 @@
// #define PIOS_MPU6000_ACCEL
/* #define PIOS_INCLUDE_HMC5843 */
#define PIOS_INCLUDE_HMC5X83
#define PIOS_INCLUDE_HMC5X83_INTERNAL
// #define PIOS_HMC5X83_HAS_GPIOS
/* #define PIOS_INCLUDE_BMP085 */
/* #define PIOS_INCLUDE_MS5611 */

View File

@ -114,6 +114,8 @@ void PIOS_Board_Init(void)
tx_buffer, PIOS_COM_MAIN_TX_BUF_LEN)) {
PIOS_Assert(0);
}
PIOS_COM_ChangeBaud(pios_com_main_id, 57600);
}
#endif

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;
}
@ -693,23 +693,7 @@ const struct pios_ppm_out_cfg pios_flexi_ppm_out_cfg = {
*/
static const struct pios_usart_cfg pios_usart_main_cfg = {
.regs = 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_HIGH,
.NVIC_IRQChannelSubPriority = 0,
.NVIC_IRQChannelCmd = ENABLE,
},
},
.rx = {
.rx = {
.gpio = GPIOA,
.init = {
.GPIO_Pin = GPIO_Pin_10,
@ -717,7 +701,7 @@ static const struct pios_usart_cfg pios_usart_main_cfg = {
.GPIO_Mode = GPIO_Mode_IPU,
},
},
.tx = {
.tx = {
.gpio = GPIOA,
.init = {
.GPIO_Pin = GPIO_Pin_9,
@ -729,23 +713,7 @@ static const struct pios_usart_cfg pios_usart_main_cfg = {
static const struct pios_usart_cfg pios_usart_flexi_cfg = {
.regs = 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_11,
@ -753,7 +721,7 @@ static const struct pios_usart_cfg pios_usart_flexi_cfg = {
.GPIO_Mode = GPIO_Mode_IPU,
},
},
.tx = {
.tx = {
.gpio = GPIOB,
.init = {
.GPIO_Pin = GPIO_Pin_10,
@ -827,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"
@ -839,29 +812,6 @@ static const struct pios_usb_cfg pios_usb_main_cfg = {
#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_FLASH_EEPROM)
#include <pios_eeprom.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

@ -37,6 +37,7 @@
#ifdef PIOS_INCLUDE_SERVO
#include <pios_servo.h>
#endif
#include <pios_board_io.h>
/*
* Pull in the board-specific static HW definitions.
@ -48,36 +49,17 @@
*/
#include "../board_hw_defs.c"
#define PIOS_COM_TELEM_USB_RX_BUF_LEN 128
#define PIOS_COM_TELEM_USB_TX_BUF_LEN 128
#define PIOS_COM_TELEM_VCP_RX_BUF_LEN 128
#define PIOS_COM_TELEM_VCP_TX_BUF_LEN 128
#define PIOS_COM_RFM22B_RF_RX_BUF_LEN 128
#define PIOS_COM_RFM22B_RF_TX_BUF_LEN 128
#define PIOS_COM_TELEM_RX_BUF_LEN 128
#define PIOS_COM_TELEM_TX_BUF_LEN 128
uint32_t pios_com_hid_id = 0;
uint32_t pios_com_vcp_id = 0;
// uint32_t pios_com_vcp_id = 0; /* this is provided by pios_board_io.c */
uint32_t pios_com_main_id = 0;
uint32_t pios_com_flexi_id = 0;
uint32_t pios_com_bridge_id = 0;
uint32_t pios_com_gcs_id = 0;
uint32_t pios_com_gcs_out_id = 0;
#if defined(PIOS_INCLUDE_PPM)
uint32_t pios_ppm_rcvr_id = 0;
#endif
#if defined(PIOS_INCLUDE_PPM_OUT)
uint32_t pios_ppm_out_id = 0;
#endif
#if defined(PIOS_INCLUDE_RFM22B)
#include <pios_rfm22b_com.h>
uint32_t pios_rfm22b_id = 0;
uint32_t pios_com_pri_radio_id = 0;
uint32_t pios_com_aux_radio_id = 0;
uint32_t pios_com_pri_radio_out_id = 0;
uint32_t pios_com_aux_radio_out_id = 0;
#endif
@ -87,41 +69,6 @@ uintptr_t pios_user_fs_id = 0;
static uint8_t servo_count = 0;
/*
* Setup a com port based on the passed cfg, driver and buffer sizes.
* tx size of 0 make the port rx only
* rx size of 0 make the port tx only
* having both tx and rx size of 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)
{
uint32_t pios_usart_id;
if (PIOS_USART_Init(&pios_usart_id, usart_port_cfg)) {
PIOS_Assert(0);
}
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);
}
}
// Forward definitions
static void PIOS_Board_PPM_callback(uint32_t context, const int16_t *channels);
@ -184,10 +131,7 @@ void PIOS_Board_Init(void)
PIOS_IAP_WriteBootCmd(2, 0);
}
#if defined(PIOS_INCLUDE_RFM22B)
OPLinkSettingsInitialize();
OPLinkStatusInitialize();
#endif /* PIOS_INCLUDE_RFM22B */
/* Retrieve the settings object. */
OPLinkSettingsData oplinkSettings;
@ -195,12 +139,7 @@ void PIOS_Board_Init(void)
/* Determine the modem protocols */
bool is_coordinator = (oplinkSettings.Protocol == OPLINKSETTINGS_PROTOCOL_OPLINKCOORDINATOR);
bool openlrs = (oplinkSettings.Protocol == OPLINKSETTINGS_PROTOCOL_OPENLRS);
bool ppm_only = (oplinkSettings.LinkType == OPLINKSETTINGS_LINKTYPE_CONTROL);
bool data_mode = ((oplinkSettings.LinkType == OPLINKSETTINGS_LINKTYPE_DATA) ||
(oplinkSettings.LinkType == OPLINKSETTINGS_LINKTYPE_DATAANDCONTROL));
bool is_enabled = ((oplinkSettings.Protocol != OPLINKSETTINGS_PROTOCOL_DISABLED) &&
((oplinkSettings.MaxRFPower != OPLINKSETTINGS_MAXRFPOWER_0) || openlrs));
bool ppm_mode = ((oplinkSettings.LinkType == OPLINKSETTINGS_LINKTYPE_CONTROL) ||
(oplinkSettings.LinkType == OPLINKSETTINGS_LINKTYPE_DATAANDCONTROL));
bool servo_main = false;
@ -300,9 +239,9 @@ void PIOS_Board_Init(void)
case OPLINKSETTINGS_MAINPORT_TELEMETRY:
case OPLINKSETTINGS_MAINPORT_SERIAL:
#ifndef PIOS_RFM22B_DEBUG_ON_TELEM
PIOS_Board_configure_com(&pios_usart_main_cfg,
PIOS_COM_TELEM_RX_BUF_LEN, PIOS_COM_TELEM_TX_BUF_LEN,
&pios_usart_com_driver, &pios_com_main_id);
PIOS_BOARD_IO_Configure_UART_COM(&pios_usart_main_cfg,
PIOS_COM_TELEM_RF_RX_BUF_LEN, PIOS_COM_TELEM_RF_TX_BUF_LEN,
&pios_com_main_id);
PIOS_COM_ChangeBaud(pios_com_main_id, mainComSpeed);
#endif /* !PIOS_RFM22B_DEBUG_ON_TELEM */
break;
@ -310,12 +249,7 @@ void PIOS_Board_Init(void)
#if defined(PIOS_INCLUDE_PPM)
/* PPM input is configured on the coordinator modem and output on the remote modem. */
if (is_coordinator) {
uint32_t pios_ppm_id;
PIOS_PPM_Init(&pios_ppm_id, &pios_ppm_main_cfg);
if (PIOS_RCVR_Init(&pios_ppm_rcvr_id, &pios_ppm_rcvr_driver, pios_ppm_id)) {
PIOS_Assert(0);
}
PIOS_BOARD_IO_Configure_PPM_RCVR(&pios_ppm_main_cfg);
}
// For some reason, PPM output on the main port doesn't work.
#if defined(PIOS_INCLUDE_PPM_OUT)
@ -359,9 +293,9 @@ void PIOS_Board_Init(void)
case OPLINKSETTINGS_FLEXIPORT_TELEMETRY:
case OPLINKSETTINGS_FLEXIPORT_SERIAL:
#ifndef PIOS_RFM22B_DEBUG_ON_TELEM
PIOS_Board_configure_com(&pios_usart_flexi_cfg,
PIOS_COM_TELEM_RX_BUF_LEN, PIOS_COM_TELEM_TX_BUF_LEN,
&pios_usart_com_driver, &pios_com_flexi_id);
PIOS_BOARD_IO_Configure_UART_COM(&pios_usart_flexi_cfg,
PIOS_COM_TELEM_RF_RX_BUF_LEN, PIOS_COM_TELEM_RF_TX_BUF_LEN,
&pios_com_flexi_id);
PIOS_COM_ChangeBaud(pios_com_flexi_id, flexiComSpeed);
#endif /* !PIOS_RFM22B_DEBUG_ON_TELEM */
break;
@ -369,12 +303,7 @@ void PIOS_Board_Init(void)
#if defined(PIOS_INCLUDE_PPM)
/* PPM input is configured on the coordinator modem and output on the remote modem. */
if (is_coordinator) {
uint32_t pios_ppm_id;
PIOS_PPM_Init(&pios_ppm_id, &pios_ppm_flexi_cfg);
if (PIOS_RCVR_Init(&pios_ppm_rcvr_id, &pios_ppm_rcvr_driver, pios_ppm_id)) {
PIOS_Assert(0);
}
PIOS_BOARD_IO_Configure_PPM_RCVR(&pios_ppm_flexi_cfg);
}
// For some reason, PPM output on the flexi port doesn't work.
#if defined(PIOS_INCLUDE_PPM_OUT)
@ -410,138 +339,11 @@ void PIOS_Board_Init(void)
PIOS_Servo_SetBankMode(1, PIOS_SERVO_BANK_MODE_PWM);
#endif
// Initialize out status object.
OPLinkStatusData oplinkStatus;
OPLinkStatusGet(&oplinkStatus);
PIOS_BOARD_IO_Configure_RFM22B();
// Get our hardware information.
const struct pios_board_info *bdinfo = &pios_board_info_blob;
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;
/* Initialize the RFM22B radio COM device. */
if (is_enabled) {
if (openlrs) {
#if defined(PIOS_INCLUDE_OPENLRS)
const struct pios_openlrs_cfg *openlrs_cfg = PIOS_BOARD_HW_DEFS_GetOpenLRSCfg(bdinfo->board_rev);
uint32_t openlrs_id;
oplinkStatus.LinkState = OPLINKSTATUS_LINKSTATE_ENABLED;
PIOS_OpenLRS_Init(&openlrs_id, PIOS_RFM22_SPI_PORT, 0, openlrs_cfg);
PIOS_OpenLRS_RegisterPPMCallback(openlrs_id, PIOS_Board_PPM_callback, 0);
#endif /* PIOS_INCLUDE_OPENLRS */
} else {
oplinkStatus.LinkState = OPLINKSTATUS_LINKSTATE_ENABLED;
// 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_pri_radio_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);
}
// Initialize the aux radio com interface
uint8_t *auxrx_buffer = (uint8_t *)pios_malloc(PIOS_COM_TELEM_RX_BUF_LEN);
uint8_t *auxtx_buffer = (uint8_t *)pios_malloc(PIOS_COM_TELEM_TX_BUF_LEN);
PIOS_Assert(auxrx_buffer);
PIOS_Assert(auxtx_buffer);
if (PIOS_COM_Init(&pios_com_aux_radio_id, &pios_rfm22b_aux_com_driver, pios_rfm22b_id,
auxrx_buffer, PIOS_COM_TELEM_RX_BUF_LEN,
auxtx_buffer, PIOS_COM_TELEM_TX_BUF_LEN)) {
PIOS_Assert(0);
}
// Set the modem (over the air) datarate.
enum rfm22b_datarate datarate = RFM22_datarate_64000;
switch (oplinkSettings.AirDataRate) {
case OPLINKSETTINGS_AIRDATARATE_9600:
datarate = RFM22_datarate_9600;
break;
case OPLINKSETTINGS_AIRDATARATE_19200:
datarate = RFM22_datarate_19200;
break;
case OPLINKSETTINGS_AIRDATARATE_32000:
datarate = RFM22_datarate_32000;
break;
case OPLINKSETTINGS_AIRDATARATE_57600:
datarate = RFM22_datarate_57600;
break;
case OPLINKSETTINGS_AIRDATARATE_64000:
datarate = RFM22_datarate_64000;
break;
case OPLINKSETTINGS_AIRDATARATE_100000:
datarate = RFM22_datarate_100000;
break;
case OPLINKSETTINGS_AIRDATARATE_128000:
datarate = RFM22_datarate_128000;
break;
case OPLINKSETTINGS_AIRDATARATE_192000:
datarate = RFM22_datarate_192000;
break;
case OPLINKSETTINGS_AIRDATARATE_256000:
datarate = RFM22_datarate_256000;
break;
}
/* 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;
}
// 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 PPM callback if we should be receiving PPM. */
if (ppm_mode || (ppm_only && !is_coordinator)) {
PIOS_RFM22B_SetPPMCallback(pios_rfm22b_id, PIOS_Board_PPM_callback, 0);
}
} // openlrs
} else {
oplinkStatus.LinkState = OPLINKSTATUS_LINKSTATE_DISABLED;
/* Set the PPM callback if we should be receiving PPM. */
if (ppm_mode || (ppm_only && !is_coordinator)) {
PIOS_RFM22B_SetPPMCallback(pios_rfm22b_id, PIOS_Board_PPM_callback, 0);
}
// Configure the primary radio stream destination.
@ -622,9 +424,6 @@ void PIOS_Board_Init(void)
break;
}
// Update the object
OPLinkStatusSet(&oplinkStatus);
/* Remap AFIO pin */
GPIO_PinRemapConfig(GPIO_Remap_SWJ_NoJTRST, ENABLE);

View File

@ -159,19 +159,26 @@ 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
//
// See also pios_board.c
// -------------------------
#define PIOS_COM_MAX_DEVS 5
#define PIOS_COM_MAX_DEVS 5
#define PIOS_COM_TELEM_USB_RX_BUF_LEN 128
#define PIOS_COM_TELEM_USB_TX_BUF_LEN 128
#define PIOS_COM_TELEM_VCP_RX_BUF_LEN 128
#define PIOS_COM_TELEM_VCP_TX_BUF_LEN 128
// The direct com ports
extern uint32_t pios_com_hid_id;
@ -191,7 +198,6 @@ extern uint32_t pios_com_pri_radio_out_id;
// The destination port for the auxiliary radio port.
extern uint32_t pios_com_aux_radio_out_id;
// The PPM IDs
extern uint32_t pios_ppm_rcvr_id;
extern uint32_t pios_ppm_out_id;
#define PIOS_COM_HID (pios_com_hid_id)
#define PIOS_COM_VCP (pios_com_vcp_id)
@ -204,7 +210,6 @@ extern uint32_t pios_ppm_out_id;
#define PIOS_COM_GCS (pios_com_gcs_id)
#define PIOS_COM_GCS_OUT (pios_com_gcs_out_id)
#define PIOS_COM_BRIDGE (pios_com_bridge_id)
#define PIOS_PPM_RECEIVER (pios_ppm_rcvr_id)
#define PIOS_PPM_OUTPUT (pios_ppm_out_id)
#define RFM22_DEBUG 1

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

@ -26,6 +26,7 @@
* 59 Temple Place, Suite 330, Boston, MA 02111-1307 USA
*/
#if defined(PIOS_INCLUDE_LED)
#include <pios_led_priv.h>
@ -463,11 +464,11 @@ static const struct pios_spi_cfg pios_spi_gyro_cfg = {
}
};
static uint32_t pios_spi_gyro_id;
uint32_t pios_spi_gyro_adapter_id;
void PIOS_SPI_gyro_irq_handler(void)
{
/* Call into the generic code to handle the IRQ for this specific device */
PIOS_SPI_IRQ_Handler(pios_spi_gyro_id);
PIOS_SPI_IRQ_Handler(pios_spi_gyro_adapter_id);
}
@ -598,11 +599,11 @@ static const struct pios_spi_cfg pios_spi_telem_flash_cfg = {
},
};
uint32_t pios_spi_telem_flash_id;
uint32_t pios_spi_telem_flash_adapter_id;
void PIOS_SPI_telem_flash_irq_handler(void)
{
/* Call into the generic code to handle the IRQ for this specific device */
PIOS_SPI_IRQ_Handler(pios_spi_telem_flash_id);
PIOS_SPI_IRQ_Handler(pios_spi_telem_flash_adapter_id);
}
@ -656,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:
@ -786,33 +787,17 @@ static const struct flashfs_logfs_cfg flashfs_internal_cfg = {
#endif /* PIOS_INCLUDE_FLASH */
#ifdef PIOS_INCLUDE_USART
#include <pios_usart_priv.h>
#ifdef PIOS_INCLUDE_COM_TELEM
/*
* MAIN USART
*/
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 = {
.rx = {
.gpio = GPIOA,
.init = {
.GPIO_Pin = GPIO_Pin_10,
@ -822,52 +807,7 @@ static const struct pios_usart_cfg pios_usart_main_cfg = {
.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 = {
.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 = {
.tx = {
.gpio = GPIOA,
.init = {
.GPIO_Pin = GPIO_Pin_9,
@ -879,118 +819,13 @@ static const struct pios_usart_cfg pios_usart_dsm_main_cfg = {
},
};
// 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 = {
.rx = {
.gpio = GPIOB,
.init = {
.GPIO_Pin = GPIO_Pin_11,
@ -1000,7 +835,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_10,
@ -1012,400 +847,11 @@ 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 */
#if defined(PIOS_INCLUDE_SRXL)
/*
* SRXL USART
*/
#include <pios_srxl_priv.h>
static const struct pios_usart_cfg pios_usart_srxl_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_OUT,
.GPIO_OType = GPIO_OType_PP,
.GPIO_PuPd = GPIO_PuPd_UP
},
},
};
#endif /* PIOS_INCLUDE_SRXL */
#if defined(PIOS_INCLUDE_HOTT)
/*
* HOTT USART
*/
#include <pios_hott_priv.h>
static const struct pios_usart_cfg pios_usart_hott_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_OUT,
.GPIO_OType = GPIO_OType_PP,
.GPIO_PuPd = GPIO_PuPd_UP
},
},
};
#endif /* PIOS_INCLUDE_HOTT */
#if defined(PIOS_INCLUDE_IBUS)
/*
* IBUS USART
*/
#include <pios_ibus_priv.h>
static const struct pios_usart_cfg pios_usart_ibus_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_OUT,
.GPIO_OType = GPIO_OType_PP,
.GPIO_PuPd = GPIO_PuPd_UP
},
},
};
static const struct pios_usart_cfg pios_usart_ibus_rcvr_cfg = {
/* FLEXI-IO (Receiver) port */
static const struct pios_usart_cfg pios_usart_flexiio_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
},
},
};
#endif /* PIOS_INCLUDE_IBUS */
#if defined(PIOS_INCLUDE_EXBUS)
/*
* EXBUS USART
*/
#include <pios_exbus_priv.h>
static const struct pios_usart_cfg pios_usart_exbus_flexi_cfg = {
.regs = USART3,
.remap = GPIO_AF_USART3,
.init = {
.USART_BaudRate = 125000,
.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_OUT,
.GPIO_OType = GPIO_OType_PP,
.GPIO_PuPd = GPIO_PuPd_UP
},
},
};
#endif /* PIOS_INCLUDE_EXBUS */
/*
* 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 = {
.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 = {
.dtr = {
// FlexIO pin 9
.gpio = GPIOC,
.init = {
@ -1416,7 +862,7 @@ static const struct pios_usart_cfg pios_usart_rcvrport_cfg = {
},
},
.tx = {
.tx = {
// * 7: PC6 = TIM8 CH1, USART6 TX
.gpio = GPIOC,
.init = {
@ -1426,10 +872,10 @@ static const struct pios_usart_cfg pios_usart_rcvrport_cfg = {
.GPIO_OType = GPIO_OType_PP,
.GPIO_PuPd = GPIO_PuPd_UP
},
.pin_source = GPIO_PinSource6,
.pin_source = GPIO_PinSource6,
},
.rx = {
.rx = {
// * 8: PC7 = TIM8 CH2, USART6 RX
.gpio = GPIOC,
.init = {
@ -1439,9 +885,10 @@ static const struct pios_usart_cfg pios_usart_rcvrport_cfg = {
.GPIO_OType = GPIO_OType_PP,
.GPIO_PuPd = GPIO_PuPd_UP
},
.pin_source = GPIO_PinSource7,
.pin_source = GPIO_PinSource7,
}
};
#endif /* PIOS_INCLUDE_USART */
#if defined(PIOS_INCLUDE_COM)
@ -1797,212 +1244,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
@ -2060,102 +1319,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 = {
@ -2271,51 +1440,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 */
#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>
#include <hwsettings.h>
@ -2450,3 +1576,203 @@ 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,
};
const struct pios_hmc5x83_cfg *PIOS_BOARD_HW_DEFS_GetInternalHMC5x83Cfg(__attribute__((unused)) uint32_t board_revision)
{
return &pios_hmc5x83_internal_cfg;
}
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_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 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_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
.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_180DEG,
.fast_prescaler = PIOS_SPI_PRESCALER_4,
.std_prescaler = PIOS_SPI_PRESCALER_64,
.max_downsample = 20,
};
const struct pios_mpu6000_cfg *PIOS_BOARD_HW_DEFS_GetMPU6000Cfg(__attribute__((unused)) uint32_t board_revision)
{
return &pios_mpu6000_cfg;
}
#endif /* PIOS_INCLUDE_MPU6000 */

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

@ -25,6 +25,15 @@
#include <pios.h>
#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.
@ -39,6 +48,7 @@
uint32_t pios_com_telem_usb_id;
static bool board_init_complete = false;
void PIOS_Board_Init()
{
if (board_init_complete) {
@ -68,7 +78,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

@ -86,6 +86,7 @@
#define PIOS_MPU6000_ACCEL
/* #define PIOS_INCLUDE_HMC5843 */
#define PIOS_INCLUDE_HMC5X83
#define PIOS_INCLUDE_HMC5X83_INTERNAL
#define PIOS_HMC5X83_HAS_GPIOS
/* #define PIOS_INCLUDE_BMP085 */
#define PIOS_INCLUDE_MS5611

View File

@ -30,21 +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 <pios_openlrs.h>
#include <pios_openlrs_rcvr_priv.h>
#include <taskinfo.h>
#include <pios_ws2811.h>
#include <auxmagsettings.h>
#ifdef PIOS_INCLUDE_INSTRUMENTATION
#include <pios_instrumentation.h>
#endif
#include <pios_board_io.h>
#include <pios_board_sensors.h>
/*
* Pull in the board-specific static HW definitions.
* Including .c files is a bit ugly but this allows all of
@ -55,354 +50,59 @@
*/
#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_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
};
#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 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
.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_180DEG,
.fast_prescaler = PIOS_SPI_PRESCALER_4,
.std_prescaler = PIOS_SPI_PRESCALER_64,
.max_downsample = 20,
};
#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_HOTT_RX_BUF_LEN 512
#define PIOS_COM_HOTT_TX_BUF_LEN 512
#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
#define PIOS_COM_MAVLINK_RX_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_rf_id = 0;
uint32_t pios_com_bridge_id = 0;
uint32_t pios_com_hott_id = 0;
uint32_t pios_com_overo_id = 0;
uint32_t pios_com_hkosd_id = 0;
uint32_t pios_com_vcp_id = 0;
uint32_t pios_com_msp_id = 0;
uint32_t pios_com_mavlink_id = 0;
#if defined(PIOS_INCLUDE_RFM22B)
uint32_t pios_rfm22b_id = 0;
#include <pios_rfm22b_com.h>
#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)
{
uint32_t pios_usart_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,
};
if (PIOS_USART_Init(&pios_usart_id, usart_port_cfg)) {
PIOS_Assert(0);
}
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,
};
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_ibus(const struct pios_usart_cfg *usart_cfg)
{
uint32_t pios_usart_ibus_id;
if (PIOS_USART_Init(&pios_usart_ibus_id, usart_cfg)) {
PIOS_Assert(0);
}
uint32_t pios_ibus_id;
if (PIOS_IBUS_Init(&pios_ibus_id, &pios_usart_com_driver, pios_usart_ibus_id)) {
PIOS_Assert(0);
}
uint32_t pios_ibus_rcvr_id;
if (PIOS_RCVR_Init(&pios_ibus_rcvr_id, &pios_ibus_rcvr_driver, pios_ibus_id)) {
PIOS_Assert(0);
}
pios_rcvr_group_map[MANUALCONTROLSETTINGS_CHANNELGROUPS_IBUS] = pios_ibus_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;
}
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,
};
/**
* PIOS_Board_Init()
* initializes all the core subsystems on this specific hardware
* called from System/openpilot.c
*/
#include <pios_board_info.h>
void PIOS_Board_Init(void)
{
const struct pios_board_info *bdinfo = &pios_board_info_blob;
@ -418,12 +118,12 @@ void PIOS_Board_Init(void)
#endif
/* Set up the SPI interface to the gyro/acelerometer */
if (PIOS_SPI_Init(&pios_spi_gyro_id, &pios_spi_gyro_cfg)) {
if (PIOS_SPI_Init(&pios_spi_gyro_adapter_id, &pios_spi_gyro_cfg)) {
PIOS_DEBUG_Assert(0);
}
/* Set up the SPI interface to the flash and rfm22b */
if (PIOS_SPI_Init(&pios_spi_telem_flash_id, &pios_spi_telem_flash_cfg)) {
if (PIOS_SPI_Init(&pios_spi_telem_flash_adapter_id, &pios_spi_telem_flash_cfg)) {
PIOS_DEBUG_Assert(0);
}
@ -432,7 +132,7 @@ void PIOS_Board_Init(void)
uintptr_t flash_id;
// Initialize the external USER flash
if (PIOS_Flash_Jedec_Init(&flash_id, pios_spi_telem_flash_id, 1)) {
if (PIOS_Flash_Jedec_Init(&flash_id, pios_spi_telem_flash_adapter_id, 1)) {
PIOS_DEBUG_Assert(0);
}
@ -473,10 +173,6 @@ void PIOS_Board_Init(void)
EventDispatcherInitialize();
UAVObjInitialize();
HwSettingsInitialize();
#if defined(PIOS_INCLUDE_RFM22B)
OPLinkSettingsInitialize();
OPLinkStatusInitialize();
#endif /* PIOS_INCLUDE_RFM22B */
/* Initialize the alarms library */
AlarmsInitialize();
@ -503,537 +199,57 @@ void PIOS_Board_Init(void)
}
/* Configure IO ports */
uint8_t hwsettings_DSMxBind;
HwSettingsDSMxBindGet(&hwsettings_DSMxBind);
/* 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;
PIOS_DELAY_WaitmS(50);
}
#endif
case HWSETTINGS_RM_FLEXIPORT_SRXL:
#if defined(PIOS_INCLUDE_SRXL)
{
uint32_t pios_usart_srxl_id;
if (PIOS_USART_Init(&pios_usart_srxl_id, &pios_usart_srxl_flexi_cfg)) {
PIOS_Assert(0);
}
uint32_t pios_srxl_id;
if (PIOS_SRXL_Init(&pios_srxl_id, &pios_usart_com_driver, pios_usart_srxl_id)) {
PIOS_Assert(0);
}
uint32_t pios_srxl_rcvr_id;
if (PIOS_RCVR_Init(&pios_srxl_rcvr_id, &pios_srxl_rcvr_driver, pios_srxl_id)) {
PIOS_Assert(0);
}
pios_rcvr_group_map[MANUALCONTROLSETTINGS_CHANNELGROUPS_SRXL] = pios_srxl_rcvr_id;
}
#endif /* PIOS_INCLUDE_SRXL */
break;
case HWSETTINGS_RM_FLEXIPORT_IBUS:
#if defined(PIOS_INCLUDE_IBUS)
PIOS_Board_configure_ibus(&pios_usart_ibus_flexi_cfg);
#endif /* PIOS_INCLUDE_IBUS */
break;
case HWSETTINGS_RM_FLEXIPORT_HOTTSUMD:
case HWSETTINGS_RM_FLEXIPORT_HOTTSUMH:
#if defined(PIOS_INCLUDE_HOTT)
{
uint32_t pios_usart_hott_id;
if (PIOS_USART_Init(&pios_usart_hott_id, &pios_usart_hott_flexi_cfg)) {
PIOS_Assert(0);
}
uint32_t pios_hott_id;
if (PIOS_HOTT_Init(&pios_hott_id, &pios_usart_com_driver, pios_usart_hott_id,
hwsettings_flexiport == HWSETTINGS_RM_FLEXIPORT_HOTTSUMD ? PIOS_HOTT_PROTO_SUMD : PIOS_HOTT_PROTO_SUMH)) {
PIOS_Assert(0);
}
uint32_t pios_hott_rcvr_id;
if (PIOS_RCVR_Init(&pios_hott_rcvr_id, &pios_hott_rcvr_driver, pios_hott_id)) {
PIOS_Assert(0);
}
pios_rcvr_group_map[MANUALCONTROLSETTINGS_CHANNELGROUPS_HOTT] = pios_hott_rcvr_id;
}
#endif /* PIOS_INCLUDE_HOTT */
break;
case HWSETTINGS_RM_FLEXIPORT_HOTTTELEMETRY:
PIOS_Board_configure_com(&pios_usart_hott_flexi_cfg, PIOS_COM_HOTT_RX_BUF_LEN, PIOS_COM_HOTT_TX_BUF_LEN, &pios_usart_com_driver, &pios_com_hott_id);
break;
case HWSETTINGS_RM_FLEXIPORT_EXBUS:
#if defined(PIOS_INCLUDE_EXBUS)
{
uint32_t pios_usart_exbus_id;
if (PIOS_USART_Init(&pios_usart_exbus_id, &pios_usart_exbus_flexi_cfg)) {
PIOS_Assert(0);
}
uint32_t pios_exbus_id;
if (PIOS_EXBUS_Init(&pios_exbus_id, &pios_usart_com_driver, pios_usart_exbus_id)) {
PIOS_Assert(0);
}
uint32_t pios_exbus_rcvr_id;
if (PIOS_RCVR_Init(&pios_exbus_rcvr_id, &pios_exbus_rcvr_driver, pios_exbus_id)) {
PIOS_Assert(0);
}
pios_rcvr_group_map[MANUALCONTROLSETTINGS_CHANNELGROUPS_EXBUS] = pios_exbus_rcvr_id;
}
#endif /* PIOS_INCLUDE_EXBUS */
break;
} /* hwsettings_rm_flexiport */
/* Moved this here to allow binding on flexiport */
/* Moved this here to allow DSM binding on flexiport */
#if defined(PIOS_INCLUDE_FLASH)
if (PIOS_FLASHFS_Logfs_Init(&pios_user_fs_id, &flashfs_external_user_cfg, &pios_jedec_flash_driver, flash_id)) {
PIOS_DEBUG_Assert(0);
}
#endif /* if defined(PIOS_INCLUDE_FLASH) */
#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_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 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_HOTTTELEMETRY:
PIOS_Board_configure_com(&pios_usart_main_cfg, PIOS_COM_HOTT_RX_BUF_LEN, PIOS_COM_HOTT_TX_BUF_LEN, &pios_usart_com_driver, &pios_com_hott_id);
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);
if (hwsettings_mainport < NELEMENTS(main_function_map)) {
PIOS_BOARD_IO_Configure_UART(&pios_usart_main_cfg, main_function_map[hwsettings_mainport]);
}
/* Initialize the RFM22B radio COM device. */
#if defined(PIOS_INCLUDE_RFM22B)
PIOS_BOARD_IO_Configure_RFM22B();
/* Fetch the OPLinkSettings object. */
OPLinkSettingsData oplinkSettings;
OPLinkSettingsGet(&oplinkSettings);
uint8_t hwsettings_radioaux;
HwSettingsRadioAuxStreamGet(&hwsettings_radioaux);
// 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.Protocol == OPLINKSETTINGS_PROTOCOL_OPLINKCOORDINATOR);
bool openlrs = (oplinkSettings.Protocol == OPLINKSETTINGS_PROTOCOL_OPENLRS);
bool data_mode = ((oplinkSettings.LinkType == OPLINKSETTINGS_LINKTYPE_DATA) ||
(oplinkSettings.LinkType == OPLINKSETTINGS_LINKTYPE_DATAANDCONTROL));
bool ppm_mode = ((oplinkSettings.LinkType == OPLINKSETTINGS_LINKTYPE_CONTROL) ||
(oplinkSettings.LinkType == OPLINKSETTINGS_LINKTYPE_DATAANDCONTROL));
bool is_enabled = ((oplinkSettings.Protocol != OPLINKSETTINGS_PROTOCOL_DISABLED) &&
((oplinkSettings.MaxRFPower != OPLINKSETTINGS_MAXRFPOWER_0) || openlrs));
if (is_enabled) {
if (openlrs) {
#if defined(PIOS_INCLUDE_OPENLRS_RCVR)
const struct pios_openlrs_cfg *openlrs_cfg = PIOS_BOARD_HW_DEFS_GetOpenLRSCfg(bdinfo->board_rev);
uint32_t openlrs_id;
PIOS_OpenLRS_Init(&openlrs_id, PIOS_RFM22_SPI_PORT, 0, openlrs_cfg);
{
uint32_t openlrsrcvr_id;
PIOS_OpenLRS_Rcvr_Init(&openlrsrcvr_id, openlrs_id);
uint32_t openlrsrcvr_rcvr_id;
if (PIOS_RCVR_Init(&openlrsrcvr_rcvr_id, &pios_openlrs_rcvr_driver, openlrsrcvr_id)) {
PIOS_Assert(0);
}
pios_rcvr_group_map[MANUALCONTROLSETTINGS_CHANNELGROUPS_OPENLRS] = openlrsrcvr_rcvr_id;
}
#endif /* PIOS_INCLUDE_OPENLRS_RCVR */
} else {
/* 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_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 modem (over the air) datarate.
enum rfm22b_datarate datarate = RFM22_datarate_64000;
switch (oplinkSettings.AirDataRate) {
case OPLINKSETTINGS_AIRDATARATE_9600:
datarate = RFM22_datarate_9600;
break;
case OPLINKSETTINGS_AIRDATARATE_19200:
datarate = RFM22_datarate_19200;
break;
case OPLINKSETTINGS_AIRDATARATE_32000:
datarate = RFM22_datarate_32000;
break;
case OPLINKSETTINGS_AIRDATARATE_57600:
datarate = RFM22_datarate_57600;
break;
case OPLINKSETTINGS_AIRDATARATE_64000:
datarate = RFM22_datarate_64000;
break;
case OPLINKSETTINGS_AIRDATARATE_100000:
datarate = RFM22_datarate_100000;
break;
case OPLINKSETTINGS_AIRDATARATE_128000:
datarate = RFM22_datarate_128000;
break;
case OPLINKSETTINGS_AIRDATARATE_192000:
datarate = RFM22_datarate_192000;
break;
case OPLINKSETTINGS_AIRDATARATE_256000:
datarate = RFM22_datarate_256000;
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);
uint8_t hwsettings_radioaux;
HwSettingsRadioAuxStreamGet(&hwsettings_radioaux);
// TODO: this is in preparation for full mavlink support and is used by LP-368
uint16_t mavlink_rx_size = PIOS_COM_MAVLINK_RX_BUF_LEN;
switch (hwsettings_radioaux) {
case HWSETTINGS_RADIOAUXSTREAM_DEBUGCONSOLE:
case HWSETTINGS_RADIOAUXSTREAM_DISABLED:
break;
case HWSETTINGS_RADIOAUXSTREAM_MAVLINK:
{
uint8_t *auxrx_buffer = 0;
if (mavlink_rx_size) {
auxrx_buffer = (uint8_t *)pios_malloc(mavlink_rx_size);
}
uint8_t *auxtx_buffer = (uint8_t *)pios_malloc(PIOS_COM_MAVLINK_TX_BUF_LEN);
PIOS_Assert(auxrx_buffer);
PIOS_Assert(auxtx_buffer);
if (PIOS_COM_Init(&pios_com_mavlink_id, &pios_rfm22b_aux_com_driver, pios_rfm22b_id,
auxrx_buffer, mavlink_rx_size,
auxtx_buffer, PIOS_COM_BRIDGE_TX_BUF_LEN)) {
PIOS_Assert(0);
}
}
}
}
} else {
oplinkStatus.LinkState = OPLINKSTATUS_LINKSTATE_DISABLED;
}
OPLinkStatusSet(&oplinkStatus);
PIOS_BOARD_IO_Configure_RadioAuxStream(hwsettings_radioaux);
#endif /* PIOS_INCLUDE_RFM22B */
#if defined(PIOS_INCLUDE_PWM) || defined(PIOS_INCLUDE_PPM)
@ -1046,12 +262,16 @@ void PIOS_Board_Init(void)
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_PWM:
#if defined(PIOS_INCLUDE_PWM)
/* Set up the receiver port. Later this should be optional */
PIOS_Board_configure_pwm(&pios_pwm_cfg);
PIOS_BOARD_IO_Configure_PWM_RCVR(&pios_pwm_cfg);
#endif /* PIOS_INCLUDE_PWM */
break;
case HWSETTINGS_RM_RCVRPORT_PPM:
@ -1065,7 +285,7 @@ void PIOS_Board_Init(void)
case HWSETTINGS_RM_RCVRPORT_PPMGPS:
case HWSETTINGS_RM_RCVRPORT_PPMHOTTTELEMETRY:
#if defined(PIOS_INCLUDE_PPM)
PIOS_Board_configure_ppm(&pios_ppm_cfg);
PIOS_BOARD_IO_Configure_PPM_RCVR(&pios_ppm_cfg);
if (hwsettings_rcvrport == HWSETTINGS_RM_RCVRPORT_PPMOUTPUTS) {
// configure servo outputs and the remaining 5 inputs as outputs
@ -1074,7 +294,7 @@ void PIOS_Board_Init(void)
// enable pwm on the remaining channels
if (hwsettings_rcvrport == HWSETTINGS_RM_RCVRPORT_PPMPWM) {
PIOS_Board_configure_pwm(&pios_pwm_ppm_cfg);
PIOS_BOARD_IO_Configure_PWM_RCVR(&pios_pwm_ppm_cfg);
}
break;
@ -1084,69 +304,9 @@ void PIOS_Board_Init(void)
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;
case HWSETTINGS_RM_RCVRPORT_HOTTTELEMETRY:
case HWSETTINGS_RM_RCVRPORT_PPMHOTTTELEMETRY:
PIOS_Board_configure_com(&pios_usart_rcvrport_cfg, PIOS_COM_HOTT_RX_BUF_LEN, PIOS_COM_HOTT_TX_BUF_LEN, &pios_usart_com_driver, &pios_com_hott_id);
break;
case HWSETTINGS_RM_RCVRPORT_IBUS:
#if defined(PIOS_INCLUDE_IBUS)
PIOS_Board_configure_ibus(&pios_usart_ibus_rcvr_cfg);
#endif /* PIOS_INCLUDE_IBUS */
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_GCS_RCVR();
#endif
#ifndef PIOS_ENABLE_DEBUG_PINS
// pios_servo_cfg points to the correct configuration based on input port settings
@ -1155,6 +315,18 @@ void PIOS_Board_Init(void)
PIOS_DEBUG_Init(pios_tim_servoport_all_pins, NELEMENTS(pios_tim_servoport_all_pins));
#endif
PIOS_BOARD_Sensors_Configure();
#ifdef PIOS_INCLUDE_WS2811
HwSettingsWS2811LED_OutOptions ws2811_pin_settings;
HwSettingsWS2811LED_OutGet(&ws2811_pin_settings);
if (ws2811_pin_settings != HWSETTINGS_WS2811LED_OUT_DISABLED && ws2811_pin_settings < NELEMENTS(pios_ws2811_pin_cfg)) {
PIOS_WS2811_Init(&pios_ws2811_cfg, &pios_ws2811_pin_cfg[ws2811_pin_settings]);
}
#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,
@ -1164,67 +336,6 @@ 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
#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_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);
PIOS_MS5611_Register();
#endif
#ifdef PIOS_INCLUDE_WS2811
#include <pios_ws2811.h>
HwSettingsWS2811LED_OutOptions ws2811_pin_settings;
HwSettingsWS2811LED_OutGet(&ws2811_pin_settings);
if (ws2811_pin_settings != HWSETTINGS_WS2811LED_OUT_DISABLED && ws2811_pin_settings < NELEMENTS(pios_ws2811_pin_cfg)) {
PIOS_WS2811_Init(&pios_ws2811_cfg, &pios_ws2811_pin_cfg[ws2811_pin_settings]);
}
#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);
}
}
}
#endif // PIOS_INCLUDE_ADC
DEBUG_PRINTF(2, "Board complete\r\n");

View File

@ -103,76 +103,56 @@
// 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_adapter_id;
#define PIOS_SPI_MPU6000_ADAPTER (pios_spi_gyro_adapter_id)
extern uint32_t pios_spi_telem_flash_adapter_id;
#define PIOS_SPI_RFM22B_ADAPTER (pios_spi_telem_flash_adapter_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_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
// ------------------------
// 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_pressure_adapter_id;
#define PIOS_I2C_MAIN_ADAPTER (pios_i2c_mag_pressure_adapter_id)
#define PIOS_I2C_HMC5X83_INTERNAL_ADAPTER (pios_i2c_mag_pressure_adapter_id)
#define PIOS_I2C_MS5611_INTERNAL_ADAPTER (pios_i2c_mag_pressure_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_MS4525DO_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_MS4525DO_ADAPTER (PIOS_I2C_FLEXI_ADAPTER)
#define PIOS_I2C_EXTERNAL_ADAPTER (PIOS_I2C_FLEXI_ADAPTER)
// -------------------------
// PIOS_USART
//
// See also pios_board.c
// -------------------------
#define PIOS_USART_MAX_DEVS 5
#define PIOS_USART_MAX_DEVS 5
#define PIOS_USART_INVERTER_PORT USART1
#define PIOS_USART_INVERTER_GPIO GPIOC
#define PIOS_USART_INVERTER_PIN GPIO_Pin_0
#define PIOS_USART_INVERTER_ENABLE Bit_SET
#define PIOS_USART_INVERTER_DISABLE Bit_RESET
// -------------------------
// PIOS_COM
//
// See also pios_board.c
// -------------------------
#define PIOS_COM_MAX_DEVS 4
extern uint32_t pios_com_telem_rf_id;
extern uint32_t pios_com_rf_id;
extern uint32_t pios_com_gps_id;
extern uint32_t pios_com_telem_usb_id;
extern uint32_t pios_com_bridge_id;
extern uint32_t pios_com_hott_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_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_RF (pios_com_rf_id)
#define PIOS_COM_BRIDGE (pios_com_bridge_id)
#define PIOS_COM_HOTT (pios_com_hott_id)
#define PIOS_COM_VCP (pios_com_vcp_id)
#define PIOS_COM_OSDHK (pios_com_hkosd_id)
#define PIOS_COM_MSP (pios_com_msp_id)
#define PIOS_COM_MAVLINK (pios_com_mavlink_id)
#if defined(PIOS_INCLUDE_DEBUG_CONSOLE)
extern uint32_t pios_com_debug_id;
#define PIOS_COM_DEBUG (pios_com_debug_id)
#endif /* PIOS_INCLUDE_DEBUG_CONSOLE */
#if defined(PIOS_INCLUDE_RFM22B)
extern uint32_t pios_rfm22b_id;
extern uint32_t pios_spi_telem_flash_id;
#define PIOS_RFM22_SPI_PORT (pios_spi_telem_flash_id)
#endif /* PIOS_INCLUDE_RFM22B */
#define PIOS_COM_MAX_DEVS 4
// -------------------------
// Packet Handler

View File

@ -42,29 +42,24 @@
* o5 | PA0 | TIM5_CH1 | ADC1_0
* o6 | PA1 | TIM5_CH2 | ADC1_1
*/
#define MAIN_USART_REGS USART2
#define MAIN_USART_REMAP GPIO_AF_USART2
#define MAIN_USART_IRQ USART2_IRQn
#define MAIN_USART_RX_GPIO GPIOA
#define MAIN_USART_RX_PIN GPIO_Pin_3
#define MAIN_USART_TX_GPIO GPIOA
#define MAIN_USART_TX_PIN GPIO_Pin_2
// Inverter for SBUS handling
#define MAIN_USART_INVERTER_GPIO GPIOC
#define MAIN_USART_INVERTER_PIN GPIO_Pin_15
#define MAIN_USART_INVERTER_CLOCK_FUNC RCC_AHB1PeriphClockCmd
#define MAIN_USART_INVERTER_CLOCK_PERIPH RCC_AHB1Periph_GPIOC
#define MAIN_USART_REGS USART2
#define MAIN_USART_REMAP GPIO_AF_USART2
#define MAIN_USART_IRQ USART2_IRQn
#define MAIN_USART_RX_GPIO GPIOA
#define MAIN_USART_RX_PIN GPIO_Pin_3
#define MAIN_USART_TX_GPIO GPIOA
#define MAIN_USART_TX_PIN GPIO_Pin_2
#define FLEXI_USART_REGS USART1
#define FLEXI_USART_REMAP GPIO_AF_USART1
#define FLEXI_USART_IRQ USART1_IRQn
#define FLEXI_USART_RX_GPIO GPIOB
#define FLEXI_USART_RX_PIN GPIO_Pin_7
#define FLEXI_USART_TX_GPIO GPIOB
#define FLEXI_USART_TX_PIN GPIO_Pin_6
#define FLEXI_USART_REGS USART1
#define FLEXI_USART_REMAP GPIO_AF_USART1
#define FLEXI_USART_IRQ USART1_IRQn
#define FLEXI_USART_RX_GPIO GPIOB
#define FLEXI_USART_RX_PIN GPIO_Pin_7
#define FLEXI_USART_TX_GPIO GPIOB
#define FLEXI_USART_TX_PIN GPIO_Pin_6
// ReceiverPort pin 3
#define FLEXI_USART_DTR_GPIO GPIOB
#define FLEXI_USART_DTR_PIN GPIO_Pin_10
#define FLEXI_USART_DTR_GPIO GPIOB
#define FLEXI_USART_DTR_PIN GPIO_Pin_10
#if defined(PIOS_INCLUDE_LED)
@ -115,8 +110,8 @@ const struct pios_gpio_cfg *PIOS_BOARD_HW_DEFS_GetLedCfg(__attribute__((unused))
#include <pios_spi_priv.h>
/*
* SPI1 Interface
* Used for MPU6000 gyro and accelerometer
* SPI2 Interface
* Used for MPU9250 gyro and accelerometer
*/
void PIOS_SPI_gyro_irq_handler(void);
void DMA1_Stream3_IRQHandler(void) __attribute__((alias("PIOS_SPI_gyro_irq_handler")));
@ -229,42 +224,26 @@ static const struct pios_spi_cfg pios_spi_gyro_cfg = {
}
};
static uint32_t pios_spi_gyro_id;
uint32_t pios_spi_gyro_adapter_id;
void PIOS_SPI_gyro_irq_handler(void)
{
/* Call into the generic code to handle the IRQ for this specific device */
PIOS_SPI_IRQ_Handler(pios_spi_gyro_id);
PIOS_SPI_IRQ_Handler(pios_spi_gyro_adapter_id);
}
#endif /* PIOS_INCLUDE_SPI */
#ifdef PIOS_INCLUDE_USART
#include <pios_usart_priv.h>
#ifdef PIOS_INCLUDE_COM_TELEM
/*
* MAIN USART
*/
static const struct pios_usart_cfg pios_usart_main_cfg = {
.regs = MAIN_USART_REGS,
.remap = MAIN_USART_REMAP,
.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 = MAIN_USART_IRQ,
.NVIC_IRQChannelPreemptionPriority = PIOS_IRQ_PRIO_MID,
.NVIC_IRQChannelSubPriority = 0,
.NVIC_IRQChannelCmd = ENABLE,
},
},
.rx = {
.rx = {
.gpio = MAIN_USART_RX_GPIO,
.init = {
.GPIO_Pin = MAIN_USART_RX_PIN,
@ -274,52 +253,7 @@ static const struct pios_usart_cfg pios_usart_main_cfg = {
.GPIO_PuPd = GPIO_PuPd_UP
},
},
.tx = {
.gpio = MAIN_USART_TX_GPIO,
.init = {
.GPIO_Pin = MAIN_USART_TX_PIN,
.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 = MAIN_USART_REGS,
.remap = MAIN_USART_REMAP,
.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 = MAIN_USART_IRQ,
.NVIC_IRQChannelPreemptionPriority = PIOS_IRQ_PRIO_HIGH,
.NVIC_IRQChannelSubPriority = 0,
.NVIC_IRQChannelCmd = ENABLE,
},
},
.rx = {
.gpio = MAIN_USART_RX_GPIO,
.init = {
.GPIO_Pin = MAIN_USART_RX_PIN,
.GPIO_Speed = GPIO_Speed_2MHz,
.GPIO_Mode = GPIO_Mode_AF,
.GPIO_OType = GPIO_OType_PP,
.GPIO_PuPd = GPIO_PuPd_UP
},
},
.tx = {
.tx = {
.gpio = MAIN_USART_TX_GPIO,
.init = {
.GPIO_Pin = MAIN_USART_TX_PIN,
@ -331,120 +265,13 @@ static const struct pios_usart_cfg pios_usart_dsm_main_cfg = {
},
};
// 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 = MAIN_USART_RX_GPIO,
.init = {
.GPIO_Pin = MAIN_USART_RX_PIN,
.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 = MAIN_USART_REGS,
.remap = MAIN_USART_REMAP,
.init = {
.USART_BaudRate = 99999,
.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 = MAIN_USART_IRQ,
.NVIC_IRQChannelPreemptionPriority = PIOS_IRQ_PRIO_HIGH,
.NVIC_IRQChannelSubPriority = 0,
.NVIC_IRQChannelCmd = ENABLE,
},
},
.rx = {
.gpio = MAIN_USART_RX_GPIO,
.init = {
.GPIO_Pin = MAIN_USART_RX_PIN,
.GPIO_Speed = GPIO_Speed_2MHz,
.GPIO_Mode = GPIO_Mode_AF,
.GPIO_OType = GPIO_OType_PP,
.GPIO_PuPd = GPIO_PuPd_UP
},
},
.tx = {
.gpio = MAIN_USART_TX_GPIO,
.init = {
.GPIO_Pin = MAIN_USART_TX_PIN,
.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 = MAIN_USART_INVERTER_GPIO,
.init = {
.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_inv_enable = Bit_SET,
.gpio_inv_disable = Bit_RESET,
.gpio_clk_func = MAIN_USART_INVERTER_CLOCK_FUNC,
.gpio_clk_periph = MAIN_USART_INVERTER_CLOCK_PERIPH,
};
#ifdef PIOS_INCLUDE_COM_FLEXI
/*
* FLEXI PORT
*/
static const struct pios_usart_cfg pios_usart_flexi_cfg = {
.regs = FLEXI_USART_REGS,
.remap = FLEXI_USART_REMAP,
.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 = FLEXI_USART_IRQ,
.NVIC_IRQChannelPreemptionPriority = PIOS_IRQ_PRIO_MID,
.NVIC_IRQChannelSubPriority = 0,
.NVIC_IRQChannelCmd = ENABLE,
},
},
.rx = {
.rx = {
.gpio = FLEXI_USART_RX_GPIO,
.init = {
.GPIO_Pin = FLEXI_USART_RX_PIN,
@ -454,358 +281,7 @@ static const struct pios_usart_cfg pios_usart_flexi_cfg = {
.GPIO_PuPd = GPIO_PuPd_UP
},
},
.tx = {
.gpio = FLEXI_USART_TX_GPIO,
.init = {
.GPIO_Pin = FLEXI_USART_TX_PIN,
.GPIO_Speed = GPIO_Speed_2MHz,
.GPIO_Mode = GPIO_Mode_AF,
.GPIO_OType = GPIO_OType_PP,
.GPIO_PuPd = GPIO_PuPd_UP
},
},
.dtr = {
.gpio = FLEXI_USART_DTR_GPIO,
.init = {
.GPIO_Pin = FLEXI_USART_DTR_PIN,
.GPIO_Speed = GPIO_Speed_25MHz,
.GPIO_Mode = GPIO_Mode_OUT,
.GPIO_OType = GPIO_OType_PP,
},
},
};
#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 = FLEXI_USART_REGS,
.remap = FLEXI_USART_REMAP,
.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 = FLEXI_USART_IRQ,
.NVIC_IRQChannelPreemptionPriority = PIOS_IRQ_PRIO_HIGH,
.NVIC_IRQChannelSubPriority = 0,
.NVIC_IRQChannelCmd = ENABLE,
},
},
.rx = {
.gpio = FLEXI_USART_RX_GPIO,
.init = {
.GPIO_Pin = FLEXI_USART_RX_PIN,
.GPIO_Speed = GPIO_Speed_2MHz,
.GPIO_Mode = GPIO_Mode_AF,
.GPIO_OType = GPIO_OType_PP,
.GPIO_PuPd = GPIO_PuPd_UP
},
},
.tx = {
.gpio = FLEXI_USART_TX_GPIO,
.init = {
.GPIO_Pin = FLEXI_USART_TX_PIN,
.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 = FLEXI_USART_RX_GPIO,
.init = {
.GPIO_Pin = FLEXI_USART_RX_PIN,
.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_HOTT)
/*
* HOTT USART
*/
#include <pios_hott_priv.h>
static const struct pios_usart_cfg pios_usart_hott_flexi_cfg = {
.regs = FLEXI_USART_REGS,
.remap = FLEXI_USART_REMAP,
.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 = FLEXI_USART_IRQ,
.NVIC_IRQChannelPreemptionPriority = PIOS_IRQ_PRIO_HIGH,
.NVIC_IRQChannelSubPriority = 0,
.NVIC_IRQChannelCmd = ENABLE,
},
},
.rx = {
.gpio = FLEXI_USART_RX_GPIO,
.init = {
.GPIO_Pin = FLEXI_USART_RX_PIN,
.GPIO_Speed = GPIO_Speed_2MHz,
.GPIO_Mode = GPIO_Mode_AF,
.GPIO_OType = GPIO_OType_PP,
.GPIO_PuPd = GPIO_PuPd_UP
},
},
.tx = {
.gpio = FLEXI_USART_TX_GPIO,
.init = {
.GPIO_Pin = FLEXI_USART_TX_PIN,
.GPIO_Speed = GPIO_Speed_2MHz,
.GPIO_Mode = GPIO_Mode_OUT,
.GPIO_OType = GPIO_OType_PP,
.GPIO_PuPd = GPIO_PuPd_UP
},
},
};
#endif /* PIOS_INCLUDE_HOTT */
#if defined(PIOS_INCLUDE_SRXL)
/*
* SRXL USART
*/
#include <pios_srxl_priv.h>
static const struct pios_usart_cfg pios_usart_srxl_flexi_cfg = {
.regs = FLEXI_USART_REGS,
.remap = FLEXI_USART_REMAP,
.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 = FLEXI_USART_IRQ,
.NVIC_IRQChannelPreemptionPriority = PIOS_IRQ_PRIO_HIGH,
.NVIC_IRQChannelSubPriority = 0,
.NVIC_IRQChannelCmd = ENABLE,
},
},
.rx = {
.gpio = FLEXI_USART_RX_GPIO,
.init = {
.GPIO_Pin = FLEXI_USART_RX_PIN,
.GPIO_Speed = GPIO_Speed_2MHz,
.GPIO_Mode = GPIO_Mode_AF,
.GPIO_OType = GPIO_OType_PP,
.GPIO_PuPd = GPIO_PuPd_UP
},
},
.tx = {
.gpio = FLEXI_USART_TX_GPIO,
.init = {
.GPIO_Pin = FLEXI_USART_TX_PIN,
.GPIO_Speed = GPIO_Speed_2MHz,
.GPIO_Mode = GPIO_Mode_OUT,
.GPIO_OType = GPIO_OType_PP,
.GPIO_PuPd = GPIO_PuPd_UP
},
},
};
#endif /* PIOS_INCLUDE_SRXL */
#if defined(PIOS_INCLUDE_IBUS)
/*
* IBUS USART
*/
#include <pios_ibus_priv.h>
static const struct pios_usart_cfg pios_usart_ibus_flexi_cfg = {
.regs = FLEXI_USART_REGS,
.remap = FLEXI_USART_REMAP,
.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 = FLEXI_USART_IRQ,
.NVIC_IRQChannelPreemptionPriority = PIOS_IRQ_PRIO_HIGH,
.NVIC_IRQChannelSubPriority = 0,
.NVIC_IRQChannelCmd = ENABLE,
},
},
.rx = {
.gpio = FLEXI_USART_RX_GPIO,
.init = {
.GPIO_Pin = FLEXI_USART_RX_PIN,
.GPIO_Speed = GPIO_Speed_2MHz,
.GPIO_Mode = GPIO_Mode_AF,
.GPIO_OType = GPIO_OType_PP,
.GPIO_PuPd = GPIO_PuPd_UP
},
},
.tx = {
.gpio = FLEXI_USART_TX_GPIO,
.init = {
.GPIO_Pin = FLEXI_USART_TX_PIN,
.GPIO_Speed = GPIO_Speed_2MHz,
.GPIO_Mode = GPIO_Mode_OUT,
.GPIO_OType = GPIO_OType_PP,
.GPIO_PuPd = GPIO_PuPd_UP
},
},
};
#endif /* PIOS_INCLUDE_IBUS */
#if defined(PIOS_INCLUDE_EXBUS)
/*
* EXBUS USART
*/
#include <pios_exbus_priv.h>
static const struct pios_usart_cfg pios_usart_exbus_flexi_cfg = {
.regs = FLEXI_USART_REGS,
.remap = FLEXI_USART_REMAP,
.init = {
.USART_BaudRate = 125000,
.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 = FLEXI_USART_IRQ,
.NVIC_IRQChannelPreemptionPriority = PIOS_IRQ_PRIO_HIGH,
.NVIC_IRQChannelSubPriority = 0,
.NVIC_IRQChannelCmd = ENABLE,
},
},
.rx = {
.gpio = FLEXI_USART_RX_GPIO,
.init = {
.GPIO_Pin = FLEXI_USART_RX_PIN,
.GPIO_Speed = GPIO_Speed_2MHz,
.GPIO_Mode = GPIO_Mode_AF,
.GPIO_OType = GPIO_OType_PP,
.GPIO_PuPd = GPIO_PuPd_UP
},
},
.tx = {
.gpio = FLEXI_USART_TX_GPIO,
.init = {
.GPIO_Pin = FLEXI_USART_TX_PIN,
.GPIO_Speed = GPIO_Speed_2MHz,
.GPIO_Mode = GPIO_Mode_OUT,
.GPIO_OType = GPIO_OType_PP,
.GPIO_PuPd = GPIO_PuPd_UP
},
},
};
#endif /* PIOS_INCLUDE_EXBUS */
/*
* HK OSD
*/
static const struct pios_usart_cfg pios_usart_hkosd_main_cfg = {
.regs = MAIN_USART_REGS,
.remap = MAIN_USART_REMAP,
.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 = MAIN_USART_IRQ,
.NVIC_IRQChannelPreemptionPriority = PIOS_IRQ_PRIO_MID,
.NVIC_IRQChannelSubPriority = 0,
.NVIC_IRQChannelCmd = ENABLE,
},
},
.rx = {
.gpio = MAIN_USART_RX_GPIO,
.init = {
.GPIO_Pin = MAIN_USART_RX_PIN,
.GPIO_Speed = GPIO_Speed_2MHz,
.GPIO_Mode = GPIO_Mode_AF,
.GPIO_OType = GPIO_OType_PP,
.GPIO_PuPd = GPIO_PuPd_UP
},
},
.tx = {
.gpio = MAIN_USART_TX_GPIO,
.init = {
.GPIO_Pin = MAIN_USART_TX_PIN,
.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 = FLEXI_USART_REGS,
.remap = FLEXI_USART_REMAP,
.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 = FLEXI_USART_IRQ,
.NVIC_IRQChannelPreemptionPriority = PIOS_IRQ_PRIO_MID,
.NVIC_IRQChannelSubPriority = 0,
.NVIC_IRQChannelCmd = ENABLE,
},
},
.rx = {
.gpio = FLEXI_USART_RX_GPIO,
.init = {
.GPIO_Pin = FLEXI_USART_RX_PIN,
.GPIO_Speed = GPIO_Speed_2MHz,
.GPIO_Mode = GPIO_Mode_AF,
.GPIO_OType = GPIO_OType_PP,
.GPIO_PuPd = GPIO_PuPd_UP
},
},
.tx = {
.tx = {
.gpio = FLEXI_USART_TX_GPIO,
.init = {
.GPIO_Pin = FLEXI_USART_TX_PIN,
@ -815,7 +291,17 @@ static const struct pios_usart_cfg pios_usart_hkosd_flexi_cfg = {
.GPIO_PuPd = GPIO_PuPd_UP
},
},
// .dtr = {
// .gpio = FLEXI_USART_DTR_GPIO,
// .init = {
// .GPIO_Pin = FLEXI_USART_DTR_PIN,
// .GPIO_Speed = GPIO_Speed_25MHz,
// .GPIO_Mode = GPIO_Mode_OUT,
// .GPIO_OType = GPIO_OType_PP,
// },
// },
};
#endif /* PIOS_INCLUDE_USART */
#if defined(PIOS_INCLUDE_COM)
@ -837,7 +323,7 @@ __attribute__((alias("PIOS_I2C_pressure_adapter_ev_irq_handler")));
void I2C3_ER_IRQHandler()
__attribute__((alias("PIOS_I2C_pressure_adapter_er_irq_handler")));
static const struct pios_i2c_adapter_cfg pios_i2c_pressure_adapter_cfg = {
static const struct pios_i2c_adapter_cfg pios_i2c_eeprom_pressure_adapter_cfg = {
.regs = I2C3,
.remapSCL = GPIO_AF_I2C3,
.remapSDA = GPIO_AF9_I2C3,
@ -890,17 +376,17 @@ static const struct pios_i2c_adapter_cfg pios_i2c_pressure_adapter_cfg = {
},
};
uint32_t pios_i2c_pressure_adapter_id;
uint32_t pios_i2c_eeprom_pressure_adapter_id;
void PIOS_I2C_pressure_adapter_ev_irq_handler(void)
{
/* Call into the generic code to handle the IRQ for this specific device */
PIOS_I2C_EV_IRQ_Handler(pios_i2c_pressure_adapter_id);
PIOS_I2C_EV_IRQ_Handler(pios_i2c_eeprom_pressure_adapter_id);
}
void PIOS_I2C_pressure_adapter_er_irq_handler(void)
{
/* Call into the generic code to handle the IRQ for this specific device */
PIOS_I2C_ER_IRQ_Handler(pios_i2c_pressure_adapter_id);
PIOS_I2C_ER_IRQ_Handler(pios_i2c_eeprom_pressure_adapter_id);
}
@ -1347,37 +833,6 @@ const struct pios_usb_cfg *PIOS_BOARD_HW_DEFS_GetUsbCfg(uint32_t board_revision)
#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>
#include <hwsettings.h>
@ -1470,3 +925,146 @@ struct pios_flash_eeprom_cfg flash_main_chip_cfg = {
};
// .i2c_address = 0x50,
#endif /* PIOS_INCLUDE_FLASH_EEPROM */
/**
* 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"
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_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 MPU9250 chip
*/
#if defined(PIOS_INCLUDE_MPU9250)
#include "pios_mpu9250.h"
static const struct pios_exti_cfg pios_exti_mpu9250_cfg __exti_config = {
.vector = PIOS_MPU9250_IRQHandler,
.line = EXTI_Line15,
.pin = {
.gpio = GPIOA,
.init = {
.GPIO_Pin = GPIO_Pin_15,
.GPIO_Speed = GPIO_Speed_100MHz,
.GPIO_Mode = GPIO_Mode_IN,
.GPIO_OType = GPIO_OType_OD,
.GPIO_PuPd = GPIO_PuPd_NOPULL,
},
},
.irq = {
.init = {
.NVIC_IRQChannel = EXTI15_10_IRQn,
.NVIC_IRQChannelPreemptionPriority = PIOS_IRQ_PRIO_HIGH,
.NVIC_IRQChannelSubPriority = 0,
.NVIC_IRQChannelCmd = ENABLE,
},
},
.exti = {
.init = {
.EXTI_Line = EXTI_Line15, // matches above GPIO pin
.EXTI_Mode = EXTI_Mode_Interrupt,
.EXTI_Trigger = EXTI_Trigger_Rising,
.EXTI_LineCmd = ENABLE,
},
},
};
static const struct pios_mpu9250_cfg pios_mpu9250_cfg = {
.exti_cfg = &pios_exti_mpu9250_cfg,
.Fifo_store = 0,
// 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_MPU9250_INT_CLR_ANYRD, // | PIOS_MPU9250_INT_LATCH_EN,
.interrupt_en = PIOS_MPU9250_INTEN_DATA_RDY,
.User_ctl = PIOS_MPU9250_USERCTL_DIS_I2C | PIOS_MPU9250_USERCTL_I2C_MST_EN,
.Pwr_mgmt_clk = PIOS_MPU9250_PWRMGMT_PLL_Z_CLK,
.accel_range = PIOS_MPU9250_ACCEL_8G,
.gyro_range = PIOS_MPU9250_SCALE_2000_DEG,
.filter = PIOS_MPU9250_LOWPASS_256_HZ,
.orientation = PIOS_MPU9250_TOP_180DEG,
.fast_prescaler = PIOS_SPI_PRESCALER_4,
.std_prescaler = PIOS_SPI_PRESCALER_64,
.max_downsample = 26,
};
const struct pios_mpu9250_cfg *PIOS_BOARD_HW_DEFS_GetMPU9250Cfg(__attribute__((unused)) uint32_t board_revision)
{
return &pios_mpu9250_cfg;
}
#endif /* PIOS_INCLUDE_MPU9250 */

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

@ -25,6 +25,7 @@
#include <pios.h>
#include <pios_board_info.h>
#include <pios_board_io.h>
/*
* Pull in the board-specific static HW definitions.
@ -39,6 +40,7 @@
uint32_t pios_com_telem_usb_id;
static bool board_init_complete = false;
void PIOS_Board_Init()
{
if (board_init_complete) {
@ -68,7 +70,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

@ -30,21 +30,19 @@
#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_ws2811.h>
#include <sanitycheck.h>
#include <actuatorsettings.h>
#include <auxmagsettings.h>
#include "sanitycheck.h"
#include "actuatorsettings.h"
#ifdef PIOS_INCLUDE_INSTRUMENTATION
#include <pios_instrumentation.h>
#endif
#include <pios_board_io.h>
#include <pios_board_sensors.h>
/*
* Pull in the board-specific static HW definitions.
* Including .c files is a bit ugly but this allows all of
@ -55,286 +53,11 @@
*/
#include "../board_hw_defs.c"
static SystemAlarmsExtendedAlarmStatusOptions RevoNanoConfigHook();
static void ActuatorSettingsUpdatedCb(UAVObjEvent *ev);
/**
* 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 external_mag = 0;
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_4096,
};
#endif /* PIOS_INCLUDE_MS5611 */
/**
* Configuration for the MPU9250 chip
*/
#if defined(PIOS_INCLUDE_MPU9250)
#include "pios_mpu9250.h"
#include "pios_mpu9250_config.h"
static const struct pios_exti_cfg pios_exti_mpu9250_cfg __exti_config = {
.vector = PIOS_MPU9250_IRQHandler,
.line = EXTI_Line15,
.pin = {
.gpio = GPIOA,
.init = {
.GPIO_Pin = GPIO_Pin_15,
.GPIO_Speed = GPIO_Speed_100MHz,
.GPIO_Mode = GPIO_Mode_IN,
.GPIO_OType = GPIO_OType_OD,
.GPIO_PuPd = GPIO_PuPd_NOPULL,
},
},
.irq = {
.init = {
.NVIC_IRQChannel = EXTI15_10_IRQn,
.NVIC_IRQChannelPreemptionPriority = PIOS_IRQ_PRIO_HIGH,
.NVIC_IRQChannelSubPriority = 0,
.NVIC_IRQChannelCmd = ENABLE,
},
},
.exti = {
.init = {
.EXTI_Line = EXTI_Line15, // matches above GPIO pin
.EXTI_Mode = EXTI_Mode_Interrupt,
.EXTI_Trigger = EXTI_Trigger_Rising,
.EXTI_LineCmd = ENABLE,
},
},
};
static const struct pios_mpu9250_cfg pios_mpu9250_cfg = {
.exti_cfg = &pios_exti_mpu9250_cfg,
.Fifo_store = 0,
// 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_MPU9250_INT_CLR_ANYRD, // | PIOS_MPU9250_INT_LATCH_EN,
.interrupt_en = PIOS_MPU9250_INTEN_DATA_RDY,
.User_ctl = PIOS_MPU9250_USERCTL_DIS_I2C | PIOS_MPU9250_USERCTL_I2C_MST_EN,
.Pwr_mgmt_clk = PIOS_MPU9250_PWRMGMT_PLL_Z_CLK,
.accel_range = PIOS_MPU9250_ACCEL_8G,
.gyro_range = PIOS_MPU9250_SCALE_2000_DEG,
.filter = PIOS_MPU9250_LOWPASS_256_HZ,
.orientation = PIOS_MPU9250_TOP_180DEG,
.fast_prescaler = PIOS_SPI_PRESCALER_4,
.std_prescaler = PIOS_SPI_PRESCALER_64,
.max_downsample = 26,
};
#endif /* PIOS_INCLUDE_MPU9250 */
/* 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_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_vcp_id = 0;
uint32_t pios_com_mavlink_id = 0;
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)
{
uint32_t pios_usart_id;
if (PIOS_USART_Init(&pios_usart_id, usart_port_cfg)) {
PIOS_Assert(0);
}
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_ibus(const struct pios_usart_cfg *usart_cfg)
{
uint32_t pios_usart_ibus_id;
if (PIOS_USART_Init(&pios_usart_ibus_id, usart_cfg)) {
PIOS_Assert(0);
}
uint32_t pios_ibus_id;
if (PIOS_IBUS_Init(&pios_ibus_id, &pios_usart_com_driver, pios_usart_ibus_id)) {
PIOS_Assert(0);
}
uint32_t pios_ibus_rcvr_id;
if (PIOS_RCVR_Init(&pios_ibus_rcvr_id, &pios_ibus_rcvr_driver, pios_ibus_id)) {
PIOS_Assert(0);
}
pios_rcvr_group_map[MANUALCONTROLSETTINGS_CHANNELGROUPS_IBUS] = pios_ibus_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;
}
static SystemAlarmsExtendedAlarmStatusOptions RevoNanoConfigHook();
static void ActuatorSettingsUpdatedCb(UAVObjEvent *ev);
/**
* PIOS_Board_Init()
@ -344,11 +67,36 @@ static void PIOS_Board_configure_ppm(const struct pios_ppm_cfg *ppm_cfg)
#include <pios_board_info.h>
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,
};
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,
};
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)
@ -363,18 +111,12 @@ void PIOS_Board_Init(void)
#endif
/* Set up the SPI interface to the gyro/acelerometer */
if (PIOS_SPI_Init(&pios_spi_gyro_id, &pios_spi_gyro_cfg)) {
if (PIOS_SPI_Init(&pios_spi_gyro_adapter_id, &pios_spi_gyro_cfg)) {
PIOS_DEBUG_Assert(0);
}
#if false
/* Set up the SPI interface to the flash and rfm22b */
if (PIOS_SPI_Init(&pios_spi_telem_flash_id, &pios_spi_telem_flash_cfg)) {
PIOS_DEBUG_Assert(0);
}
#endif
#ifdef PIOS_INCLUDE_I2C
if (PIOS_I2C_Init(&pios_i2c_pressure_adapter_id, &pios_i2c_pressure_adapter_cfg)) {
if (PIOS_I2C_Init(&pios_i2c_eeprom_pressure_adapter_id, &pios_i2c_eeprom_pressure_adapter_cfg)) {
PIOS_DEBUG_Assert(0);
}
#endif
@ -384,7 +126,7 @@ void PIOS_Board_Init(void)
uintptr_t flash_id = 0;
// Initialize the external USER flash
if (PIOS_Flash_EEPROM_Init(&flash_id, &flash_main_chip_cfg, pios_i2c_pressure_adapter_id, 0x50)) {
if (PIOS_Flash_EEPROM_Init(&flash_id, &flash_main_chip_cfg, pios_i2c_eeprom_pressure_adapter_id, 0x50)) {
PIOS_DEBUG_Assert(0);
}
@ -425,10 +167,6 @@ void PIOS_Board_Init(void)
EventDispatcherInitialize();
UAVObjInitialize();
HwSettingsInitialize();
#if defined(PIOS_INCLUDE_RFM22B)
OPLinkSettingsInitialize();
OPLinkStatusInitialize();
#endif /* PIOS_INCLUDE_RFM22B */
/* Initialize the alarms library */
AlarmsInitialize();
@ -452,364 +190,25 @@ 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;
PIOS_BOARD_IO_Configure_USB();
#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 defined(PIOS_INCLUDE_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;
case HWSETTINGS_RM_FLEXIPORT_SRXL:
#if defined(PIOS_INCLUDE_SRXL)
{
uint32_t pios_usart_srxl_id;
if (PIOS_USART_Init(&pios_usart_srxl_id, &pios_usart_srxl_flexi_cfg)) {
PIOS_Assert(0);
}
uint32_t pios_srxl_id;
if (PIOS_SRXL_Init(&pios_srxl_id, &pios_usart_com_driver, pios_usart_srxl_id)) {
PIOS_Assert(0);
}
if (hwsettings_flexiport < NELEMENTS(flexi_function_map)) {
PIOS_BOARD_IO_Configure_UART(&pios_usart_flexi_cfg, flexi_function_map[hwsettings_flexiport]);
}
uint32_t pios_srxl_rcvr_id;
if (PIOS_RCVR_Init(&pios_srxl_rcvr_id, &pios_srxl_rcvr_driver, pios_srxl_id)) {
PIOS_Assert(0);
}
pios_rcvr_group_map[MANUALCONTROLSETTINGS_CHANNELGROUPS_SRXL] = pios_srxl_rcvr_id;
}
#endif /* PIOS_INCLUDE_SRXL */
break;
case HWSETTINGS_RM_FLEXIPORT_IBUS:
#if defined(PIOS_INCLUDE_IBUS)
PIOS_Board_configure_ibus(&pios_usart_ibus_flexi_cfg);
#endif /* PIOS_INCLUDE_IBUS */
break;
case HWSETTINGS_RM_FLEXIPORT_HOTTSUMD:
case HWSETTINGS_RM_FLEXIPORT_HOTTSUMH:
#if defined(PIOS_INCLUDE_HOTT)
{
uint32_t pios_usart_hott_id;
if (PIOS_USART_Init(&pios_usart_hott_id, &pios_usart_hott_flexi_cfg)) {
PIOS_Assert(0);
}
uint32_t pios_hott_id;
if (PIOS_HOTT_Init(&pios_hott_id, &pios_usart_com_driver, pios_usart_hott_id,
hwsettings_flexiport == HWSETTINGS_RM_FLEXIPORT_HOTTSUMD ? PIOS_HOTT_PROTO_SUMD : PIOS_HOTT_PROTO_SUMH)) {
PIOS_Assert(0);
}
uint32_t pios_hott_rcvr_id;
if (PIOS_RCVR_Init(&pios_hott_rcvr_id, &pios_hott_rcvr_driver, pios_hott_id)) {
PIOS_Assert(0);
}
pios_rcvr_group_map[MANUALCONTROLSETTINGS_CHANNELGROUPS_HOTT] = pios_hott_rcvr_id;
}
#endif /* PIOS_INCLUDE_HOTT */
break;
case HWSETTINGS_RM_FLEXIPORT_EXBUS:
#if defined(PIOS_INCLUDE_EXBUS)
{
uint32_t pios_usart_exbus_id;
if (PIOS_USART_Init(&pios_usart_exbus_id, &pios_usart_exbus_flexi_cfg)) {
PIOS_Assert(0);
}
uint32_t pios_exbus_id;
if (PIOS_EXBUS_Init(&pios_exbus_id, &pios_usart_com_driver, pios_usart_exbus_id)) {
PIOS_Assert(0);
}
uint32_t pios_exbus_rcvr_id;
if (PIOS_RCVR_Init(&pios_exbus_rcvr_id, &pios_exbus_rcvr_driver, pios_exbus_id)) {
PIOS_Assert(0);
}
pios_rcvr_group_map[MANUALCONTROLSETTINGS_CHANNELGROUPS_EXBUS] = pios_exbus_rcvr_id;
}
#endif /* PIOS_INCLUDE_EXBUS */
break;
} /* hwsettings_rm_flexiport */
/* Configure main USART port */
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_PWM) || defined(PIOS_INCLUDE_PPM)
@ -828,7 +227,7 @@ void PIOS_Board_Init(void)
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);
PIOS_BOARD_IO_Configure_PWM_RCVR(&pios_pwm_cfg);
#endif /* PIOS_INCLUDE_PWM */
break;
case HWSETTINGS_RM_RCVRPORT_PPM:
@ -840,7 +239,7 @@ void PIOS_Board_Init(void)
pios_servo_cfg = &pios_servo_cfg_out_in_ppm;
}
PIOS_Board_configure_ppm(&pios_ppm_cfg);
PIOS_BOARD_IO_Configure_PPM_RCVR(&pios_ppm_cfg);
break;
#endif /* PIOS_INCLUDE_PPM */
@ -851,16 +250,9 @@ void PIOS_Board_Init(void)
}
#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_GCS_RCVR();
#endif
#ifdef PIOS_INCLUDE_WS2811
#include <pios_ws2811.h>
@ -884,31 +276,7 @@ void PIOS_Board_Init(void)
PIOS_DELAY_WaitmS(50);
#if defined(PIOS_INCLUDE_ADC)
PIOS_ADC_Init(&pios_adc_cfg);
#endif
#if defined(PIOS_INCLUDE_MPU9250)
PIOS_MPU9250_Init(pios_spi_gyro_id, 0, &pios_mpu9250_cfg);
PIOS_MPU9250_CONFIG_Configure();
PIOS_MPU9250_MainRegister();
PIOS_MPU9250_MagRegister();
#endif
#if defined(PIOS_INCLUDE_MS5611)
PIOS_MS5611_Init(&pios_ms5611_cfg, pios_i2c_pressure_adapter_id);
PIOS_MS5611_Register();
#endif
#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_BOARD_Sensors_Configure();
// Attach the board config check hook
SANITYCHECK_AttachHook(&RevoNanoConfigHook);

View File

@ -103,75 +103,52 @@
// 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_adapter_id;
#define PIOS_SPI_MPU9250_ADAPTER (pios_spi_gyro_adapter_id)
// ------------------------
// PIOS_WDG
// ------------------------
#define PIOS_WATCHDOG_TIMEOUT 500
#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_WATCHDOG_TIMEOUT 500
#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
// ------------------------
// PIOS_I2C
// See also pios_board.c
// ------------------------
#define PIOS_I2C_MAX_DEVS 3
extern uint32_t pios_i2c_mag_pressure_adapter_id;
#define PIOS_I2C_MAIN_ADAPTER (pios_i2c_mag_pressure_adapter_id)
#define PIOS_I2C_MAX_DEVS 3
extern uint32_t pios_i2c_eeprom_pressure_adapter_id;
#define PIOS_I2C_MS5611_INTERNAL_ADAPTER (pios_i2c_eeprom_pressure_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_MS4525DO_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_MS4525DO_ADAPTER (PIOS_I2C_FLEXI_ADAPTER)
#define PIOS_I2C_EXTERNAL_ADAPTER (PIOS_I2C_FLEXI_ADAPTER)
// -------------------------
// PIOS_USART
//
// See also pios_board.c
// -------------------------
#define PIOS_USART_MAX_DEVS 5
#define PIOS_USART_MAX_DEVS 5
// Inverter for SBUS handling
#define PIOS_USART_INVERTER_PORT USART2
#define PIOS_USART_INVERTER_GPIO GPIOC
#define PIOS_USART_INVERTER_PIN GPIO_Pin_15
#define PIOS_USART_INVERTER_ENABLE Bit_SET
#define PIOS_USART_INVERTER_DISABLE Bit_RESET
// -------------------------
// PIOS_COM
//
// See also pios_board.c
// -------------------------
#define PIOS_COM_MAX_DEVS 4
extern uint32_t pios_com_telem_rf_id;
extern uint32_t pios_com_rf_id;
extern uint32_t pios_com_gps_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_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_RF (pios_com_rf_id)
#define PIOS_COM_BRIDGE (pios_com_bridge_id)
#define PIOS_COM_VCP (pios_com_vcp_id)
#define PIOS_COM_OSDHK (pios_com_hkosd_id)
#define PIOS_COM_MSP (pios_com_msp_id)
#define PIOS_COM_MAVLINK (pios_com_mavlink_id)
#if defined(PIOS_INCLUDE_DEBUG_CONSOLE)
extern uint32_t pios_com_debug_id;
#define PIOS_COM_DEBUG (pios_com_debug_id)
#endif /* PIOS_INCLUDE_DEBUG_CONSOLE */
#if defined(PIOS_INCLUDE_RFM22B)
extern uint32_t pios_rfm22b_id;
extern uint32_t pios_spi_telem_flash_id;
#define PIOS_RFM22_SPI_PORT (pios_spi_telem_flash_id)
#endif /* PIOS_INCLUDE_RFM22B */
#define PIOS_COM_MAX_DEVS 4
// -------------------------
// Packet Handler
// -------------------------
@ -262,7 +239,7 @@ extern uint32_t pios_packet_handler;
// -------------------------
#define PIOS_SBUS_MAX_DEVS 1
#define PIOS_SBUS_NUM_INPUTS (16 + 2)
#define PIOS_SBUS_BAUD_RATE 99999 /* f411 / 96mhz sysclk / usart2 baud rate weirdness */
// -------------------------
// Receiver HOTT input
// -------------------------

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,11 @@ static const struct pios_usart_cfg pios_usart_aux_cfg = {
/*
* AUX USART SBUS ( UART/ S Bus label on rev2)
*/
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 +725,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,
@ -814,24 +746,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 +756,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 +770,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 +1625,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

@ -83,6 +83,7 @@
#define PIOS_MPU6000_ACCEL
/* #define PIOS_INCLUDE_HMC5843 */
#define PIOS_INCLUDE_HMC5X83
#define PIOS_INCLUDE_HMC5X83_INTERNAL
#define PIOS_HMC5X83_HAS_GPIOS
/* #define PIOS_INCLUDE_BMP085 */
#define PIOS_INCLUDE_MS5611

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
@ -412,8 +58,6 @@ static void PIOS_Board_configure_dsm(const struct pios_usart_cfg *pios_usart_dsm
void PIOS_Board_Init(void)
{
const struct pios_board_info *bdinfo = &pios_board_info_blob;
/* Delay system */
PIOS_DELAY_Init();
@ -516,293 +160,100 @@ 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);
#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 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 +265,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 +277,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_RCVR(&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_RCVR(&pios_ppm_cfg);
#endif /* PIOS_INCLUDE_PPM */
case HWSETTINGS_RV_RCVRPORT_OUTPUTS:
@ -929,17 +322,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_GCS_RCVR();
#endif
#ifndef PIOS_ENABLE_DEBUG_PINS
switch (hwsettings_rcvrport) {
@ -972,69 +357,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,37 +81,54 @@
// 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
//
// See also pios_board.c
// -------------------------
#define PIOS_USART_MAX_DEVS 5
#define PIOS_USART_MAX_DEVS 5
// Inverter for SBUS handling
#define PIOS_USART_INVERTER_PORT UART4
#define PIOS_USART_INVERTER_GPIO GPIOC
#define PIOS_USART_INVERTER_PIN GPIO_Pin_3
#define PIOS_USART_INVERTER_ENABLE Bit_SET
#define PIOS_USART_INVERTER_DISABLE Bit_RESET
// -------------------------
// PIOS_COM
@ -119,26 +136,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

@ -52,7 +52,7 @@
#define PIOS_INCLUDE_SPI
#define PIOS_INCLUDE_SYS
#define PIOS_INCLUDE_TASK_MONITOR
#define PIOS_INCLUDE_USART
// #define PIOS_INCLUDE_USART
// #define PIOS_INCLUDE_USB
#define PIOS_INCLUDE_USB_HID
// #define PIOS_INCLUDE_GPIO
@ -87,8 +87,8 @@
#define PIOS_INCLUDE_RCVR
#define PIOS_INCLUDE_DSM
// #define PIOS_INCLUDE_SBUS
#define PIOS_INCLUDE_PPM
#define PIOS_INCLUDE_PWM
// #define PIOS_INCLUDE_PPM
// #define PIOS_INCLUDE_PWM
/* #define PIOS_INCLUDE_GCSRCVR */
/* #define PIOS_INCLUDE_OPLINKRCVR */
#define PIOS_INCLUDE_IAP

View File

@ -254,11 +254,11 @@ static const struct pios_spi_cfg pios_spi_gyro_cfg = {
}
};
static uint32_t pios_spi_gyro_id;
uint32_t pios_spi_gyro_adapter_id;
void PIOS_SPI_gyro_irq_handler(void)
{
/* Call into the generic code to handle the IRQ for this specific device */
PIOS_SPI_IRQ_Handler(pios_spi_gyro_id);
PIOS_SPI_IRQ_Handler(pios_spi_gyro_adapter_id);
}
@ -389,11 +389,11 @@ static const struct pios_spi_cfg pios_spi_telem_flash_cfg = {
},
};
uint32_t pios_spi_telem_flash_id;
uint32_t pios_spi_telem_flash_adapter_id;
void PIOS_SPI_telem_flash_irq_handler(void)
{
/* Call into the generic code to handle the IRQ for this specific device */
PIOS_SPI_IRQ_Handler(pios_spi_telem_flash_id);
PIOS_SPI_IRQ_Handler(pios_spi_telem_flash_adapter_id);
}
@ -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,33 +540,17 @@ static const struct flashfs_logfs_cfg flashfs_internal_cfg = {
#endif /* PIOS_INCLUDE_FLASH */
#ifdef PIOS_INCLUDE_USART
#include <pios_usart_priv.h>
#ifdef PIOS_INCLUDE_COM_TELEM
/*
* MAIN PORT
*/
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 = {
.rx = {
.gpio = GPIOA,
.init = {
.GPIO_Pin = GPIO_Pin_10,
@ -576,52 +560,7 @@ static const struct pios_usart_cfg pios_usart_main_cfg = {
.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 = {
.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 = {
.tx = {
.gpio = GPIOA,
.init = {
.GPIO_Pin = GPIO_Pin_9,
@ -633,49 +572,13 @@ static const struct pios_usart_cfg pios_usart_dsm_main_cfg = {
},
};
// 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 */
#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 = {
.rx = {
.gpio = GPIOB,
.init = {
.GPIO_Pin = GPIO_Pin_11,
@ -685,475 +588,7 @@ static const struct pios_usart_cfg pios_usart_flexi_cfg = {
.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
},
},
};
#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 */
#if defined(PIOS_INCLUDE_SRXL)
/*
* SRXL USART
*/
#include <pios_srxl_priv.h>
static const struct pios_usart_cfg pios_usart_srxl_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_OUT,
.GPIO_OType = GPIO_OType_PP,
.GPIO_PuPd = GPIO_PuPd_UP
},
},
};
static const struct pios_usart_cfg pios_usart_srxl_rcvr_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
},
},
};
#endif /* PIOS_INCLUDE_SRXL */
#if defined(PIOS_INCLUDE_IBUS)
/*
* IBUS USART
*/
#include <pios_ibus_priv.h>
static const struct pios_usart_cfg pios_usart_ibus_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_OUT,
.GPIO_OType = GPIO_OType_PP,
.GPIO_PuPd = GPIO_PuPd_UP
},
},
};
static const struct pios_usart_cfg pios_usart_ibus_rcvr_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
},
},
};
#endif /* PIOS_INCLUDE_IBUS */
// these were copied from Revo support
// they might need to be further modified for Sparky2 support
#if defined(PIOS_INCLUDE_HOTT)
/*
* HOTT USART
*/
#include <pios_hott_priv.h>
static const struct pios_usart_cfg pios_usart_hott_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_OUT,
.GPIO_OType = GPIO_OType_PP,
.GPIO_PuPd = GPIO_PuPd_UP
},
},
};
static const struct pios_usart_cfg pios_usart_hott_rcvr_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
},
},
};
#endif /* PIOS_INCLUDE_HOTT */
#if defined(PIOS_INCLUDE_EXBUS)
/*
* EXBUS USART
*/
#include <pios_exbus_priv.h>
static const struct pios_usart_cfg pios_usart_exbus_flexi_cfg = {
.regs = USART3,
.remap = GPIO_AF_USART3,
.init = {
.USART_BaudRate = 125000,
.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_OUT,
.GPIO_OType = GPIO_OType_PP,
.GPIO_PuPd = GPIO_PuPd_UP
},
},
};
static const struct pios_usart_cfg pios_usart_exbus_rcvr_cfg = {
.regs = USART6,
.remap = GPIO_AF_USART6,
.init = {
.USART_BaudRate = 125000,
.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
},
},
};
#endif /* PIOS_INCLUDE_EXBUS */
/*
* 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 = {
.tx = {
.gpio = GPIOB,
.init = {
.GPIO_Pin = GPIO_Pin_10,
@ -1170,32 +605,10 @@ static const struct pios_usart_cfg pios_usart_hkosd_flexi_cfg = {
* RCVR PORT
*/
#if defined(PIOS_INCLUDE_SBUS)
/*
* S.Bus USART
*/
#include <pios_sbus_priv.h>
static const struct pios_usart_cfg pios_usart_sbus_rcvr_cfg = {
static const struct pios_usart_cfg pios_usart_rcvr_cfg = {
.regs = USART6,
.remap = GPIO_AF_USART6,
.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 = USART6_IRQn,
.NVIC_IRQChannelPreemptionPriority = PIOS_IRQ_PRIO_HIGH,
.NVIC_IRQChannelSubPriority = 0,
.NVIC_IRQChannelCmd = ENABLE,
},
},
.rx = {
.rx = {
.gpio = GPIOC,
.init = {
.GPIO_Pin = GPIO_Pin_7,
@ -1206,81 +619,7 @@ static const struct pios_usart_cfg pios_usart_sbus_rcvr_cfg = {
},
},
};
static const struct pios_sbus_cfg pios_sbus_cfg = {
/* Inverter configuration */
.inv = {
.gpio = GPIOC,
.init = {
.GPIO_Pin = GPIO_Pin_6,
.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,
};
#endif /* PIOS_INCLUDE_SBUS */
#ifdef PIOS_INCLUDE_DSM
// It looks like TL notes originally came from OP's pios_dsm_main_cfg
// (TL note) Because of the inverter on the main port this will not
// (TL note) work. Notice the mode is set to IN to maintain API
// (TL note) compatibility but protect the pins
static const struct pios_dsm_cfg pios_dsm_rcvr_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_rcvr_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
},
},
};
#endif /* PIOS_INCLUDE_DSM */
#endif /* PIOS_INCLUDE_USART */
#if defined(PIOS_INCLUDE_COM)
@ -1295,14 +634,14 @@ static const struct pios_usart_cfg pios_usart_dsm_rcvr_cfg = {
/*
* I2C Adapters
*/
void PIOS_i2c_mag_pressure_adapter_ev_irq_handler(void);
void PIOS_i2c_mag_pressure_adapter_er_irq_handler(void);
void PIOS_i2c_pressure_adapter_ev_irq_handler(void);
void PIOS_i2c_pressure_adapter_er_irq_handler(void);
void I2C1_EV_IRQHandler()
__attribute__((alias("PIOS_i2c_mag_pressure_adapter_ev_irq_handler")));
__attribute__((alias("PIOS_i2c_pressure_adapter_ev_irq_handler")));
void I2C1_ER_IRQHandler()
__attribute__((alias("PIOS_i2c_mag_pressure_adapter_er_irq_handler")));
__attribute__((alias("PIOS_i2c_pressure_adapter_er_irq_handler")));
static const struct pios_i2c_adapter_cfg pios_i2c_mag_pressure_adapter_cfg = {
static const struct pios_i2c_adapter_cfg pios_i2c_pressure_adapter_cfg = {
.regs = I2C1,
.remapSCL = GPIO_AF_I2C1,
.remapSDA = GPIO_AF_I2C1,
@ -1355,17 +694,17 @@ static const struct pios_i2c_adapter_cfg pios_i2c_mag_pressure_adapter_cfg = {
},
};
uint32_t pios_i2c_mag_pressure_adapter_id;
void PIOS_i2c_mag_pressure_adapter_ev_irq_handler(void)
uint32_t pios_i2c_pressure_adapter_id;
void PIOS_i2c_pressure_adapter_ev_irq_handler(void)
{
/* Call into the generic code to handle the IRQ for this specific device */
PIOS_I2C_EV_IRQ_Handler(pios_i2c_mag_pressure_adapter_id);
PIOS_I2C_EV_IRQ_Handler(pios_i2c_pressure_adapter_id);
}
void PIOS_i2c_mag_pressure_adapter_er_irq_handler(void)
void PIOS_i2c_pressure_adapter_er_irq_handler(void)
{
/* Call into the generic code to handle the IRQ for this specific device */
PIOS_I2C_ER_IRQ_Handler(pios_i2c_mag_pressure_adapter_id);
PIOS_I2C_ER_IRQ_Handler(pios_i2c_pressure_adapter_id);
}
@ -1441,8 +780,8 @@ void PIOS_I2C_flexiport_adapter_er_irq_handler(void)
}
void PIOS_i2c_mag_pressure_adapter_ev_irq_handler(void);
void PIOS_i2c_mag_pressure_adapter_er_irq_handler(void);
void PIOS_i2c_pressure_adapter_ev_irq_handler(void);
void PIOS_i2c_pressure_adapter_er_irq_handler(void);
#endif /* PIOS_INCLUDE_I2C */
@ -1720,7 +1059,7 @@ static const struct pios_ppm_cfg pios_ppm_cfg = {
#if defined(PIOS_INCLUDE_USB)
#include "pios_usb_priv.h"
static const struct pios_usb_cfg pios_usb_main_rm2_cfg = {
static const struct pios_usb_cfg pios_usb_main_spk2_cfg = {
.irq = {
.init = {
.NVIC_IRQChannel = OTG_FS_IRQn,
@ -1743,7 +1082,7 @@ static const struct pios_usb_cfg pios_usb_main_rm2_cfg = {
const struct pios_usb_cfg *PIOS_BOARD_HW_DEFS_GetUsbCfg(__attribute__((unused)) uint32_t board_revision)
{
return &pios_usb_main_rm2_cfg;
return &pios_usb_main_spk2_cfg;
}
#include "pios_usb_board_data_priv.h"
@ -1759,37 +1098,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>
#include <hwsettings.h>
@ -1906,3 +1214,144 @@ 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"
static const struct pios_hmc5x83_cfg pios_hmc5x83_external_cfg = {
#ifdef PIOS_HMC5X83_HAS_GPIOS
.exti_cfg = NULL,
#endif /* PIOS_HMC5X83_HAS_GPIOS */
.M_ODR = PIOS_HMC5x83_ODR_75,
.Meas_Conf = PIOS_HMC5x83_MEASCONF_NORMAL,
.Gain = PIOS_HMC5x83_GAIN_1_9,
.Mode = PIOS_HMC5x83_MODE_CONTINUOUS,
.Driver = &PIOS_HMC5x83_I2C_DRIVER,
.Orientation = PIOS_HMC5X83_ORIENTATION_EAST_NORTH_UP,
};
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 MPU9250 chip
*/
#if defined(PIOS_INCLUDE_MPU9250)
#include "pios_mpu9250.h"
static const struct pios_exti_cfg pios_exti_mpu9250_cfg __exti_config = {
.vector = PIOS_MPU9250_IRQHandler,
.line = EXTI_Line5,
.pin = {
.gpio = GPIOC,
.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_HIGH,
.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,
},
},
};
static const struct pios_mpu9250_cfg pios_mpu9250_cfg = {
.exti_cfg = &pios_exti_mpu9250_cfg,
.Fifo_store = 0,
// 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_MPU9250_INT_CLR_ANYRD, // | PIOS_MPU9250_INT_LATCH_EN,
.interrupt_en = PIOS_MPU9250_INTEN_DATA_RDY,
.User_ctl = PIOS_MPU9250_USERCTL_DIS_I2C | PIOS_MPU9250_USERCTL_I2C_MST_EN,
.Pwr_mgmt_clk = PIOS_MPU9250_PWRMGMT_PLL_Z_CLK,
.accel_range = PIOS_MPU9250_ACCEL_8G,
.gyro_range = PIOS_MPU9250_SCALE_2000_DEG,
.filter = PIOS_MPU9250_LOWPASS_256_HZ,
.orientation = PIOS_MPU9250_TOP_180DEG,
.fast_prescaler = PIOS_SPI_PRESCALER_4,
.std_prescaler = PIOS_SPI_PRESCALER_64,
.max_downsample = 26,
};
const struct pios_mpu9250_cfg *PIOS_BOARD_HW_DEFS_GetMPU9250Cfg(__attribute__((unused)) uint32_t board_revision)
{
return &pios_mpu9250_cfg;
}
#endif /* PIOS_INCLUDE_MPU9250 */

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
@ -39,6 +38,7 @@
uint32_t pios_com_telem_usb_id;
static bool board_init_complete = false;
void PIOS_Board_Init()
{
if (board_init_complete) {
@ -68,7 +68,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

@ -30,22 +30,18 @@
#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 <pios_openlrs.h>
#include <pios_openlrs_rcvr_priv.h>
#include <taskinfo.h>
#include <pios_ws2811.h>
#include <sanitycheck.h>
#include <actuatorsettings.h>
#include <auxmagsettings.h>
#ifdef PIOS_INCLUDE_INSTRUMENTATION
#include <pios_instrumentation.h>
#endif
#ifdef PIOS_INCLUDE_WS2811
#include <pios_ws2811.h>
#endif
#include <pios_board_io.h>
#include <pios_board_sensors.h>
/*
* Pull in the board-specific static HW definitions.
@ -57,339 +53,45 @@
*/
#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 i2c_port_mag = 0;
pios_hmc5x83_dev_t flexi_port_mag = 0;
static const struct pios_hmc5x83_cfg pios_hmc5x83_cfg = {
#ifdef PIOS_HMC5X83_HAS_GPIOS
.exti_cfg = NULL,
#endif /* PIOS_HMC5X83_HAS_GPIOS */
.M_ODR = PIOS_HMC5x83_ODR_75,
.Meas_Conf = PIOS_HMC5x83_MEASCONF_NORMAL,
.Gain = PIOS_HMC5x83_GAIN_1_9,
.Mode = PIOS_HMC5x83_MODE_CONTINUOUS,
.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 MPU9250 chip
*/
#if defined(PIOS_INCLUDE_MPU9250)
#include "pios_mpu9250.h"
#include "pios_mpu9250_config.h"
static const struct pios_exti_cfg pios_exti_mpu9250_cfg __exti_config = {
.vector = PIOS_MPU9250_IRQHandler,
.line = EXTI_Line5,
.pin = {
.gpio = GPIOC,
.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_HIGH,
.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,
},
},
};
static const struct pios_mpu9250_cfg pios_mpu9250_cfg = {
.exti_cfg = &pios_exti_mpu9250_cfg,
.Fifo_store = 0,
// 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_MPU9250_INT_CLR_ANYRD, // | PIOS_MPU9250_INT_LATCH_EN,
.interrupt_en = PIOS_MPU9250_INTEN_DATA_RDY,
.User_ctl = PIOS_MPU9250_USERCTL_DIS_I2C | PIOS_MPU9250_USERCTL_I2C_MST_EN,
.Pwr_mgmt_clk = PIOS_MPU9250_PWRMGMT_PLL_Z_CLK,
.accel_range = PIOS_MPU9250_ACCEL_8G,
.gyro_range = PIOS_MPU9250_SCALE_2000_DEG,
.filter = PIOS_MPU9250_LOWPASS_256_HZ,
.orientation = PIOS_MPU9250_TOP_180DEG,
.fast_prescaler = PIOS_SPI_PRESCALER_4,
.std_prescaler = PIOS_SPI_PRESCALER_64,
.max_downsample = 26,
};
#endif /* PIOS_INCLUDE_MPU9250 */
/* 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
#define PIOS_COM_MAVLINK_RX_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_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;
#include <pios_rfm22b_com.h>
#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)
{
uint32_t pios_usart_id;
static const PIOS_BOARD_IO_UART_Function rcvr_function_map[] = {
[HWSETTINGS_SPK2_RCVRPORT_SBUS] = PIOS_BOARD_IO_UART_SBUS,
[HWSETTINGS_SPK2_RCVRPORT_DSM] = PIOS_BOARD_IO_UART_DSM_RCVR,
[HWSETTINGS_SPK2_RCVRPORT_SRXL] = PIOS_BOARD_IO_UART_SRXL,
[HWSETTINGS_SPK2_RCVRPORT_IBUS] = PIOS_BOARD_IO_UART_IBUS,
[HWSETTINGS_SPK2_RCVRPORT_EXBUS] = PIOS_BOARD_IO_UART_EXBUS,
[HWSETTINGS_SPK2_RCVRPORT_HOTTSUMD] = PIOS_BOARD_IO_UART_HOTT_SUMD,
[HWSETTINGS_SPK2_RCVRPORT_HOTTSUMH] = PIOS_BOARD_IO_UART_HOTT_SUMH,
};
if (PIOS_USART_Init(&pios_usart_id, usart_port_cfg)) {
PIOS_Assert(0);
}
static const PIOS_BOARD_IO_UART_Function main_function_map[] = {
[HWSETTINGS_SPK2_MAINPORT_TELEMETRY] = PIOS_BOARD_IO_UART_TELEMETRY,
[HWSETTINGS_SPK2_MAINPORT_GPS] = PIOS_BOARD_IO_UART_GPS,
[HWSETTINGS_SPK2_MAINPORT_DSM] = PIOS_BOARD_IO_UART_DSM_MAIN,
[HWSETTINGS_SPK2_MAINPORT_DEBUGCONSOLE] = PIOS_BOARD_IO_UART_DEBUGCONSOLE,
[HWSETTINGS_SPK2_MAINPORT_COMBRIDGE] = PIOS_BOARD_IO_UART_COMBRIDGE,
[HWSETTINGS_SPK2_MAINPORT_OSDHK] = PIOS_BOARD_IO_UART_OSDHK,
[HWSETTINGS_SPK2_MAINPORT_MSP] = PIOS_BOARD_IO_UART_MSP,
[HWSETTINGS_SPK2_MAINPORT_MAVLINK] = PIOS_BOARD_IO_UART_MAVLINK,
};
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_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;
}
static void PIOS_Board_configure_srxl(const struct pios_usart_cfg *usart_cfg)
{
uint32_t pios_usart_srxl_id;
if (PIOS_USART_Init(&pios_usart_srxl_id, usart_cfg)) {
PIOS_Assert(0);
}
uint32_t pios_srxl_id;
if (PIOS_SRXL_Init(&pios_srxl_id, &pios_usart_com_driver, pios_usart_srxl_id)) {
PIOS_Assert(0);
}
uint32_t pios_srxl_rcvr_id;
if (PIOS_RCVR_Init(&pios_srxl_rcvr_id, &pios_srxl_rcvr_driver, pios_srxl_id)) {
PIOS_Assert(0);
}
pios_rcvr_group_map[MANUALCONTROLSETTINGS_CHANNELGROUPS_SRXL] = pios_srxl_rcvr_id;
}
static void PIOS_Board_configure_ibus(const struct pios_usart_cfg *usart_cfg)
{
uint32_t pios_usart_ibus_id;
if (PIOS_USART_Init(&pios_usart_ibus_id, usart_cfg)) {
PIOS_Assert(0);
}
uint32_t pios_ibus_id;
if (PIOS_IBUS_Init(&pios_ibus_id, &pios_usart_com_driver, pios_usart_ibus_id)) {
PIOS_Assert(0);
}
uint32_t pios_ibus_rcvr_id;
if (PIOS_RCVR_Init(&pios_ibus_rcvr_id, &pios_ibus_rcvr_driver, pios_ibus_id)) {
PIOS_Assert(0);
}
pios_rcvr_group_map[MANUALCONTROLSETTINGS_CHANNELGROUPS_IBUS] = pios_ibus_rcvr_id;
}
static void PIOS_Board_configure_exbus(const struct pios_usart_cfg *usart_cfg)
{
uint32_t pios_usart_exbus_id;
if (PIOS_USART_Init(&pios_usart_exbus_id, usart_cfg)) {
PIOS_Assert(0);
}
uint32_t pios_exbus_id;
if (PIOS_EXBUS_Init(&pios_exbus_id, &pios_usart_com_driver, pios_usart_exbus_id)) {
PIOS_Assert(0);
}
uint32_t pios_exbus_rcvr_id;
if (PIOS_RCVR_Init(&pios_exbus_rcvr_id, &pios_exbus_rcvr_driver, pios_exbus_id)) {
PIOS_Assert(0);
}
pios_rcvr_group_map[MANUALCONTROLSETTINGS_CHANNELGROUPS_EXBUS] = pios_exbus_rcvr_id;
}
static void PIOS_Board_configure_hott(const struct pios_usart_cfg *usart_cfg, enum pios_hott_proto proto)
{
uint32_t pios_usart_hott_id;
if (PIOS_USART_Init(&pios_usart_hott_id, usart_cfg)) {
PIOS_Assert(0);
}
uint32_t pios_hott_id;
if (PIOS_HOTT_Init(&pios_hott_id, &pios_usart_com_driver, pios_usart_hott_id, proto)) {
PIOS_Assert(0);
}
uint32_t pios_hott_rcvr_id;
if (PIOS_RCVR_Init(&pios_hott_rcvr_id, &pios_hott_rcvr_driver, pios_hott_id)) {
PIOS_Assert(0);
}
pios_rcvr_group_map[MANUALCONTROLSETTINGS_CHANNELGROUPS_HOTT] = pios_hott_rcvr_id;
}
static const PIOS_BOARD_IO_UART_Function flexi_function_map[] = {
[HWSETTINGS_SPK2_FLEXIPORT_TELEMETRY] = PIOS_BOARD_IO_UART_TELEMETRY,
[HWSETTINGS_SPK2_FLEXIPORT_GPS] = PIOS_BOARD_IO_UART_GPS,
[HWSETTINGS_SPK2_FLEXIPORT_DSM] = PIOS_BOARD_IO_UART_DSM_FLEXI,
[HWSETTINGS_SPK2_FLEXIPORT_EXBUS] = PIOS_BOARD_IO_UART_EXBUS,
[HWSETTINGS_SPK2_FLEXIPORT_HOTTSUMD] = PIOS_BOARD_IO_UART_HOTT_SUMD,
[HWSETTINGS_SPK2_FLEXIPORT_HOTTSUMH] = PIOS_BOARD_IO_UART_HOTT_SUMH,
[HWSETTINGS_SPK2_FLEXIPORT_SRXL] = PIOS_BOARD_IO_UART_SRXL,
[HWSETTINGS_SPK2_FLEXIPORT_IBUS] = PIOS_BOARD_IO_UART_IBUS,
[HWSETTINGS_SPK2_FLEXIPORT_DEBUGCONSOLE] = PIOS_BOARD_IO_UART_DEBUGCONSOLE,
[HWSETTINGS_SPK2_FLEXIPORT_COMBRIDGE] = PIOS_BOARD_IO_UART_COMBRIDGE,
[HWSETTINGS_SPK2_FLEXIPORT_OSDHK] = PIOS_BOARD_IO_UART_OSDHK,
[HWSETTINGS_SPK2_FLEXIPORT_MSP] = PIOS_BOARD_IO_UART_MSP,
[HWSETTINGS_SPK2_FLEXIPORT_MAVLINK] = PIOS_BOARD_IO_UART_MAVLINK,
};
/**
* PIOS_Board_Init()
@ -397,13 +99,8 @@ static void PIOS_Board_configure_hott(const struct pios_usart_cfg *usart_cfg, en
* 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)
@ -418,27 +115,21 @@ void PIOS_Board_Init(void)
#endif
/* Set up the SPI interface to the gyro/acelerometer */
if (PIOS_SPI_Init(&pios_spi_gyro_id, &pios_spi_gyro_cfg)) {
if (PIOS_SPI_Init(&pios_spi_gyro_adapter_id, &pios_spi_gyro_cfg)) {
PIOS_DEBUG_Assert(0);
}
/* Set up the SPI interface to the flash and rfm22b */
if (PIOS_SPI_Init(&pios_spi_telem_flash_id, &pios_spi_telem_flash_cfg)) {
if (PIOS_SPI_Init(&pios_spi_telem_flash_adapter_id, &pios_spi_telem_flash_cfg)) {
PIOS_DEBUG_Assert(0);
}
#ifdef PIOS_INCLUDE_I2C
if (PIOS_I2C_Init(&pios_i2c_mag_pressure_adapter_id, &pios_i2c_mag_pressure_adapter_cfg)) {
PIOS_DEBUG_Assert(0);
}
#endif
#if defined(PIOS_INCLUDE_FLASH)
/* Connect flash to the appropriate interface and configure it */
uintptr_t flash_id = 0;
// Initialize the external USER flash
if (PIOS_Flash_Jedec_Init(&flash_id, pios_spi_telem_flash_id, 1)) {
if (PIOS_Flash_Jedec_Init(&flash_id, pios_spi_telem_flash_adapter_id, 1)) {
PIOS_DEBUG_Assert(0);
}
@ -477,13 +168,6 @@ void PIOS_Board_Init(void)
EventDispatcherInitialize();
UAVObjInitialize();
HwSettingsInitialize();
#if defined(PIOS_INCLUDE_RFM22B)
OPLinkSettingsInitialize();
OPLinkStatusInitialize();
#endif /* PIOS_INCLUDE_RFM22B */
#if defined(PIOS_INCLUDE_HMC5X83)
AuxMagSettingsInitialize();
#endif /* PIOS_INCLUDE_HMC5X83 */
/* Initialize the alarms library */
AlarmsInitialize();
@ -511,110 +195,29 @@ void PIOS_Board_Init(void)
}
/* Configure IO ports */
uint8_t hwsettings_DSMxBind;
HwSettingsDSMxBindGet(&hwsettings_DSMxBind);
/* Configure FlexiPort */
uint8_t hwsettings_flexiport;
HwSettingsSPK2_FlexiPortGet(&hwsettings_flexiport);
switch (hwsettings_flexiport) {
case HWSETTINGS_SPK2_FLEXIPORT_DISABLED:
break;
case HWSETTINGS_SPK2_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_SPK2_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)
#if defined(PIOS_INCLUDE_HMC5X83)
{
// get auxmag type
AuxMagSettingsTypeOptions option;
AuxMagSettingsTypeGet(&option);
// the FlexiPort type is I2C, so if the AuxMag type is Flexi(Port) then set it up
if (option == AUXMAGSETTINGS_TYPE_FLEXI) {
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 */
// attach the 5x83 mag to the previously inited I2C2
flexi_port_mag = PIOS_HMC5x83_Init(&pios_hmc5x83_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(flexi_port_mag, PIOS_SENSORS_TYPE_3AXIS_AUXMAG);
// mag alarm is cleared later, so use I2C
AlarmsSet(SYSTEMALARMS_ALARM_I2C, (flexi_port_mag) ? SYSTEMALARMS_ALARM_OK : SYSTEMALARMS_ALARM_WARNING);
}
/* Set up internal I2C bus */
if (PIOS_I2C_Init(&pios_i2c_pressure_adapter_id, &pios_i2c_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);
}
#endif /* PIOS_INCLUDE_HMC5X83 */
#endif /* PIOS_INCLUDE_I2C */
break;
case HWSETTINGS_SPK2_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_SPK2_FLEXIPORT_DSM:
// TODO: Define the various Channelgroup for Sparky2 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_SPK2_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_SPK2_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_SPK2_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_SPK2_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_SPK2_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;
case HWSETTINGS_SPK2_FLEXIPORT_SRXL:
#if defined(PIOS_INCLUDE_SRXL)
PIOS_Board_configure_srxl(&pios_usart_srxl_flexi_cfg);
#endif /* PIOS_INCLUDE_SRXL */
break;
case HWSETTINGS_SPK2_FLEXIPORT_IBUS:
#if defined(PIOS_INCLUDE_IBUS)
PIOS_Board_configure_ibus(&pios_usart_ibus_flexi_cfg);
#endif /* PIOS_INCLUDE_IBUS */
break;
case HWSETTINGS_SPK2_FLEXIPORT_HOTTSUMD:
case HWSETTINGS_SPK2_FLEXIPORT_HOTTSUMH:
#if defined(PIOS_INCLUDE_HOTT)
PIOS_Board_configure_hott(&pios_usart_hott_flexi_cfg,
hwsettings_flexiport == HWSETTINGS_SPK2_FLEXIPORT_HOTTSUMD ? PIOS_HOTT_PROTO_SUMD : PIOS_HOTT_PROTO_SUMH);
#endif /* PIOS_INCLUDE_HOTT */
break;
case HWSETTINGS_SPK2_FLEXIPORT_EXBUS:
#if defined(PIOS_INCLUDE_EXBUS)
PIOS_Board_configure_exbus(&pios_usart_exbus_flexi_cfg);
#endif /* PIOS_INCLUDE_EXBUS */
break;
} /* hwsettings_spk2_flexiport */
PIOS_DELAY_WaitmS(50);
}
#endif
/* Moved this here to allow binding on flexiport */
#if defined(PIOS_INCLUDE_FLASH)
@ -624,459 +227,65 @@ void PIOS_Board_Init(void)
#endif /* if defined(PIOS_INCLUDE_FLASH) */
#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_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 main USART port */
uint8_t hwsettings_mainport;
HwSettingsSPK2_MainPortGet(&hwsettings_mainport);
switch (hwsettings_mainport) {
case HWSETTINGS_SPK2_MAINPORT_DISABLED:
break;
case HWSETTINGS_SPK2_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_SPK2_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_SPK2_MAINPORT_DSM:
// Force binding to zero on the main port
hwsettings_DSMxBind = 0;
// TODO: Define the various Channelgroup for Sparky2 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_SPK2_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_SPK2_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_SPK2_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_SPK2_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_SPK2_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_spk2_mainport */
/* 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.Protocol == OPLINKSETTINGS_PROTOCOL_OPLINKCOORDINATOR);
bool openlrs = (oplinkSettings.Protocol == OPLINKSETTINGS_PROTOCOL_OPENLRS);
bool data_mode = ((oplinkSettings.LinkType == OPLINKSETTINGS_LINKTYPE_DATA) ||
(oplinkSettings.LinkType == OPLINKSETTINGS_LINKTYPE_DATAANDCONTROL));
bool ppm_mode = ((oplinkSettings.LinkType == OPLINKSETTINGS_LINKTYPE_CONTROL) ||
(oplinkSettings.LinkType == OPLINKSETTINGS_LINKTYPE_DATAANDCONTROL));
bool is_enabled = ((oplinkSettings.Protocol != OPLINKSETTINGS_PROTOCOL_DISABLED) &&
((oplinkSettings.MaxRFPower != OPLINKSETTINGS_MAXRFPOWER_0) || openlrs));
if (is_enabled) {
if (openlrs) {
#if defined(PIOS_INCLUDE_OPENLRS_RCVR)
const struct pios_openlrs_cfg *openlrs_cfg = PIOS_BOARD_HW_DEFS_GetOpenLRSCfg();
uint32_t openlrs_id;
PIOS_OpenLRS_Init(&openlrs_id, PIOS_RFM22_SPI_PORT, 0, openlrs_cfg);
{
uint32_t openlrsrcvr_id;
PIOS_OpenLRS_Rcvr_Init(&openlrsrcvr_id, openlrs_id);
uint32_t openlrsrcvr_rcvr_id;
if (PIOS_RCVR_Init(&openlrsrcvr_rcvr_id, &pios_openlrs_rcvr_driver, openlrsrcvr_id)) {
PIOS_Assert(0);
}
pios_rcvr_group_map[MANUALCONTROLSETTINGS_CHANNELGROUPS_OPENLRS] = openlrsrcvr_rcvr_id;
}
#endif /* PIOS_INCLUDE_OPENLRS_RCVR */
} else {
/* 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_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 modem (over the air) datarate.
enum rfm22b_datarate datarate = RFM22_datarate_64000;
switch (oplinkSettings.AirDataRate) {
case OPLINKSETTINGS_AIRDATARATE_9600:
datarate = RFM22_datarate_9600;
break;
case OPLINKSETTINGS_AIRDATARATE_19200:
datarate = RFM22_datarate_19200;
break;
case OPLINKSETTINGS_AIRDATARATE_32000:
datarate = RFM22_datarate_32000;
break;
case OPLINKSETTINGS_AIRDATARATE_57600:
datarate = RFM22_datarate_57600;
break;
case OPLINKSETTINGS_AIRDATARATE_64000:
datarate = RFM22_datarate_64000;
break;
case OPLINKSETTINGS_AIRDATARATE_100000:
datarate = RFM22_datarate_100000;
break;
case OPLINKSETTINGS_AIRDATARATE_128000:
datarate = RFM22_datarate_128000;
break;
case OPLINKSETTINGS_AIRDATARATE_192000:
datarate = RFM22_datarate_192000;
break;
case OPLINKSETTINGS_AIRDATARATE_256000:
datarate = RFM22_datarate_256000;
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 poer 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);
// TODO: this is in preparation for full mavlink support and is used by LP-368
uint16_t mavlink_rx_size = PIOS_COM_MAVLINK_RX_BUF_LEN;
uint8_t hwsettings_radioaux;
HwSettingsRadioAuxStreamGet(&hwsettings_radioaux);
switch (hwsettings_radioaux) {
case HWSETTINGS_RADIOAUXSTREAM_DEBUGCONSOLE:
case HWSETTINGS_RADIOAUXSTREAM_DISABLED:
break;
case HWSETTINGS_RADIOAUXSTREAM_MAVLINK:
{
uint8_t *auxrx_buffer = 0;
if (mavlink_rx_size) {
auxrx_buffer = (uint8_t *)pios_malloc(mavlink_rx_size);
}
uint8_t *auxtx_buffer = (uint8_t *)pios_malloc(PIOS_COM_MAVLINK_TX_BUF_LEN);
PIOS_Assert(auxrx_buffer);
PIOS_Assert(auxtx_buffer);
if (PIOS_COM_Init(&pios_com_mavlink_id, &pios_rfm22b_aux_com_driver, pios_rfm22b_id,
auxrx_buffer, mavlink_rx_size,
auxtx_buffer, PIOS_COM_BRIDGE_TX_BUF_LEN)) {
PIOS_Assert(0);
}
}
}
}
} else {
oplinkStatus.LinkState = OPLINKSTATUS_LINKSTATE_DISABLED;
if (hwsettings_mainport < NELEMENTS(main_function_map)) {
PIOS_BOARD_IO_Configure_UART(&pios_usart_main_cfg, main_function_map[hwsettings_mainport]);
}
OPLinkStatusSet(&oplinkStatus);
#endif /* PIOS_INCLUDE_RFM22B */
#if defined(PIOS_INCLUDE_RFM22B)
PIOS_BOARD_IO_Configure_RFM22B();
#if 1
#if defined(PIOS_INCLUDE_PPM)
const struct pios_servo_cfg *pios_servo_cfg;
// default to servo outputs only
pios_servo_cfg = &pios_servo_cfg_out;
#endif
#endif
uint8_t hwsettings_radioaux;
HwSettingsRadioAuxStreamGet(&hwsettings_radioaux);
PIOS_BOARD_IO_Configure_RadioAuxStream(hwsettings_radioaux);
#endif /* PIOS_INCLUDE_RFM22B */
// Configure the receiver port
// Sparky2 receiver input on PC7 TIM8 CH2
// include PPM,S.Bus,DSM,SRXL,IBus,EX.Bus,HoTT SUMD,HoTT SUMH
/* Configure the receiver port*/
uint8_t hwsettings_rcvrport;
HwSettingsSPK2_RcvrPortGet(&hwsettings_rcvrport);
switch (hwsettings_rcvrport) {
case HWSETTINGS_SPK2_RCVRPORT_PPM:
if (hwsettings_rcvrport < NELEMENTS(rcvr_function_map)) {
PIOS_BOARD_IO_Configure_UART(&pios_usart_rcvr_cfg, rcvr_function_map[hwsettings_rcvrport]);
}
#if defined(PIOS_INCLUDE_PPM)
PIOS_Board_configure_ppm(&pios_ppm_cfg);
#endif /* PIOS_INCLUDE_PPM */
break;
case HWSETTINGS_SPK2_RCVRPORT_SBUS:
#if defined(PIOS_INCLUDE_SBUS)
{
uint32_t pios_usart_sbus_id;
if (PIOS_USART_Init(&pios_usart_sbus_id, &pios_usart_sbus_rcvr_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;
}
if (hwsettings_rcvrport == HWSETTINGS_SPK2_RCVRPORT_PPM) {
PIOS_BOARD_IO_Configure_PPM_RCVR(&pios_ppm_cfg);
}
#endif
break;
case HWSETTINGS_SPK2_RCVRPORT_SRXL:
#if defined(PIOS_INCLUDE_SRXL)
PIOS_Board_configure_srxl(&pios_usart_srxl_rcvr_cfg);
#endif /* PIOS_INCLUDE_SRXL */
break;
case HWSETTINGS_SPK2_RCVRPORT_IBUS:
#if defined(PIOS_INCLUDE_IBUS)
PIOS_Board_configure_ibus(&pios_usart_ibus_rcvr_cfg);
#endif /* PIOS_INCLUDE_IBUS */
break;
case HWSETTINGS_SPK2_RCVRPORT_HOTTSUMD:
case HWSETTINGS_SPK2_RCVRPORT_HOTTSUMH:
#if defined(PIOS_INCLUDE_HOTT)
PIOS_Board_configure_hott(&pios_usart_hott_rcvr_cfg,
hwsettings_rcvrport == HWSETTINGS_SPK2_RCVRPORT_HOTTSUMD ? PIOS_HOTT_PROTO_SUMD : PIOS_HOTT_PROTO_SUMH);
#endif /* PIOS_INCLUDE_HOTT */
break;
case HWSETTINGS_SPK2_RCVRPORT_EXBUS:
#if defined(PIOS_INCLUDE_EXBUS)
PIOS_Board_configure_exbus(&pios_usart_exbus_rcvr_cfg);
#endif /* PIOS_INCLUDE_EXBUS */
break;
case HWSETTINGS_SPK2_RCVRPORT_DSM:
// TODO: Define the various Channelgroup for Sparky2 dsm inputs and handle here
PIOS_Board_configure_dsm(&pios_usart_dsm_rcvr_cfg, &pios_dsm_rcvr_cfg,
&pios_usart_com_driver, MANUALCONTROLSETTINGS_CHANNELGROUPS_DSMRCVRPORT, &hwsettings_DSMxBind);
break;
default:
break;
}
#ifdef PIOS_INCLUDE_GCSRCVR
PIOS_BOARD_IO_Configure_GCS_RCVR();
#endif
if (hwsettings_rcvrport != HWSETTINGS_SPK2_RCVRPORT_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);
}
#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 */
#if 1
#ifndef PIOS_ENABLE_DEBUG_PINS
// pios_servo_cfg points to the correct configuration based on input port settings
PIOS_Servo_Init(pios_servo_cfg);
PIOS_Servo_Init(&pios_servo_cfg_out);
#else
PIOS_DEBUG_Init(pios_tim_servoport_all_pins, NELEMENTS(pios_tim_servoport_all_pins));
#endif
#endif
PIOS_BOARD_Sensors_Configure();
#ifdef PIOS_INCLUDE_WS2811
HwSettingsWS2811LED_OutOptions ws2811_pin_settings;
HwSettingsWS2811LED_OutGet(&ws2811_pin_settings);
if (ws2811_pin_settings != HWSETTINGS_WS2811LED_OUT_DISABLED && ws2811_pin_settings < NELEMENTS(pios_ws2811_pin_cfg)) {
PIOS_WS2811_Init(&pios_ws2811_cfg, &pios_ws2811_pin_cfg[ws2811_pin_settings]);
}
#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,
@ -1086,101 +295,7 @@ void PIOS_Board_Init(void)
.GPIO_OType = GPIO_OType_OD,
};
GPIO_Init(GPIOA, &gpioA8);
#if defined(PIOS_INCLUDE_ADC)
PIOS_ADC_Init(&pios_adc_cfg);
#endif
#if defined(PIOS_INCLUDE_MPU9250)
PIOS_MPU9250_Init(pios_spi_gyro_id, 0, &pios_mpu9250_cfg);
PIOS_MPU9250_CONFIG_Configure();
PIOS_MPU9250_MainRegister();
PIOS_MPU9250_MagRegister();
#endif
#if 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
// 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)
// on board mag is in the MPU9250
// this hmc5x83 mag is an external mag
i2c_port_mag = PIOS_HMC5x83_Init(&pios_hmc5x83_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 */
PIOS_HMC5x83_Register(i2c_port_mag, PIOS_SENSORS_TYPE_3AXIS_AUXMAG);
#endif /* PIOS_INCLUDE_HMC5X83 */
#else /* if 0 */
#if defined(PIOS_INCLUDE_I2C)
#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
HwSettingsSPK2_I2CPortOptions i2cOption;
AuxMagSettingsTypeOptions option;
HwSettingsSPK2_I2CPortGet(&i2cOption);
AuxMagSettingsTypeGet(&option);
// if the I2CPort type is I2C(Port) and the AuxMag type is I2C(Port) then set it up
if (i2cOption == HWSETTINGS_SPK2_I2CPORT_I2C && option == AUXMAGSETTINGS_TYPE_I2C) {
// attach the 5x83 mag to the previously inited I2C2
i2c_port_mag = PIOS_HMC5x83_Init(&pios_hmc5x83_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
// 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(i2c_port_mag, PIOS_SENSORS_TYPE_3AXIS_AUXMAG);
// mag alarm is cleared later, so use I2C
AlarmsSet(SYSTEMALARMS_ALARM_I2C, (i2c_port_mag) ? SYSTEMALARMS_ALARM_OK : SYSTEMALARMS_ALARM_WARNING);
}
#endif /* PIOS_INCLUDE_HMC5X83 */
#endif /* PIOS_INCLUDE_I2C */
#endif /* 0 */
#if defined(PIOS_INCLUDE_MS5611)
PIOS_MS5611_Init(&pios_ms5611_cfg, pios_i2c_mag_pressure_adapter_id);
PIOS_MS5611_Register();
#endif /* PIOS_INCLUDE_MS5611 */
#ifdef PIOS_INCLUDE_WS2811
#include <pios_ws2811.h>
HwSettingsWS2811LED_OutOptions ws2811_pin_settings;
HwSettingsWS2811LED_OutGet(&ws2811_pin_settings);
if (ws2811_pin_settings != HWSETTINGS_WS2811LED_OUT_DISABLED && ws2811_pin_settings < NELEMENTS(pios_ws2811_pin_cfg)) {
PIOS_WS2811_Init(&pios_ws2811_cfg, &pios_ws2811_pin_cfg[ws2811_pin_settings]);
}
#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);
}
}
}
#endif // PIOS_INCLUDE_ADC
#endif /* PIOS_INCLUDE_ADC */
}
/**

View File

@ -105,74 +105,56 @@
// PIOS_SPI
// See also pios_board.c
// ------------------------
#define PIOS_SPI_MAX_DEVS 3
#define PIOS_SPI_MAX_DEVS 3
extern uint32_t pios_spi_telem_flash_adapter_id;
#define PIOS_SPI_RFM22B_ADAPTER (pios_spi_telem_flash_adapter_id)
extern uint32_t pios_spi_gyro_adapter_id;
#define PIOS_SPI_MPU9250_ADAPTER (pios_spi_gyro_adapter_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_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
// ------------------------
// PIOS_I2C
// See also pios_board.c
// ------------------------
#define PIOS_I2C_MAX_DEVS 3
extern uint32_t pios_i2c_mag_pressure_adapter_id;
#define PIOS_I2C_MAIN_ADAPTER (pios_i2c_mag_pressure_adapter_id)
#define PIOS_I2C_MAX_DEVS 3
extern uint32_t pios_i2c_pressure_adapter_id;
#define PIOS_I2C_MS5611_INTERNAL_ADAPTER (pios_i2c_pressure_adapter_id)
#define PIOS_I2C_EXTERNAL_ADAPTER (pios_i2c_pressure_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_MS4525DO_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_MS4525DO_ADAPTER (PIOS_I2C_FLEXI_ADAPTER)
// -------------------------
// PIOS_USART
//
// See also pios_board.c
// -------------------------
#define PIOS_USART_MAX_DEVS 5
#define PIOS_USART_MAX_DEVS 5
// Inverter for SBUS handling
#define PIOS_USART_INVERTER_PORT USART6
#define PIOS_USART_INVERTER_GPIO GPIOC
#define PIOS_USART_INVERTER_PIN GPIO_Pin_4
#define PIOS_USART_INVERTER_ENABLE Bit_SET
#define PIOS_USART_INVERTER_DISABLE Bit_RESET
// -------------------------
// PIOS_COM
//
// See also pios_board.c
// -------------------------
#define PIOS_COM_MAX_DEVS 4
extern uint32_t pios_com_telem_rf_id;
extern uint32_t pios_com_rf_id;
extern uint32_t pios_com_gps_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_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_RF (pios_com_rf_id)
#define PIOS_COM_BRIDGE (pios_com_bridge_id)
#define PIOS_COM_VCP (pios_com_vcp_id)
#define PIOS_COM_OSDHK (pios_com_hkosd_id)
#define PIOS_COM_MSP (pios_com_msp_id)
#define PIOS_COM_MAVLINK (pios_com_mavlink_id)
#if defined(PIOS_INCLUDE_DEBUG_CONSOLE)
extern uint32_t pios_com_debug_id;
#define PIOS_COM_DEBUG (pios_com_debug_id)
#endif /* PIOS_INCLUDE_DEBUG_CONSOLE */
#if defined(PIOS_INCLUDE_RFM22B)
extern uint32_t pios_rfm22b_id;
extern uint32_t pios_spi_telem_flash_id;
#define PIOS_RFM22_SPI_PORT (pios_spi_telem_flash_id)
#endif /* PIOS_INCLUDE_RFM22B */
#define PIOS_COM_MAX_DEVS 4
// -------------------------
// Packet Handler

View File

@ -29,11 +29,12 @@
<field name="MAVLinkSpeed" units="bps" type="enum" elements="1" options="2400,4800,9600,19200,38400,57600,115200" defaultvalue="57600"/>
<field name="USB_HIDPort" units="function" type="enum" elements="1" options="USBTelemetry,RCTransmitter,Disabled" defaultvalue="USBTelemetry"/>
<field name="USB_VCPPort" units="function" type="enum" elements="1" options="USBTelemetry,ComBridge,DebugConsole,Disabled,MAVLink" defaultvalue="Disabled"/>
<field name="RadioAuxStream" units="function" type="enum" elements="1" options="DebugConsole,Disabled,MAVLink" defaultvalue="Disabled"/>
<field name="RadioAuxStream" units="function" type="enum" elements="1" options="DebugConsole,Disabled,MAVLink,ComBridge" defaultvalue="Disabled"/>
<field name="OptionalModules" units="" type="enum" elementnames="CameraStab,CameraControl,GPS,Fault,Altitude,Airspeed,TxPID,Battery,Overo,MagBaro,OsdHk,AutoTune" options="Disabled,Enabled" defaultvalue="Disabled"/>
<field name="ADCRouting" units="" type="enum" elementnames="adc0,adc1,adc2,adc3,adc4,adc5,adc6,adc7" options="Disabled,BatteryVoltage,BatteryCurrent,AnalogAirspeed,Generic" defaultvalue="Disabled"/>
<field name="DSMxBind" units="" type="uint8" elements="1" defaultvalue="0"/>
<field name="SBusMode" units="" type="enum" elements="1" options="Normal,Non Inverted" defaultvalue="Normal"/>
<field name="WS2811LED_Out" units="" type="enum" elements="1" options="ServoOut1,ServoOut2,ServoOut3,ServoOut4,ServoOut5,ServoOut6,FlexiIOPin3,FlexiIOPin4,Disabled" defaultvalue="Disabled"
limits="%0905NE:ServoOut2:ServoOut3:ServoOut4:ServoOut5:ServoOut6:FlexiIOPin3:FlexiIOPin4;"
/>