mirror of
https://bitbucket.org/librepilot/librepilot.git
synced 2025-01-30 15:52:12 +01:00
LP-480 Moved sensors initialization to pios_board_sensors.c
This commit is contained in:
parent
c9f6ba55a0
commit
9eb1f3b5e5
@ -101,6 +101,7 @@ 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
|
||||
|
@ -67,21 +67,12 @@
|
||||
# endif /* PIOS_INCLUDE_RCVR */
|
||||
#endif /* PIOS_INCLUDE_RFM22B */
|
||||
|
||||
#ifdef PIOS_INCLUDE_ADC
|
||||
# include <pios_adc_priv.h>
|
||||
#endif
|
||||
|
||||
#ifdef PIOS_INCLUDE_MS5611
|
||||
# include <pios_ms5611.h>
|
||||
#endif
|
||||
|
||||
#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 "auxmagsettings.h"
|
||||
#include "gcsreceiver.h"
|
||||
|
||||
#ifdef PIOS_INCLUDE_GPS
|
||||
@ -118,14 +109,6 @@ uint32_t pios_com_telem_usb_id; /* USB telemetry */
|
||||
uint32_t pios_usb_rctx_id;
|
||||
#endif
|
||||
|
||||
#if defined(PIOS_INCLUDE_HMC5X83)
|
||||
# include "pios_hmc5x83.h"
|
||||
# if defined(PIOS_HMC5X83_HAS_GPIOS)
|
||||
pios_hmc5x83_dev_t pios_hmc5x83_internal_id;
|
||||
# endif
|
||||
#endif
|
||||
|
||||
|
||||
#include "pios_usb_board_data_priv.h"
|
||||
#include "pios_usb_desc_hid_cdc_priv.h"
|
||||
#include "pios_usb_desc_hid_only_priv.h"
|
||||
@ -185,7 +168,7 @@ void PIOS_BOARD_IO_Configure_USB()
|
||||
#if defined(PIOS_INCLUDE_USB_CDC)
|
||||
uint8_t hwsettings_usb_vcpport;
|
||||
HwSettingsUSB_VCPPortGet(&hwsettings_usb_vcpport);
|
||||
|
||||
|
||||
if (PIOS_USB_DESC_HID_CDC_Init()) {
|
||||
PIOS_Assert(0);
|
||||
}
|
||||
@ -297,38 +280,38 @@ struct uart_function {
|
||||
};
|
||||
|
||||
static const struct uart_function uart_function_map[] = {
|
||||
[PIOS_BOARD_IO_UART_TELEMETRY] = {
|
||||
[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] = {
|
||||
[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] = {
|
||||
[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,
|
||||
},
|
||||
|
||||
[PIOS_BOARD_IO_UART_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,
|
||||
},
|
||||
|
||||
[PIOS_BOARD_IO_UART_OSDHK] = {
|
||||
[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,
|
||||
[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,
|
||||
},
|
||||
@ -339,67 +322,67 @@ static const struct uart_function uart_function_map[] = {
|
||||
.com_tx_buf_len = PIOS_COM_DEBUGCONSOLE_TX_BUF_LEN,
|
||||
},
|
||||
#endif
|
||||
[PIOS_BOARD_IO_UART_COMBRIDGE] = {
|
||||
[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] = {
|
||||
[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] = {
|
||||
[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] = {
|
||||
[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] = {
|
||||
[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] = {
|
||||
[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] = {
|
||||
[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] = {
|
||||
[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] = {
|
||||
[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] = {
|
||||
[PIOS_BOARD_IO_UART_SBUS] = {
|
||||
.rcvr_init = &PIOS_SBus_Init_Helper,
|
||||
.rcvr_driver = &pios_sbus_rcvr_driver,
|
||||
.rcvr_group = MANUALCONTROLSETTINGS_CHANNELGROUPS_SBUS,
|
||||
@ -495,7 +478,7 @@ void PIOS_BOARD_IO_Configure_GCSRCVR()
|
||||
|
||||
#ifdef PIOS_INCLUDE_RFM22B
|
||||
|
||||
void PIOS_BOARD_IO_Configure_RFM22B(uint32_t spi_id, PIOS_BOARD_IO_RADIOAUX_Function radioaux_function)
|
||||
void PIOS_BOARD_IO_Configure_RFM22B(PIOS_BOARD_IO_RADIOAUX_Function radioaux_function)
|
||||
{
|
||||
#if defined(PIOS_INCLUDE_RFM22B)
|
||||
OPLinkSettingsInitialize();
|
||||
@ -533,11 +516,11 @@ void PIOS_BOARD_IO_Configure_RFM22B(uint32_t spi_id, PIOS_BOARD_IO_RADIOAUX_Func
|
||||
uint32_t openlrs_id;
|
||||
const struct pios_openlrs_cfg *openlrs_cfg = PIOS_BOARD_HW_DEFS_GetOpenLRSCfg(pios_board_info_blob.board_rev);
|
||||
|
||||
PIOS_OpenLRS_Init(&openlrs_id, spi_id, 0, openlrs_cfg);
|
||||
PIOS_OpenLRS_Init(&openlrs_id, PIOS_SPI_RFM22B_ADAPTER, 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);
|
||||
@ -548,7 +531,7 @@ void PIOS_BOARD_IO_Configure_RFM22B(uint32_t spi_id, PIOS_BOARD_IO_RADIOAUX_Func
|
||||
/* Configure the RFM22B device. */
|
||||
const struct pios_rfm22b_cfg *rfm22b_cfg = PIOS_BOARD_HW_DEFS_GetRfm22Cfg(pios_board_info_blob.board_rev);
|
||||
|
||||
if (PIOS_RFM22B_Init(&pios_rfm22b_id, spi_id, rfm22b_cfg->slave_num, rfm22b_cfg, oplinkSettings.RFBand)) {
|
||||
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)
|
||||
@ -646,7 +629,7 @@ void PIOS_BOARD_IO_Configure_RFM22B(uint32_t spi_id, PIOS_BOARD_IO_RADIOAUX_Func
|
||||
uint16_t mavlink_rx_size = PIOS_COM_MAVLINK_RX_BUF_LEN;
|
||||
|
||||
switch (radioaux_function) {
|
||||
default: ;
|
||||
default:;
|
||||
case PIOS_BOARD_IO_RADIOAUX_DEBUGCONSOLE:
|
||||
#ifdef PIOS_INCLUDE_DEBUG_CONSOLE
|
||||
if (PIOS_COM_Init(&pios_com_debug_id, &pios_rfm22b_aux_com_driver, pios_rfm22b_id,
|
||||
@ -655,15 +638,14 @@ void PIOS_BOARD_IO_Configure_RFM22B(uint32_t spi_id, PIOS_BOARD_IO_RADIOAUX_Func
|
||||
PIOS_Assert(0);
|
||||
}
|
||||
#endif
|
||||
break;
|
||||
break;
|
||||
case PIOS_BOARD_IO_RADIOAUX_COMBRIDGE:
|
||||
if(PIOS_COM_Init(&pios_com_bridge_id, &pios_rfm22b_aux_com_driver, pios_rfm22b_id,
|
||||
0, PIOS_COM_BRIDGE_RX_BUF_LEN,
|
||||
0, PIOS_COM_BRIDGE_TX_BUF_LEN))
|
||||
{
|
||||
if (PIOS_COM_Init(&pios_com_bridge_id, &pios_rfm22b_aux_com_driver, pios_rfm22b_id,
|
||||
0, PIOS_COM_BRIDGE_RX_BUF_LEN,
|
||||
0, PIOS_COM_BRIDGE_TX_BUF_LEN)) {
|
||||
PIOS_Assert(0);
|
||||
}
|
||||
break;
|
||||
break;
|
||||
case PIOS_BOARD_IO_RADIOAUX_MAVLINK:
|
||||
if (PIOS_COM_Init(&pios_com_mavlink_id, &pios_rfm22b_aux_com_driver, pios_rfm22b_id,
|
||||
0, mavlink_rx_size,
|
||||
@ -679,106 +661,3 @@ void PIOS_BOARD_IO_Configure_RFM22B(uint32_t spi_id, PIOS_BOARD_IO_RADIOAUX_Func
|
||||
OPLinkStatusSet(&oplinkStatus);
|
||||
}
|
||||
#endif /* ifdef PIOS_INCLUDE_RFM22B */
|
||||
|
||||
#ifdef PIOS_INCLUDE_I2C
|
||||
void PIOS_BOARD_IO_Configure_I2C(uint32_t i2c_internal_id, uint32_t i2c_external_id)
|
||||
{
|
||||
// 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, i2c_internal_id, 0);
|
||||
# ifdef PIOS_INCLUDE_WDG
|
||||
// give HMC5x83 on I2C some extra time to allow for reset, etc. if needed
|
||||
// this is not in a loop, so it is safe
|
||||
PIOS_WDG_Clear();
|
||||
# endif /* PIOS_INCLUDE_WDG */
|
||||
|
||||
#ifdef PIOS_HMC5X83_HAS_GPIOS
|
||||
pios_hmc5x83_internal_id = internal_mag;
|
||||
#endif
|
||||
// add this sensor to the sensor task's list
|
||||
PIOS_HMC5x83_Register(internal_mag, PIOS_SENSORS_TYPE_3AXIS_MAG);
|
||||
}
|
||||
|
||||
# endif /* PIOS_INCLUDE_HMC5X83_INTERNAL */
|
||||
|
||||
// internal ms5611 baro
|
||||
#if defined(PIOS_INCLUDE_MS5611)
|
||||
PIOS_MS5611_Init(PIOS_BOARD_HW_DEFS_GetMS5611Cfg(pios_board_info_blob.board_rev), i2c_internal_id);
|
||||
PIOS_MS5611_Register();
|
||||
#endif
|
||||
|
||||
// internal bmp280 baro
|
||||
// internal MPU6000 imu (i2c)
|
||||
// internal eeprom (revo nano) - NOT HERE, should be initialized earlier
|
||||
|
||||
|
||||
/* Initialize external sensors */
|
||||
|
||||
// aux mag
|
||||
# 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 = i2c_external_id;
|
||||
} else if (option == AUXMAGSETTINGS_TYPE_I2C) {
|
||||
// i2c_internal (or Sparky2/F3 dedicated I2C port)
|
||||
i2c_id = i2c_internal_id;
|
||||
}
|
||||
|
||||
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 */
|
||||
|
||||
// external ETASV3 Eagletree Airspeed v3
|
||||
// external MS4525D PixHawk Airpeed based on MS4525DO
|
||||
|
||||
// BMA180 accelerometer?
|
||||
// bmp085/bmp180 baro
|
||||
|
||||
// hmc5843 mag
|
||||
// i2c esc (?)
|
||||
// UBX DCC
|
||||
}
|
||||
#endif /* ifdef PIOS_INCLUDE_I2C */
|
||||
|
||||
#ifdef PIOS_INCLUDE_ADC
|
||||
void PIOS_BOARD_IO_Configure_ADC()
|
||||
{
|
||||
PIOS_ADC_Init(PIOS_BOARD_HW_DEFS_GetAdcCfg(pios_board_info_blob.board_rev));
|
||||
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 */
|
||||
|
187
flight/pios/common/pios_board_sensors.c
Normal file
187
flight/pios/common/pios_board_sensors.c
Normal file
@ -0,0 +1,187 @@
|
||||
/**
|
||||
******************************************************************************
|
||||
*
|
||||
* @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
|
||||
|
||||
#if defined(PIOS_INCLUDE_ADXL345)
|
||||
# include <pios_adxl345.h>
|
||||
#endif
|
||||
|
||||
#ifdef PIOS_INCLUDE_MPU9250
|
||||
# include <pios_mpu9250.h>
|
||||
# include <pios_mpu9250_config.h>
|
||||
#endif
|
||||
|
||||
#if defined(PIOS_INCLUDE_HMC5X83)
|
||||
# include "pios_hmc5x83.h"
|
||||
# if defined(PIOS_HMC5X83_HAS_GPIOS)
|
||||
pios_hmc5x83_dev_t pios_hmc5x83_internal_id;
|
||||
# endif
|
||||
#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_ADXL345
|
||||
PIOS_ADXL345_Init(PIOS_SPI_ADXL345_ADAPTER, 0);
|
||||
#endif
|
||||
|
||||
#ifdef PIOS_INCLUDE_MPU9250
|
||||
const struct pios_mpu9250_cfg *mpu9250_cfg = PIOS_BOARD_HW_DEFS_GetMPU9250Cfg(pios_board_info_blob.board_rev);
|
||||
if (mpu9250_cfg) {
|
||||
PIOS_MPU9250_Init(PIOS_SPI_MPU9250_ADAPTER, 0, mpu9250_cfg);
|
||||
PIOS_MPU9250_CONFIG_Configure();
|
||||
PIOS_MPU9250_MainRegister();
|
||||
PIOS_MPU9250_MagRegister();
|
||||
}
|
||||
#endif /* PIOS_INCLUDE_MPU9250 */
|
||||
|
||||
|
||||
// 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
|
||||
PIOS_ADC_Init(PIOS_BOARD_HW_DEFS_GetAdcCfg(pios_board_info_blob.board_rev));
|
||||
#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
|
||||
}
|
@ -320,7 +320,7 @@ 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,
|
||||
|
@ -53,4 +53,10 @@ const struct pios_bmp280_cfg *PIOS_BOARD_HW_DEFS_GetBMP280Cfg(uint32_t board_rev
|
||||
#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
|
||||
#endif /* PIOS_BOARD_HW_H */
|
||||
|
@ -112,32 +112,32 @@ extern uint32_t pios_com_rf_id; /* oplink telemetry */
|
||||
|
||||
/* HK OSD ?? */
|
||||
extern uint32_t pios_com_hkosd_id;
|
||||
#define PIOS_COM_OSDHK (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
|
||||
# define PIOS_COM_HKOSD_RX_BUF_LEN 22
|
||||
#endif
|
||||
#ifndef PIOS_COM_HKOSD_TX_BUF_LEN
|
||||
# define PIOS_COM_HKOSD_TX_BUF_LEN 22
|
||||
# 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)
|
||||
#define PIOS_COM_MSP (pios_com_msp_id)
|
||||
#ifndef PIOS_COM_MSP_TX_BUF_LEN
|
||||
# define PIOS_COM_MSP_TX_BUF_LEN 128
|
||||
# define PIOS_COM_MSP_TX_BUF_LEN 128
|
||||
#endif
|
||||
#ifndef PIOS_COM_MSP_RX_BUF_LEN
|
||||
# define PIOS_COM_MSP_RX_BUF_LEN 64
|
||||
# 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)
|
||||
#define PIOS_COM_MAVLINK (pios_com_mavlink_id)
|
||||
#ifndef PIOS_COM_MAVLINK_TX_BUF_LEN
|
||||
# define PIOS_COM_MAVLINK_TX_BUF_LEN 128
|
||||
# define PIOS_COM_MAVLINK_TX_BUF_LEN 128
|
||||
#endif
|
||||
#ifndef PIOS_COM_MAVLINK_RX_BUF_LEN
|
||||
# define PIOS_COM_MAVLINK_RX_BUF_LEN 128
|
||||
# define PIOS_COM_MAVLINK_RX_BUF_LEN 128
|
||||
#endif
|
||||
|
||||
/* HoTT Telemetry */
|
||||
@ -149,7 +149,7 @@ extern uint32_t pios_com_mavlink_id;
|
||||
# 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)
|
||||
# define PIOS_COM_HOTT (pios_com_hott_id)
|
||||
#endif
|
||||
|
||||
/* USB VCP */
|
||||
@ -192,7 +192,7 @@ typedef enum {
|
||||
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_FRSKY_SPORT_TELEMETRY, /* com */
|
||||
PIOS_BOARD_IO_UART_HOTT_BRIDGE, /* com */
|
||||
} PIOS_BOARD_IO_UART_Function;
|
||||
|
||||
@ -201,15 +201,15 @@ typedef enum {
|
||||
PIOS_BOARD_IO_RADIOAUX_MAVLINK,
|
||||
PIOS_BOARD_IO_RADIOAUX_COMBRIDGE,
|
||||
PIOS_BOARD_IO_RADIOAUX_DEBUGCONSOLE,
|
||||
// PIOS_BOARD_IO_RADIOAUX_FRSKY_SPORT_TELEMETRY,
|
||||
// PIOS_BOARD_IO_RADIOAUX_FRSKY_SPORT_TELEMETRY,
|
||||
} PIOS_BOARD_IO_RADIOAUX_Function;
|
||||
|
||||
#ifdef PIOS_INCLUDE_USB
|
||||
void PIOS_BOARD_IO_Configure_USB();
|
||||
//# if defined(PIOS_INCLUDE_USB_HID)
|
||||
//# include <pios_usb_hid_priv.h>
|
||||
//extern const struct pios_usb_hid_cfg pios_usb_hid_cfg;
|
||||
//# endif /* PIOS_INCLUDE_USB_HID */
|
||||
// # if defined(PIOS_INCLUDE_USB_HID)
|
||||
// # include <pios_usb_hid_priv.h>
|
||||
// extern const struct pios_usb_hid_cfg pios_usb_hid_cfg;
|
||||
// # endif /* PIOS_INCLUDE_USB_HID */
|
||||
#endif /* PIOS_INCLUDE_USB */
|
||||
#ifdef PIOS_INCLUDE_PWM
|
||||
void PIOS_BOARD_IO_Configure_PWM(const struct pios_pwm_cfg *pwm_cfg);
|
||||
@ -221,11 +221,7 @@ void PIOS_BOARD_IO_Configure_PPM(const struct pios_ppm_cfg *ppm_cfg);
|
||||
void PIOS_BOARD_IO_Configure_UART(const struct pios_usart_cfg *usart_cfg, PIOS_BOARD_IO_UART_Function function);
|
||||
|
||||
#ifdef PIOS_INCLUDE_RFM22B
|
||||
void PIOS_BOARD_IO_Configure_RFM22B(uint32_t spi_id, PIOS_BOARD_IO_RADIOAUX_Function function);
|
||||
#endif
|
||||
|
||||
#ifdef PIOS_INCLUDE_I2C
|
||||
void PIOS_BOARD_IO_Configure_I2C(uint32_t i2c_internal_id, uint32_t i2c_external_id);
|
||||
void PIOS_BOARD_IO_Configure_RFM22B(PIOS_BOARD_IO_RADIOAUX_Function function);
|
||||
#endif
|
||||
|
||||
#ifdef PIOS_INCLUDE_GCSRCVR
|
||||
|
33
flight/pios/inc/pios_board_sensors.h
Normal file
33
flight/pios/inc/pios_board_sensors.h
Normal 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 */
|
@ -30,20 +30,20 @@
|
||||
* 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, \
|
||||
}
|
||||
{ \
|
||||
.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_ */
|
||||
|
@ -58,11 +58,11 @@ void PIOS_SYS_Init(void)
|
||||
* 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 |
|
||||
@ -82,13 +82,13 @@ void PIOS_SYS_Init(void)
|
||||
RCC_APB1Periph_I2C1 |
|
||||
RCC_APB1Periph_I2C2 |
|
||||
RCC_APB1Periph_USB |
|
||||
// RCC_APB1Periph_CAN1 | /* bxCAN unfortunately interferes with USB */
|
||||
// RCC_APB1Periph_CAN2 |
|
||||
// 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 |
|
||||
|
@ -52,7 +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,
|
||||
.ioctl = PIOS_USART_Ioctl,
|
||||
};
|
||||
|
||||
enum pios_usart_dev_magic {
|
||||
@ -69,7 +69,7 @@ struct pios_usart_dev {
|
||||
uint32_t tx_out_context;
|
||||
|
||||
uint32_t rx_dropped;
|
||||
uint8_t irq_channel;
|
||||
uint8_t irq_channel;
|
||||
};
|
||||
|
||||
static bool PIOS_USART_validate(struct pios_usart_dev *usart_dev)
|
||||
@ -80,11 +80,11 @@ static bool PIOS_USART_validate(struct pios_usart_dev *usart_dev)
|
||||
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;
|
||||
}
|
||||
|
||||
@ -95,9 +95,9 @@ static int32_t PIOS_USART_SetIrqPrio(struct pios_usart_dev *usart_dev, uint8_t i
|
||||
.NVIC_IRQChannelPreemptionPriority = irq_prio,
|
||||
.NVIC_IRQChannelCmd = ENABLE,
|
||||
};
|
||||
|
||||
|
||||
NVIC_Init(&init);
|
||||
|
||||
|
||||
return 0;
|
||||
}
|
||||
|
||||
@ -180,7 +180,7 @@ 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;
|
||||
|
||||
/* Initialize the comm parameter structure */
|
||||
USART_StructInit(&usart_dev->init); // 9600 8n1
|
||||
@ -214,9 +214,9 @@ int32_t PIOS_USART_Init(uint32_t *usart_id, const struct pios_usart_cfg *cfg)
|
||||
usart_dev->irq_channel = USART3_IRQn;
|
||||
break;
|
||||
}
|
||||
|
||||
|
||||
PIOS_USART_SetIrqPrio(usart_dev, PIOS_IRQ_PRIO_MID);
|
||||
|
||||
|
||||
USART_ITConfig(usart_dev->cfg->regs, USART_IT_RXNE, ENABLE);
|
||||
USART_ITConfig(usart_dev->cfg->regs, USART_IT_TXE, ENABLE);
|
||||
|
||||
@ -452,28 +452,28 @@ static void PIOS_USART_generic_irq_handler(uint32_t usart_id)
|
||||
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);
|
||||
|
||||
|
||||
switch (ctl) {
|
||||
case PIOS_IOCTL_USART_SET_IRQ_PRIO:
|
||||
return PIOS_USART_SetIrqPrio(usart_dev, *(uint8_t *)param);
|
||||
|
||||
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;
|
||||
default:
|
||||
if (usart_dev->cfg->ioctl) {
|
||||
return usart_dev->cfg->ioctl(usart_id, ctl, param);
|
||||
}
|
||||
return -1;
|
||||
case PIOS_IOCTL_USART_SET_IRQ_PRIO:
|
||||
return PIOS_USART_SetIrqPrio(usart_dev, *(uint8_t *)param);
|
||||
|
||||
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;
|
||||
default:
|
||||
if (usart_dev->cfg->ioctl) {
|
||||
return usart_dev->cfg->ioctl(usart_id, ctl, param);
|
||||
}
|
||||
return -1;
|
||||
}
|
||||
|
||||
|
||||
return 0;
|
||||
}
|
||||
|
||||
|
@ -59,7 +59,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,
|
||||
.ioctl = PIOS_USART_Ioctl,
|
||||
};
|
||||
|
||||
enum pios_usart_dev_magic {
|
||||
|
@ -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(__attribute__((unused)) uint32_t board_revision)
|
||||
{
|
||||
return &pios_adc_cfg;
|
||||
}
|
||||
#endif /* if defined(PIOS_INCLUDE_ADC) */
|
||||
|
||||
#include "pios_tim_priv.h"
|
||||
@ -593,16 +598,16 @@ static const struct pios_tim_channel pios_tim_ppm_flexi_port = TIM_SERVO_CHANNEL
|
||||
#include "pios_usart_priv.h"
|
||||
|
||||
// Inverter for SBUS handling
|
||||
#define MAIN_USART_INVERTER_GPIO GPIOB
|
||||
#define MAIN_USART_INVERTER_PIN GPIO_Pin_2
|
||||
#define MAIN_USART_INVERTER_ENABLE Bit_SET
|
||||
#define MAIN_USART_INVERTER_DISABLE Bit_RESET
|
||||
#define MAIN_USART_INVERTER_GPIO GPIOB
|
||||
#define MAIN_USART_INVERTER_PIN GPIO_Pin_2
|
||||
#define MAIN_USART_INVERTER_ENABLE Bit_SET
|
||||
#define MAIN_USART_INVERTER_DISABLE Bit_RESET
|
||||
|
||||
static int32_t PIOS_BOARD_USART_Ioctl(uint32_t usart_id, uint32_t ctl, void *param);
|
||||
|
||||
static const struct pios_usart_cfg pios_usart_main_cfg = {
|
||||
.regs = USART1,
|
||||
.rx = {
|
||||
.rx = {
|
||||
.gpio = GPIOA,
|
||||
.init = {
|
||||
.GPIO_Pin = GPIO_Pin_10,
|
||||
@ -610,7 +615,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,
|
||||
@ -618,12 +623,12 @@ static const struct pios_usart_cfg pios_usart_main_cfg = {
|
||||
.GPIO_Mode = GPIO_Mode_AF_PP,
|
||||
},
|
||||
},
|
||||
.ioctl = PIOS_BOARD_USART_Ioctl,
|
||||
.ioctl = PIOS_BOARD_USART_Ioctl,
|
||||
};
|
||||
|
||||
static const struct pios_usart_cfg pios_usart_flexi_cfg = {
|
||||
.regs = USART3,
|
||||
.rx = {
|
||||
.rx = {
|
||||
.gpio = GPIOB,
|
||||
.init = {
|
||||
.GPIO_Pin = GPIO_Pin_11,
|
||||
@ -631,7 +636,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,
|
||||
@ -967,16 +972,16 @@ static const struct pios_usb_cfg pios_usb_main_cfg_cc3d = {
|
||||
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);
|
||||
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;
|
||||
}
|
||||
@ -988,7 +993,6 @@ const struct pios_usb_cfg *PIOS_BOARD_HW_DEFS_GetUsbCfg(uint32_t board_revision)
|
||||
*/
|
||||
#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,
|
||||
@ -1037,6 +1041,9 @@ static const struct pios_mpu6000_cfg pios_mpu6000_cfg = {
|
||||
.std_prescaler = PIOS_SPI_PRESCALER_64,
|
||||
.max_downsample = 2
|
||||
};
|
||||
|
||||
const struct pios_mpu6000_cfg *PIOS_BOARD_HW_DEFS_GetMPU6000Cfg(__attribute__((unused)) uint32_t board_revision)
|
||||
{
|
||||
return &pios_mpu6000_cfg;
|
||||
}
|
||||
#endif /* PIOS_INCLUDE_MPU6000 */
|
||||
|
||||
|
||||
|
@ -38,11 +38,9 @@
|
||||
#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.
|
||||
@ -91,19 +89,19 @@ static const PIOS_BOARD_IO_UART_Function flexi_function_map[] = {
|
||||
int32_t PIOS_BOARD_USART_Ioctl(uint32_t usart_id, uint32_t ctl, void *param)
|
||||
{
|
||||
const struct pios_usart_cfg *usart_cfg = PIOS_USART_GetConfig(usart_id);
|
||||
|
||||
|
||||
switch (ctl) {
|
||||
case PIOS_IOCTL_USART_SET_INVERTED:
|
||||
if (usart_cfg->regs == pios_usart_main_cfg.regs) { /* main port */
|
||||
GPIO_WriteBit(MAIN_USART_INVERTER_GPIO,
|
||||
MAIN_USART_INVERTER_PIN,
|
||||
(*(enum PIOS_USART_Inverted *)param & PIOS_USART_Inverted_Rx) ? MAIN_USART_INVERTER_ENABLE : MAIN_USART_INVERTER_DISABLE);
|
||||
|
||||
return 0;
|
||||
}
|
||||
break;
|
||||
case PIOS_IOCTL_USART_SET_INVERTED:
|
||||
if (usart_cfg->regs == pios_usart_main_cfg.regs) { /* main port */
|
||||
GPIO_WriteBit(MAIN_USART_INVERTER_GPIO,
|
||||
MAIN_USART_INVERTER_PIN,
|
||||
(*(enum PIOS_USART_Inverted *)param & PIOS_USART_Inverted_Rx) ? MAIN_USART_INVERTER_ENABLE : MAIN_USART_INVERTER_DISABLE);
|
||||
|
||||
return 0;
|
||||
}
|
||||
break;
|
||||
}
|
||||
|
||||
|
||||
return -1;
|
||||
}
|
||||
|
||||
@ -133,12 +131,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;
|
||||
@ -151,7 +149,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)) {
|
||||
@ -159,7 +157,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)) {
|
||||
@ -233,28 +231,28 @@ void PIOS_Board_Init(void)
|
||||
/* Configure FlexiPort */
|
||||
uint8_t hwsettings_flexiport;
|
||||
HwSettingsCC_FlexiPortGet(&hwsettings_flexiport);
|
||||
|
||||
|
||||
if (hwsettings_flexiport < NELEMENTS(flexi_function_map)) {
|
||||
PIOS_BOARD_IO_Configure_UART(&pios_usart_flexi_cfg, flexi_function_map[hwsettings_flexiport]);
|
||||
}
|
||||
|
||||
switch(hwsettings_flexiport) {
|
||||
case HWSETTINGS_CC_FLEXIPORT_I2C:
|
||||
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_PPM:
|
||||
break;
|
||||
case HWSETTINGS_CC_FLEXIPORT_PPM:
|
||||
#if defined(PIOS_INCLUDE_PPM_FLEXI)
|
||||
PIOS_BOARD_IO_Configure_PPM(&pios_ppm_flexi_cfg);
|
||||
PIOS_BOARD_IO_Configure_PPM(&pios_ppm_flexi_cfg);
|
||||
#endif /* PIOS_INCLUDE_PPM_FLEXI */
|
||||
break;
|
||||
break;
|
||||
}
|
||||
|
||||
/* Configure main USART port */
|
||||
|
||||
|
||||
/* Initialize inverter gpio and set it to off */
|
||||
{
|
||||
GPIO_InitTypeDef inverterGPIOInit = {
|
||||
@ -262,16 +260,16 @@ void PIOS_Board_Init(void)
|
||||
.GPIO_Mode = GPIO_Mode_Out_PP,
|
||||
.GPIO_Speed = GPIO_Speed_2MHz,
|
||||
};
|
||||
|
||||
|
||||
GPIO_Init(MAIN_USART_INVERTER_GPIO, &inverterGPIOInit);
|
||||
GPIO_WriteBit(MAIN_USART_INVERTER_GPIO,
|
||||
MAIN_USART_INVERTER_PIN,
|
||||
MAIN_USART_INVERTER_DISABLE);
|
||||
}
|
||||
|
||||
|
||||
uint8_t hwsettings_mainport;
|
||||
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]);
|
||||
}
|
||||
@ -298,7 +296,7 @@ void PIOS_Board_Init(void)
|
||||
case HWSETTINGS_CC_RCVRPORT_PPMOUTPUTSNOONESHOT:
|
||||
case HWSETTINGS_CC_RCVRPORT_PPM_PIN8ONESHOT:
|
||||
#if defined(PIOS_INCLUDE_PPM)
|
||||
PIOS_BOARD_IO_Configure_PPM((hwsettings_rcvrport == HWSETTINGS_CC_RCVRPORT_PPM_PIN8ONESHOT) ? &pios_ppm_pin8_cfg : &pios_ppm_cfg);
|
||||
PIOS_BOARD_IO_Configure_PPM((hwsettings_rcvrport == HWSETTINGS_CC_RCVRPORT_PPM_PIN8ONESHOT) ? &pios_ppm_pin8_cfg : &pios_ppm_cfg);
|
||||
#endif /* PIOS_INCLUDE_PPM */
|
||||
break;
|
||||
case HWSETTINGS_CC_RCVRPORT_PPMPWMNOONESHOT:
|
||||
@ -341,33 +339,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);
|
||||
|
||||
|
@ -116,19 +116,23 @@ 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
|
||||
|
||||
// -------------------------
|
||||
// PIOS_COM
|
||||
//
|
||||
// See also pios_board.c
|
||||
// -------------------------
|
||||
#define PIOS_COM_MAX_DEVS 3
|
||||
#define PIOS_COM_MAX_DEVS 3
|
||||
|
||||
#define PIOS_COM_TELEM_RF_RX_BUF_LEN 32
|
||||
#define PIOS_COM_TELEM_RF_TX_BUF_LEN 12
|
||||
|
@ -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);
|
||||
}
|
||||
|
||||
|
||||
@ -606,17 +606,17 @@ static const struct flashfs_logfs_cfg flashfs_internal_user_cfg = {
|
||||
* MAIN USART
|
||||
*/
|
||||
// Inverter for SBUS handling
|
||||
#define MAIN_USART_INVERTER_GPIO GPIOC
|
||||
#define MAIN_USART_INVERTER_PIN GPIO_Pin_0
|
||||
#define MAIN_USART_INVERTER_ENABLE Bit_SET
|
||||
#define MAIN_USART_INVERTER_DISABLE Bit_RESET
|
||||
#define MAIN_USART_INVERTER_GPIO GPIOC
|
||||
#define MAIN_USART_INVERTER_PIN GPIO_Pin_0
|
||||
#define MAIN_USART_INVERTER_ENABLE Bit_SET
|
||||
#define MAIN_USART_INVERTER_DISABLE Bit_RESET
|
||||
|
||||
static int32_t PIOS_BOARD_USART_Ioctl(uint32_t usart_id, uint32_t ctl, void *param);
|
||||
|
||||
static const struct pios_usart_cfg pios_usart_main_cfg = {
|
||||
.regs = USART1,
|
||||
.remap = GPIO_AF_USART1,
|
||||
.rx = {
|
||||
.rx = {
|
||||
.gpio = GPIOA,
|
||||
.init = {
|
||||
.GPIO_Pin = GPIO_Pin_10,
|
||||
@ -626,7 +626,7 @@ static const struct pios_usart_cfg pios_usart_main_cfg = {
|
||||
.GPIO_PuPd = GPIO_PuPd_UP
|
||||
},
|
||||
},
|
||||
.tx = {
|
||||
.tx = {
|
||||
.gpio = GPIOA,
|
||||
.init = {
|
||||
.GPIO_Pin = GPIO_Pin_9,
|
||||
@ -636,7 +636,7 @@ static const struct pios_usart_cfg pios_usart_main_cfg = {
|
||||
.GPIO_PuPd = GPIO_PuPd_UP
|
||||
},
|
||||
},
|
||||
.ioctl = PIOS_BOARD_USART_Ioctl,
|
||||
.ioctl = PIOS_BOARD_USART_Ioctl,
|
||||
};
|
||||
|
||||
/*
|
||||
@ -645,7 +645,7 @@ static const struct pios_usart_cfg pios_usart_main_cfg = {
|
||||
static const struct pios_usart_cfg pios_usart_flexi_cfg = {
|
||||
.regs = USART3,
|
||||
.remap = GPIO_AF_USART3,
|
||||
.rx = {
|
||||
.rx = {
|
||||
.gpio = GPIOB,
|
||||
.init = {
|
||||
.GPIO_Pin = GPIO_Pin_11,
|
||||
@ -655,7 +655,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,
|
||||
@ -671,7 +671,7 @@ static const struct pios_usart_cfg pios_usart_flexi_cfg = {
|
||||
static const struct pios_usart_cfg pios_usart_flexiio_cfg = {
|
||||
.regs = USART6,
|
||||
.remap = GPIO_AF_USART6,
|
||||
.dtr = {
|
||||
.dtr = {
|
||||
// FlexIO pin 9
|
||||
.gpio = GPIOC,
|
||||
.init = {
|
||||
@ -682,7 +682,7 @@ static const struct pios_usart_cfg pios_usart_flexiio_cfg = {
|
||||
},
|
||||
},
|
||||
|
||||
.tx = {
|
||||
.tx = {
|
||||
// * 7: PC6 = TIM8 CH1, USART6 TX
|
||||
.gpio = GPIOC,
|
||||
.init = {
|
||||
@ -692,10 +692,10 @@ static const struct pios_usart_cfg pios_usart_flexiio_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 = {
|
||||
@ -705,7 +705,7 @@ static const struct pios_usart_cfg pios_usart_flexiio_cfg = {
|
||||
.GPIO_OType = GPIO_OType_PP,
|
||||
.GPIO_PuPd = GPIO_PuPd_UP
|
||||
},
|
||||
.pin_source = GPIO_PinSource7,
|
||||
.pin_source = GPIO_PinSource7,
|
||||
}
|
||||
};
|
||||
|
||||
@ -1066,18 +1066,18 @@ static const struct pios_tim_clock_cfg tim_12_cfg = {
|
||||
#include <pios_servo_config.h>
|
||||
|
||||
static const struct pios_tim_channel pios_tim_servoport_all_pins[] = {
|
||||
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),
|
||||
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
|
||||
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(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
|
||||
};
|
||||
|
||||
@ -1140,10 +1140,10 @@ const struct pios_servo_cfg pios_servo_cfg_out_in = {
|
||||
static const struct pios_tim_channel pios_tim_rcvrport_all_channels[] = {
|
||||
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),
|
||||
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 = {
|
||||
@ -1448,7 +1448,6 @@ const struct pios_ms5611_cfg *PIOS_BOARD_HW_DEFS_GetMS5611Cfg(__attribute__((unu
|
||||
*/
|
||||
#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,
|
||||
@ -1496,6 +1495,10 @@ static const struct pios_mpu6000_cfg pios_mpu6000_cfg = {
|
||||
.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 */
|
||||
|
||||
|
||||
|
@ -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();
|
||||
|
@ -39,6 +39,7 @@
|
||||
#endif
|
||||
|
||||
#include <pios_board_io.h>
|
||||
#include <pios_board_sensors.h>
|
||||
|
||||
/*
|
||||
* Pull in the board-specific static HW definitions.
|
||||
@ -101,25 +102,25 @@ static const PIOS_BOARD_IO_UART_Function flexi_function_map[] = {
|
||||
static const PIOS_BOARD_IO_RADIOAUX_Function radioaux_function_map[] = {
|
||||
[HWSETTINGS_RADIOAUXSTREAM_DEBUGCONSOLE] = PIOS_BOARD_IO_RADIOAUX_DEBUGCONSOLE,
|
||||
[HWSETTINGS_RADIOAUXSTREAM_MAVLINK] = PIOS_BOARD_IO_RADIOAUX_MAVLINK,
|
||||
[HWSETTINGS_RADIOAUXSTREAM_COMBRIDGE] = PIOS_BOARD_IO_RADIOAUX_COMBRIDGE,
|
||||
[HWSETTINGS_RADIOAUXSTREAM_COMBRIDGE] = PIOS_BOARD_IO_RADIOAUX_COMBRIDGE,
|
||||
};
|
||||
|
||||
int32_t PIOS_BOARD_USART_Ioctl(uint32_t usart_id, uint32_t ctl, void *param)
|
||||
{
|
||||
const struct pios_usart_cfg *usart_cfg = PIOS_USART_GetConfig(usart_id);
|
||||
|
||||
|
||||
switch (ctl) {
|
||||
case PIOS_IOCTL_USART_SET_INVERTED:
|
||||
if (usart_cfg->regs == pios_usart_main_cfg.regs) { /* main port */
|
||||
GPIO_WriteBit(MAIN_USART_INVERTER_GPIO,
|
||||
MAIN_USART_INVERTER_PIN,
|
||||
(*(enum PIOS_USART_Inverted *)param & PIOS_USART_Inverted_Rx) ? MAIN_USART_INVERTER_ENABLE : MAIN_USART_INVERTER_DISABLE);
|
||||
|
||||
return 0;
|
||||
}
|
||||
break;
|
||||
case PIOS_IOCTL_USART_SET_INVERTED:
|
||||
if (usart_cfg->regs == pios_usart_main_cfg.regs) { /* main port */
|
||||
GPIO_WriteBit(MAIN_USART_INVERTER_GPIO,
|
||||
MAIN_USART_INVERTER_PIN,
|
||||
(*(enum PIOS_USART_Inverted *)param & PIOS_USART_Inverted_Rx) ? MAIN_USART_INVERTER_ENABLE : MAIN_USART_INVERTER_DISABLE);
|
||||
|
||||
return 0;
|
||||
}
|
||||
break;
|
||||
}
|
||||
|
||||
|
||||
return -1;
|
||||
}
|
||||
|
||||
@ -143,17 +144,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;
|
||||
@ -229,30 +233,28 @@ void PIOS_Board_Init(void)
|
||||
}
|
||||
|
||||
/* Configure IO ports */
|
||||
|
||||
|
||||
/* Configure FlexiPort */
|
||||
uint8_t hwsettings_flexiport;
|
||||
HwSettingsRM_FlexiPortGet(&hwsettings_flexiport);
|
||||
|
||||
|
||||
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);
|
||||
}
|
||||
|
||||
PIOS_BOARD_IO_Configure_I2C(pios_i2c_mag_pressure_adapter_id, pios_i2c_flexiport_adapter_id);
|
||||
#endif
|
||||
|
||||
#if defined(PIOS_INCLUDE_USB)
|
||||
@ -260,7 +262,7 @@ void PIOS_Board_Init(void)
|
||||
#endif
|
||||
|
||||
/* Configure main USART port */
|
||||
|
||||
|
||||
/* Initialize inverter gpio and set it to off */
|
||||
{
|
||||
GPIO_InitTypeDef inverterGPIOInit = {
|
||||
@ -270,30 +272,30 @@ void PIOS_Board_Init(void)
|
||||
.GPIO_OType = GPIO_OType_PP,
|
||||
.GPIO_PuPd = GPIO_PuPd_UP
|
||||
};
|
||||
|
||||
|
||||
GPIO_Init(MAIN_USART_INVERTER_GPIO, &inverterGPIOInit);
|
||||
GPIO_WriteBit(MAIN_USART_INVERTER_GPIO,
|
||||
MAIN_USART_INVERTER_PIN,
|
||||
MAIN_USART_INVERTER_DISABLE);
|
||||
}
|
||||
|
||||
|
||||
uint8_t hwsettings_mainport;
|
||||
HwSettingsRM_MainPortGet(&hwsettings_mainport);
|
||||
|
||||
|
||||
if (hwsettings_mainport < NELEMENTS(main_function_map)) {
|
||||
PIOS_BOARD_IO_Configure_UART(&pios_usart_main_cfg, main_function_map[hwsettings_mainport]);
|
||||
}
|
||||
|
||||
|
||||
#if defined(PIOS_INCLUDE_RFM22B)
|
||||
uint8_t hwsettings_radioaux;
|
||||
HwSettingsRadioAuxStreamGet(&hwsettings_radioaux);
|
||||
|
||||
if(hwsettings_radioaux < NELEMENTS(radioaux_function_map)) {
|
||||
if (hwsettings_radioaux < NELEMENTS(radioaux_function_map)) {
|
||||
PIOS_BOARD_IO_Configure_RFM22B(pios_spi_telem_flash_id, radioaux_function_map[hwsettings_radioaux]);
|
||||
}
|
||||
#endif /* PIOS_INCLUDE_RFM22B */
|
||||
|
||||
|
||||
|
||||
#if defined(PIOS_INCLUDE_PWM) || defined(PIOS_INCLUDE_PPM)
|
||||
|
||||
const struct pios_servo_cfg *pios_servo_cfg;
|
||||
@ -304,47 +306,47 @@ 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_PWM:
|
||||
case HWSETTINGS_RM_RCVRPORT_PWM:
|
||||
#if defined(PIOS_INCLUDE_PWM)
|
||||
/* Set up the receiver port. Later this should be optional */
|
||||
PIOS_BOARD_IO_Configure_PWM(&pios_pwm_cfg);
|
||||
/* Set up the receiver port. Later this should be optional */
|
||||
PIOS_BOARD_IO_Configure_PWM(&pios_pwm_cfg);
|
||||
#endif /* PIOS_INCLUDE_PWM */
|
||||
break;
|
||||
case HWSETTINGS_RM_RCVRPORT_PPM:
|
||||
case HWSETTINGS_RM_RCVRPORT_PPMOUTPUTS:
|
||||
case HWSETTINGS_RM_RCVRPORT_PPMPWM:
|
||||
case HWSETTINGS_RM_RCVRPORT_PPMTELEMETRY:
|
||||
case HWSETTINGS_RM_RCVRPORT_PPMDEBUGCONSOLE:
|
||||
case HWSETTINGS_RM_RCVRPORT_PPMCOMBRIDGE:
|
||||
case HWSETTINGS_RM_RCVRPORT_PPMMSP:
|
||||
case HWSETTINGS_RM_RCVRPORT_PPMMAVLINK:
|
||||
case HWSETTINGS_RM_RCVRPORT_PPMGPS:
|
||||
break;
|
||||
case HWSETTINGS_RM_RCVRPORT_PPM:
|
||||
case HWSETTINGS_RM_RCVRPORT_PPMOUTPUTS:
|
||||
case HWSETTINGS_RM_RCVRPORT_PPMPWM:
|
||||
case HWSETTINGS_RM_RCVRPORT_PPMTELEMETRY:
|
||||
case HWSETTINGS_RM_RCVRPORT_PPMDEBUGCONSOLE:
|
||||
case HWSETTINGS_RM_RCVRPORT_PPMCOMBRIDGE:
|
||||
case HWSETTINGS_RM_RCVRPORT_PPMMSP:
|
||||
case HWSETTINGS_RM_RCVRPORT_PPMMAVLINK:
|
||||
case HWSETTINGS_RM_RCVRPORT_PPMGPS:
|
||||
#if defined(PIOS_INCLUDE_PPM)
|
||||
PIOS_BOARD_IO_Configure_PPM(&pios_ppm_cfg);
|
||||
|
||||
if (hwsettings_rcvrport == HWSETTINGS_RM_RCVRPORT_PPMOUTPUTS) {
|
||||
// configure servo outputs and the remaining 5 inputs as outputs
|
||||
pios_servo_cfg = &pios_servo_cfg_out_in_ppm;
|
||||
}
|
||||
|
||||
// enable pwm on the remaining channels
|
||||
if (hwsettings_rcvrport == HWSETTINGS_RM_RCVRPORT_PPMPWM) {
|
||||
PIOS_BOARD_IO_Configure_PWM(&pios_pwm_ppm_cfg);
|
||||
}
|
||||
|
||||
break;
|
||||
PIOS_BOARD_IO_Configure_PPM(&pios_ppm_cfg);
|
||||
|
||||
if (hwsettings_rcvrport == HWSETTINGS_RM_RCVRPORT_PPMOUTPUTS) {
|
||||
// configure servo outputs and the remaining 5 inputs as outputs
|
||||
pios_servo_cfg = &pios_servo_cfg_out_in_ppm;
|
||||
}
|
||||
|
||||
// enable pwm on the remaining channels
|
||||
if (hwsettings_rcvrport == HWSETTINGS_RM_RCVRPORT_PPMPWM) {
|
||||
PIOS_BOARD_IO_Configure_PWM(&pios_pwm_ppm_cfg);
|
||||
}
|
||||
|
||||
break;
|
||||
#endif /* PIOS_INCLUDE_PPM */
|
||||
case HWSETTINGS_RM_RCVRPORT_OUTPUTS:
|
||||
// configure only the servo outputs
|
||||
pios_servo_cfg = &pios_servo_cfg_out_in;
|
||||
break;
|
||||
case HWSETTINGS_RM_RCVRPORT_OUTPUTS:
|
||||
// configure only the servo outputs
|
||||
pios_servo_cfg = &pios_servo_cfg_out_in;
|
||||
break;
|
||||
}
|
||||
#ifdef PIOS_INCLUDE_GCSRCVR
|
||||
PIOS_BOARD_IO_Configure_GCSRCVR();
|
||||
@ -357,16 +359,12 @@ void PIOS_Board_Init(void)
|
||||
PIOS_DEBUG_Init(pios_tim_servoport_all_pins, NELEMENTS(pios_tim_servoport_all_pins));
|
||||
#endif
|
||||
|
||||
#if defined(PIOS_INCLUDE_MPU6000)
|
||||
PIOS_MPU6000_Init(pios_spi_gyro_id, 0, &pios_mpu6000_cfg);
|
||||
PIOS_MPU6000_CONFIG_Configure();
|
||||
PIOS_MPU6000_Register();
|
||||
#endif
|
||||
|
||||
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 = {
|
||||
@ -377,8 +375,6 @@ void PIOS_Board_Init(void)
|
||||
.GPIO_OType = GPIO_OType_OD,
|
||||
};
|
||||
GPIO_Init(GPIOA, &gpioA8);
|
||||
|
||||
PIOS_BOARD_IO_Configure_ADC();
|
||||
#endif // PIOS_INCLUDE_ADC
|
||||
}
|
||||
|
||||
|
@ -85,29 +85,34 @@
|
||||
// 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
|
||||
@ -121,7 +126,7 @@ extern uint32_t pios_i2c_flexiport_adapter_id;
|
||||
//
|
||||
// See also pios_board.c
|
||||
// -------------------------
|
||||
#define PIOS_COM_MAX_DEVS 4
|
||||
#define PIOS_COM_MAX_DEVS 4
|
||||
|
||||
// -------------------------
|
||||
// Packet Handler
|
||||
|
@ -693,7 +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,
|
||||
.rx = {
|
||||
.rx = {
|
||||
.gpio = GPIOA,
|
||||
.init = {
|
||||
.GPIO_Pin = GPIO_Pin_10,
|
||||
@ -701,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,
|
||||
@ -713,7 +713,7 @@ static const struct pios_usart_cfg pios_usart_main_cfg = {
|
||||
|
||||
static const struct pios_usart_cfg pios_usart_flexi_cfg = {
|
||||
.regs = USART3,
|
||||
.rx = {
|
||||
.rx = {
|
||||
.gpio = GPIOB,
|
||||
.init = {
|
||||
.GPIO_Pin = GPIO_Pin_11,
|
||||
@ -721,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,
|
||||
|
@ -464,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);
|
||||
}
|
||||
|
||||
|
||||
@ -599,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);
|
||||
}
|
||||
|
||||
|
||||
@ -794,10 +794,10 @@ static const struct flashfs_logfs_cfg flashfs_internal_cfg = {
|
||||
*/
|
||||
|
||||
// Inverter for SBUS handling
|
||||
#define MAIN_USART_INVERTER_GPIO GPIOC
|
||||
#define MAIN_USART_INVERTER_PIN GPIO_Pin_0
|
||||
#define MAIN_USART_INVERTER_ENABLE Bit_SET
|
||||
#define MAIN_USART_INVERTER_DISABLE Bit_RESET
|
||||
#define MAIN_USART_INVERTER_GPIO GPIOC
|
||||
#define MAIN_USART_INVERTER_PIN GPIO_Pin_0
|
||||
#define MAIN_USART_INVERTER_ENABLE Bit_SET
|
||||
#define MAIN_USART_INVERTER_DISABLE Bit_RESET
|
||||
|
||||
static int32_t PIOS_BOARD_USART_Ioctl(uint32_t usart_id, uint32_t ctl, void *param);
|
||||
|
||||
@ -1254,18 +1254,18 @@ static const struct pios_tim_clock_cfg tim_12_cfg = {
|
||||
#include <pios_servo_config.h>
|
||||
|
||||
static const struct pios_tim_channel pios_tim_servoport_all_pins[] = {
|
||||
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),
|
||||
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
|
||||
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(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
|
||||
};
|
||||
|
||||
@ -1328,10 +1328,10 @@ const struct pios_servo_cfg pios_servo_cfg_out_in = {
|
||||
static const struct pios_tim_channel pios_tim_rcvrport_all_channels[] = {
|
||||
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),
|
||||
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 = {
|
||||
@ -1738,7 +1738,6 @@ const struct pios_ms5611_cfg *PIOS_BOARD_HW_DEFS_GetMS5611Cfg(__attribute__((unu
|
||||
*/
|
||||
#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,
|
||||
@ -1789,4 +1788,10 @@ static const struct pios_mpu6000_cfg pios_mpu6000_cfg = {
|
||||
.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 */
|
||||
|
@ -38,6 +38,7 @@
|
||||
#endif
|
||||
|
||||
#include <pios_board_io.h>
|
||||
#include <pios_board_sensors.h>
|
||||
|
||||
/*
|
||||
* Pull in the board-specific static HW definitions.
|
||||
@ -100,7 +101,7 @@ static const PIOS_BOARD_IO_UART_Function flexi_function_map[] = {
|
||||
static const PIOS_BOARD_IO_RADIOAUX_Function radioaux_function_map[] = {
|
||||
[HWSETTINGS_RADIOAUXSTREAM_DEBUGCONSOLE] = PIOS_BOARD_IO_RADIOAUX_DEBUGCONSOLE,
|
||||
[HWSETTINGS_RADIOAUXSTREAM_MAVLINK] = PIOS_BOARD_IO_RADIOAUX_MAVLINK,
|
||||
[HWSETTINGS_RADIOAUXSTREAM_COMBRIDGE] = PIOS_BOARD_IO_RADIOAUX_COMBRIDGE,
|
||||
[HWSETTINGS_RADIOAUXSTREAM_COMBRIDGE] = PIOS_BOARD_IO_RADIOAUX_COMBRIDGE,
|
||||
};
|
||||
|
||||
|
||||
@ -143,12 +144,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);
|
||||
}
|
||||
|
||||
@ -157,7 +158,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);
|
||||
}
|
||||
|
||||
@ -246,8 +247,6 @@ void PIOS_Board_Init(void)
|
||||
}
|
||||
PIOS_DELAY_WaitmS(50);
|
||||
}
|
||||
|
||||
PIOS_BOARD_IO_Configure_I2C(pios_i2c_mag_pressure_adapter_id, pios_i2c_flexiport_adapter_id);
|
||||
#endif
|
||||
|
||||
/* Moved this here to allow DSM binding on flexiport */
|
||||
@ -273,7 +272,7 @@ void PIOS_Board_Init(void)
|
||||
.GPIO_OType = GPIO_OType_PP,
|
||||
.GPIO_PuPd = GPIO_PuPd_UP
|
||||
};
|
||||
|
||||
|
||||
GPIO_Init(MAIN_USART_INVERTER_GPIO, &inverterGPIOInit);
|
||||
GPIO_WriteBit(MAIN_USART_INVERTER_GPIO,
|
||||
MAIN_USART_INVERTER_PIN,
|
||||
@ -290,9 +289,9 @@ void PIOS_Board_Init(void)
|
||||
#if defined(PIOS_INCLUDE_RFM22B)
|
||||
uint8_t hwsettings_radioaux;
|
||||
HwSettingsRadioAuxStreamGet(&hwsettings_radioaux);
|
||||
|
||||
if(hwsettings_radioaux < NELEMENTS(radioaux_function_map)) {
|
||||
PIOS_BOARD_IO_Configure_RFM22B(pios_spi_telem_flash_id, radioaux_function_map[hwsettings_radioaux]);
|
||||
|
||||
if (hwsettings_radioaux < NELEMENTS(radioaux_function_map)) {
|
||||
PIOS_BOARD_IO_Configure_RFM22B(radioaux_function_map[hwsettings_radioaux]);
|
||||
}
|
||||
#endif /* PIOS_INCLUDE_RFM22B */
|
||||
|
||||
@ -359,16 +358,12 @@ void PIOS_Board_Init(void)
|
||||
PIOS_DEBUG_Init(pios_tim_servoport_all_pins, NELEMENTS(pios_tim_servoport_all_pins));
|
||||
#endif
|
||||
|
||||
#if defined(PIOS_INCLUDE_MPU6000)
|
||||
PIOS_MPU6000_Init(pios_spi_gyro_id, 0, &pios_mpu6000_cfg);
|
||||
PIOS_MPU6000_CONFIG_Configure();
|
||||
PIOS_MPU6000_Register();
|
||||
#endif
|
||||
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]);
|
||||
}
|
||||
@ -384,8 +379,6 @@ void PIOS_Board_Init(void)
|
||||
.GPIO_OType = GPIO_OType_OD,
|
||||
};
|
||||
GPIO_Init(GPIOA, &gpioA8);
|
||||
|
||||
PIOS_BOARD_IO_Configure_ADC();
|
||||
#endif // PIOS_INCLUDE_ADC
|
||||
|
||||
DEBUG_PRINTF(2, "Board complete\r\n");
|
||||
|
@ -103,30 +103,36 @@
|
||||
// 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
|
||||
@ -140,7 +146,7 @@ extern uint32_t pios_i2c_flexiport_adapter_id;
|
||||
//
|
||||
// See also pios_board.c
|
||||
// -------------------------
|
||||
#define PIOS_COM_MAX_DEVS 4
|
||||
#define PIOS_COM_MAX_DEVS 4
|
||||
|
||||
// -------------------------
|
||||
// Packet Handler
|
||||
|
@ -42,29 +42,29 @@
|
||||
* 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
|
||||
#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_ENABLE Bit_SET
|
||||
#define MAIN_USART_INVERTER_DISABLE Bit_RESET
|
||||
#define MAIN_USART_INVERTER_GPIO GPIOC
|
||||
#define MAIN_USART_INVERTER_PIN GPIO_Pin_15
|
||||
#define MAIN_USART_INVERTER_ENABLE Bit_SET
|
||||
#define MAIN_USART_INVERTER_DISABLE Bit_RESET
|
||||
|
||||
#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 +115,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,11 +229,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);
|
||||
}
|
||||
|
||||
#endif /* PIOS_INCLUDE_SPI */
|
||||
@ -249,7 +249,7 @@ static int32_t PIOS_BOARD_USART_Ioctl(uint32_t usart_id, uint32_t ctl, void *par
|
||||
static const struct pios_usart_cfg pios_usart_main_cfg = {
|
||||
.regs = MAIN_USART_REGS,
|
||||
.remap = MAIN_USART_REMAP,
|
||||
.rx = {
|
||||
.rx = {
|
||||
.gpio = MAIN_USART_RX_GPIO,
|
||||
.init = {
|
||||
.GPIO_Pin = MAIN_USART_RX_PIN,
|
||||
@ -259,7 +259,7 @@ static const struct pios_usart_cfg pios_usart_main_cfg = {
|
||||
.GPIO_PuPd = GPIO_PuPd_UP
|
||||
},
|
||||
},
|
||||
.tx = {
|
||||
.tx = {
|
||||
.gpio = MAIN_USART_TX_GPIO,
|
||||
.init = {
|
||||
.GPIO_Pin = MAIN_USART_TX_PIN,
|
||||
@ -278,7 +278,7 @@ static const struct pios_usart_cfg pios_usart_main_cfg = {
|
||||
static const struct pios_usart_cfg pios_usart_flexi_cfg = {
|
||||
.regs = FLEXI_USART_REGS,
|
||||
.remap = FLEXI_USART_REMAP,
|
||||
.rx = {
|
||||
.rx = {
|
||||
.gpio = FLEXI_USART_RX_GPIO,
|
||||
.init = {
|
||||
.GPIO_Pin = FLEXI_USART_RX_PIN,
|
||||
@ -288,7 +288,7 @@ static const struct pios_usart_cfg pios_usart_flexi_cfg = {
|
||||
.GPIO_PuPd = GPIO_PuPd_UP
|
||||
},
|
||||
},
|
||||
.tx = {
|
||||
.tx = {
|
||||
.gpio = FLEXI_USART_TX_GPIO,
|
||||
.init = {
|
||||
.GPIO_Pin = FLEXI_USART_TX_PIN,
|
||||
@ -298,15 +298,15 @@ static const struct pios_usart_cfg pios_usart_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,
|
||||
// },
|
||||
// },
|
||||
// .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,
|
||||
// },
|
||||
// },
|
||||
};
|
||||
|
||||
#if defined(PIOS_INCLUDE_COM)
|
||||
@ -329,7 +329,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,
|
||||
@ -382,17 +382,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);
|
||||
}
|
||||
|
||||
|
||||
@ -937,7 +937,6 @@ struct pios_flash_eeprom_cfg flash_main_chip_cfg = {
|
||||
*/
|
||||
|
||||
|
||||
|
||||
#if defined(PIOS_INCLUDE_ADC)
|
||||
|
||||
#include "pios_adc_priv.h"
|
||||
@ -1019,7 +1018,6 @@ const struct pios_ms5611_cfg *PIOS_BOARD_HW_DEFS_GetMS5611Cfg(__attribute__((unu
|
||||
*/
|
||||
#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,
|
||||
@ -1070,4 +1068,9 @@ static const struct pios_mpu9250_cfg pios_mpu9250_cfg = {
|
||||
.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 */
|
||||
|
@ -41,6 +41,7 @@
|
||||
#endif
|
||||
|
||||
#include <pios_board_io.h>
|
||||
#include <pios_board_sensors.h>
|
||||
|
||||
/*
|
||||
* Pull in the board-specific static HW definitions.
|
||||
@ -97,19 +98,19 @@ static const PIOS_BOARD_IO_UART_Function main_function_map[] = {
|
||||
int32_t PIOS_BOARD_USART_Ioctl(uint32_t usart_id, uint32_t ctl, void *param)
|
||||
{
|
||||
const struct pios_usart_cfg *usart_cfg = PIOS_USART_GetConfig(usart_id);
|
||||
|
||||
|
||||
switch (ctl) {
|
||||
case PIOS_IOCTL_USART_SET_INVERTED:
|
||||
if (usart_cfg->regs == pios_usart_main_cfg.regs) { /* main port */
|
||||
GPIO_WriteBit(MAIN_USART_INVERTER_GPIO,
|
||||
MAIN_USART_INVERTER_PIN,
|
||||
(*(enum PIOS_USART_Inverted *)param & PIOS_USART_Inverted_Rx) ? MAIN_USART_INVERTER_ENABLE : MAIN_USART_INVERTER_DISABLE);
|
||||
|
||||
return 0;
|
||||
}
|
||||
break;
|
||||
case PIOS_IOCTL_USART_SET_INVERTED:
|
||||
if (usart_cfg->regs == pios_usart_main_cfg.regs) { /* main port */
|
||||
GPIO_WriteBit(MAIN_USART_INVERTER_GPIO,
|
||||
MAIN_USART_INVERTER_PIN,
|
||||
(*(enum PIOS_USART_Inverted *)param & PIOS_USART_Inverted_Rx) ? MAIN_USART_INVERTER_ENABLE : MAIN_USART_INVERTER_DISABLE);
|
||||
|
||||
return 0;
|
||||
}
|
||||
break;
|
||||
}
|
||||
|
||||
|
||||
return -1;
|
||||
}
|
||||
|
||||
@ -129,18 +130,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
|
||||
@ -150,7 +145,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);
|
||||
}
|
||||
|
||||
@ -213,7 +208,7 @@ void PIOS_Board_Init(void)
|
||||
HwSettingsSetDefaults(HwSettingsHandle(), 0);
|
||||
AlarmsSet(SYSTEMALARMS_ALARM_BOOTFAULT, SYSTEMALARMS_ALARM_CRITICAL);
|
||||
}
|
||||
|
||||
|
||||
#if defined(PIOS_INCLUDE_USB)
|
||||
PIOS_BOARD_IO_Configure_USB();
|
||||
#endif
|
||||
@ -221,21 +216,21 @@ void PIOS_Board_Init(void)
|
||||
/* Configure FlexiPort */
|
||||
uint8_t hwsettings_flexiport;
|
||||
HwSettingsRM_FlexiPortGet(&hwsettings_flexiport);
|
||||
|
||||
|
||||
if (hwsettings_flexiport < NELEMENTS(flexi_function_map)) {
|
||||
PIOS_BOARD_IO_Configure_UART(&pios_usart_flexi_cfg, flexi_function_map[hwsettings_flexiport]);
|
||||
}
|
||||
|
||||
/* Configure main USART port */
|
||||
|
||||
|
||||
/* Initialize inverter gpio and set it to off */
|
||||
{
|
||||
GPIO_InitTypeDef inverterGPIOInit = {
|
||||
.GPIO_Pin = MAIN_USART_INVERTER_PIN,
|
||||
.GPIO_Speed = GPIO_Speed_2MHz,
|
||||
.GPIO_Mode = GPIO_Mode_OUT,
|
||||
.GPIO_OType = GPIO_OType_PP,
|
||||
.GPIO_PuPd = GPIO_PuPd_UP
|
||||
.GPIO_Pin = MAIN_USART_INVERTER_PIN,
|
||||
.GPIO_Speed = GPIO_Speed_2MHz,
|
||||
.GPIO_Mode = GPIO_Mode_OUT,
|
||||
.GPIO_OType = GPIO_OType_PP,
|
||||
.GPIO_PuPd = GPIO_PuPd_UP
|
||||
};
|
||||
|
||||
GPIO_Init(MAIN_USART_INVERTER_GPIO, &inverterGPIOInit);
|
||||
@ -243,10 +238,10 @@ void PIOS_Board_Init(void)
|
||||
MAIN_USART_INVERTER_PIN,
|
||||
MAIN_USART_INVERTER_DISABLE);
|
||||
}
|
||||
|
||||
|
||||
uint8_t hwsettings_mainport;
|
||||
HwSettingsRM_MainPortGet(&hwsettings_mainport);
|
||||
|
||||
|
||||
if (hwsettings_mainport < NELEMENTS(main_function_map)) {
|
||||
PIOS_BOARD_IO_Configure_UART(&pios_usart_main_cfg, main_function_map[hwsettings_mainport]);
|
||||
}
|
||||
@ -317,16 +312,7 @@ void PIOS_Board_Init(void)
|
||||
|
||||
PIOS_DELAY_WaitmS(50);
|
||||
|
||||
#if defined(PIOS_INCLUDE_ADC)
|
||||
PIOS_BOARD_IO_Configure_ADC();
|
||||
#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
|
||||
PIOS_BOARD_Sensors_Configure();
|
||||
|
||||
// Attach the board config check hook
|
||||
SANITYCHECK_AttachHook(&RevoNanoConfigHook);
|
||||
|
@ -103,30 +103,32 @@
|
||||
// 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
|
||||
@ -140,7 +142,7 @@ extern uint32_t pios_i2c_flexiport_adapter_id;
|
||||
//
|
||||
// See also pios_board.c
|
||||
// -------------------------
|
||||
#define PIOS_COM_MAX_DEVS 4
|
||||
#define PIOS_COM_MAX_DEVS 4
|
||||
// -------------------------
|
||||
// Packet Handler
|
||||
// -------------------------
|
||||
|
@ -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);
|
||||
}
|
||||
|
||||
|
||||
@ -549,7 +549,7 @@ static const struct flashfs_logfs_cfg flashfs_internal_cfg = {
|
||||
static const struct pios_usart_cfg pios_usart_main_cfg = {
|
||||
.regs = USART1,
|
||||
.remap = GPIO_AF_USART1,
|
||||
.rx = {
|
||||
.rx = {
|
||||
.gpio = GPIOA,
|
||||
.init = {
|
||||
.GPIO_Pin = GPIO_Pin_10,
|
||||
@ -559,7 +559,7 @@ static const struct pios_usart_cfg pios_usart_main_cfg = {
|
||||
.GPIO_PuPd = GPIO_PuPd_UP
|
||||
},
|
||||
},
|
||||
.tx = {
|
||||
.tx = {
|
||||
.gpio = GPIOA,
|
||||
.init = {
|
||||
.GPIO_Pin = GPIO_Pin_9,
|
||||
@ -577,7 +577,7 @@ static const struct pios_usart_cfg pios_usart_main_cfg = {
|
||||
static const struct pios_usart_cfg pios_usart_flexi_cfg = {
|
||||
.regs = USART3,
|
||||
.remap = GPIO_AF_USART3,
|
||||
.rx = {
|
||||
.rx = {
|
||||
.gpio = GPIOB,
|
||||
.init = {
|
||||
.GPIO_Pin = GPIO_Pin_11,
|
||||
@ -587,7 +587,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,
|
||||
@ -605,10 +605,10 @@ static const struct pios_usart_cfg pios_usart_flexi_cfg = {
|
||||
*/
|
||||
|
||||
// Inverter for SBUS handling
|
||||
#define RCVR_USART_INVERTER_GPIO GPIOC
|
||||
#define RCVR_USART_INVERTER_PIN GPIO_Pin_4
|
||||
#define RCVR_USART_INVERTER_ENABLE Bit_SET
|
||||
#define RCVR_USART_INVERTER_DISABLE Bit_RESET
|
||||
#define RCVR_USART_INVERTER_GPIO GPIOC
|
||||
#define RCVR_USART_INVERTER_PIN GPIO_Pin_4
|
||||
#define RCVR_USART_INVERTER_ENABLE Bit_SET
|
||||
#define RCVR_USART_INVERTER_DISABLE Bit_RESET
|
||||
|
||||
static int32_t PIOS_BOARD_USART_Ioctl(uint32_t usart_id, uint32_t ctl, void *param);
|
||||
|
||||
@ -616,7 +616,7 @@ static int32_t PIOS_BOARD_USART_Ioctl(uint32_t usart_id, uint32_t ctl, void *par
|
||||
static const struct pios_usart_cfg pios_usart_rcvr_cfg = {
|
||||
.regs = USART6,
|
||||
.remap = GPIO_AF_USART6,
|
||||
.rx = {
|
||||
.rx = {
|
||||
.gpio = GPIOC,
|
||||
.init = {
|
||||
.GPIO_Pin = GPIO_Pin_7,
|
||||
@ -626,7 +626,7 @@ static const struct pios_usart_cfg pios_usart_rcvr_cfg = {
|
||||
.GPIO_PuPd = GPIO_PuPd_UP
|
||||
},
|
||||
},
|
||||
.ioctl = PIOS_BOARD_USART_Ioctl,
|
||||
.ioctl = PIOS_BOARD_USART_Ioctl,
|
||||
};
|
||||
|
||||
#if defined(PIOS_INCLUDE_COM)
|
||||
@ -642,14 +642,14 @@ static const struct pios_usart_cfg pios_usart_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,
|
||||
@ -702,17 +702,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);
|
||||
}
|
||||
|
||||
|
||||
@ -788,8 +788,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 */
|
||||
|
||||
@ -1307,7 +1307,6 @@ const struct pios_ms5611_cfg *PIOS_BOARD_HW_DEFS_GetMS5611Cfg(__attribute__((unu
|
||||
*/
|
||||
#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,
|
||||
@ -1358,5 +1357,9 @@ static const struct pios_mpu9250_cfg pios_mpu9250_cfg = {
|
||||
.std_prescaler = PIOS_SPI_PRESCALER_64,
|
||||
.max_downsample = 26,
|
||||
};
|
||||
#endif /* PIOS_INCLUDE_MPU9250 */
|
||||
|
||||
const struct pios_mpu9250_cfg *PIOS_BOARD_HW_DEFS_GetMPU9250Cfg(__attribute__((unused)) uint32_t board_revision)
|
||||
{
|
||||
return &pios_mpu9250_cfg;
|
||||
}
|
||||
#endif /* PIOS_INCLUDE_MPU9250 */
|
||||
|
@ -41,7 +41,7 @@
|
||||
#endif
|
||||
|
||||
#include <pios_board_io.h>
|
||||
|
||||
#include <pios_board_sensors.h>
|
||||
|
||||
/*
|
||||
* Pull in the board-specific static HW definitions.
|
||||
@ -57,24 +57,24 @@ uintptr_t pios_uavo_settings_fs_id;
|
||||
uintptr_t pios_user_fs_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_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,
|
||||
};
|
||||
|
||||
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_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,
|
||||
[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,
|
||||
};
|
||||
|
||||
static const PIOS_BOARD_IO_UART_Function flexi_function_map[] = {
|
||||
@ -96,25 +96,25 @@ static const PIOS_BOARD_IO_UART_Function flexi_function_map[] = {
|
||||
static const PIOS_BOARD_IO_RADIOAUX_Function radioaux_function_map[] = {
|
||||
[HWSETTINGS_RADIOAUXSTREAM_DEBUGCONSOLE] = PIOS_BOARD_IO_RADIOAUX_DEBUGCONSOLE,
|
||||
[HWSETTINGS_RADIOAUXSTREAM_MAVLINK] = PIOS_BOARD_IO_RADIOAUX_MAVLINK,
|
||||
[HWSETTINGS_RADIOAUXSTREAM_COMBRIDGE] = PIOS_BOARD_IO_RADIOAUX_COMBRIDGE,
|
||||
[HWSETTINGS_RADIOAUXSTREAM_COMBRIDGE] = PIOS_BOARD_IO_RADIOAUX_COMBRIDGE,
|
||||
};
|
||||
|
||||
int32_t PIOS_BOARD_USART_Ioctl(uint32_t usart_id, uint32_t ctl, void *param)
|
||||
{
|
||||
const struct pios_usart_cfg *usart_cfg = PIOS_USART_GetConfig(usart_id);
|
||||
|
||||
|
||||
switch (ctl) {
|
||||
case PIOS_IOCTL_USART_SET_INVERTED:
|
||||
if (usart_cfg->regs == pios_usart_rcvr_cfg.regs) { /* rcvr port */
|
||||
GPIO_WriteBit(RCVR_USART_INVERTER_GPIO,
|
||||
RCVR_USART_INVERTER_PIN,
|
||||
(*(enum PIOS_USART_Inverted *)param & PIOS_USART_Inverted_Rx) ? RCVR_USART_INVERTER_ENABLE : RCVR_USART_INVERTER_DISABLE);
|
||||
|
||||
return 0;
|
||||
}
|
||||
break;
|
||||
case PIOS_IOCTL_USART_SET_INVERTED:
|
||||
if (usart_cfg->regs == pios_usart_rcvr_cfg.regs) { /* rcvr port */
|
||||
GPIO_WriteBit(RCVR_USART_INVERTER_GPIO,
|
||||
RCVR_USART_INVERTER_PIN,
|
||||
(*(enum PIOS_USART_Inverted *)param & PIOS_USART_Inverted_Rx) ? RCVR_USART_INVERTER_ENABLE : RCVR_USART_INVERTER_DISABLE);
|
||||
|
||||
return 0;
|
||||
}
|
||||
break;
|
||||
}
|
||||
|
||||
|
||||
return -1;
|
||||
}
|
||||
|
||||
@ -140,12 +140,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);
|
||||
}
|
||||
|
||||
@ -154,7 +154,7 @@ void PIOS_Board_Init(void)
|
||||
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);
|
||||
}
|
||||
|
||||
@ -224,26 +224,24 @@ void PIOS_Board_Init(void)
|
||||
/* Configure FlexiPort */
|
||||
uint8_t hwsettings_flexiport;
|
||||
HwSettingsSPK2_FlexiPortGet(&hwsettings_flexiport);
|
||||
|
||||
|
||||
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)) {
|
||||
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);
|
||||
}
|
||||
PIOS_DELAY_WaitmS(50);
|
||||
}
|
||||
|
||||
PIOS_BOARD_IO_Configure_I2C(pios_i2c_mag_pressure_adapter_id, pios_i2c_flexiport_adapter_id);
|
||||
#endif
|
||||
|
||||
/* Moved this here to allow binding on flexiport */
|
||||
@ -259,16 +257,17 @@ void PIOS_Board_Init(void)
|
||||
|
||||
uint8_t hwsettings_mainport;
|
||||
HwSettingsSPK2_MainPortGet(&hwsettings_mainport);
|
||||
|
||||
if (hwsettings_mainport < NELEMENTS(main_function_map)) {
|
||||
PIOS_BOARD_IO_Configure_UART(&pios_usart_main_cfg, main_function_map[hwsettings_mainport]);
|
||||
}
|
||||
|
||||
|
||||
#if defined(PIOS_INCLUDE_RFM22B)
|
||||
uint8_t hwsettings_radioaux;
|
||||
HwSettingsRadioAuxStreamGet(&hwsettings_radioaux);
|
||||
|
||||
if(hwsettings_radioaux < NELEMENTS(radioaux_function_map)) {
|
||||
PIOS_BOARD_IO_Configure_RFM22B(pios_spi_telem_flash_id, radioaux_function_map[hwsettings_radioaux]);
|
||||
|
||||
if (hwsettings_radioaux < NELEMENTS(radioaux_function_map)) {
|
||||
PIOS_BOARD_IO_Configure_RFM22B(radioaux_function_map[hwsettings_radioaux]);
|
||||
}
|
||||
#endif /* PIOS_INCLUDE_RFM22B */
|
||||
|
||||
@ -281,7 +280,7 @@ void PIOS_Board_Init(void)
|
||||
.GPIO_OType = GPIO_OType_PP,
|
||||
.GPIO_PuPd = GPIO_PuPd_UP
|
||||
};
|
||||
|
||||
|
||||
GPIO_Init(RCVR_USART_INVERTER_GPIO, &inverterGPIOInit);
|
||||
GPIO_WriteBit(RCVR_USART_INVERTER_GPIO,
|
||||
RCVR_USART_INVERTER_PIN,
|
||||
@ -292,16 +291,16 @@ void PIOS_Board_Init(void)
|
||||
// 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);
|
||||
|
||||
|
||||
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)
|
||||
if(hwsettings_rcvrport == HWSETTINGS_SPK2_RCVRPORT_PPM) {
|
||||
if (hwsettings_rcvrport == HWSETTINGS_SPK2_RCVRPORT_PPM) {
|
||||
PIOS_BOARD_IO_Configure_PPM(&pios_ppm_cfg);
|
||||
}
|
||||
#endif
|
||||
@ -316,12 +315,7 @@ void PIOS_Board_Init(void)
|
||||
PIOS_DEBUG_Init(pios_tim_servoport_all_pins, NELEMENTS(pios_tim_servoport_all_pins));
|
||||
#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
|
||||
PIOS_BOARD_Sensors_Configure();
|
||||
|
||||
#ifdef PIOS_INCLUDE_WS2811
|
||||
HwSettingsWS2811LED_OutOptions ws2811_pin_settings;
|
||||
@ -342,10 +336,7 @@ void PIOS_Board_Init(void)
|
||||
.GPIO_OType = GPIO_OType_OD,
|
||||
};
|
||||
GPIO_Init(GPIOA, &gpioA8);
|
||||
|
||||
PIOS_BOARD_IO_Configure_ADC();
|
||||
#endif /* PIOS_INCLUDE_ADC */
|
||||
|
||||
}
|
||||
|
||||
/**
|
||||
|
@ -105,30 +105,35 @@
|
||||
// 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
|
||||
@ -142,7 +147,7 @@ extern uint32_t pios_i2c_flexiport_adapter_id;
|
||||
//
|
||||
// See also pios_board.c
|
||||
// -------------------------
|
||||
#define PIOS_COM_MAX_DEVS 4
|
||||
#define PIOS_COM_MAX_DEVS 4
|
||||
|
||||
// -------------------------
|
||||
// Packet Handler
|
||||
|
Loading…
x
Reference in New Issue
Block a user