mirror of
https://bitbucket.org/librepilot/librepilot.git
synced 2025-02-20 10:54:14 +01:00
LP-480 More work in progress.
This commit is contained in:
parent
ddc4f3d855
commit
5cebebe33b
@ -62,7 +62,7 @@
|
||||
#include <pios_notify.h>
|
||||
#include <pios_task_monitor.h>
|
||||
#include <pios_board_init.h>
|
||||
|
||||
#include <pios_board_io.h>
|
||||
|
||||
#ifdef PIOS_INCLUDE_INSTRUMENTATION
|
||||
#include <instrumentation.h>
|
||||
|
@ -354,6 +354,17 @@ static const struct uart_function uart_function_map[] = {
|
||||
.com_rx_buf_len = PIOS_COM_HKOSD_RX_BUF_LEN,
|
||||
.com_tx_buf_len = PIOS_COM_HKOSD_TX_BUF_LEN,
|
||||
},
|
||||
#ifdef PIOS_INCLUDE_DEBUG_CONSOLE
|
||||
[PIOS_BOARD_IO_UART_DEBUGCONSOLE] = {
|
||||
.com_id = &pios_com_debug_id,
|
||||
.com_tx_buf_len = PIOS_COM_DEBUGCONSOLE_TX_BUF_LEN,
|
||||
},
|
||||
#endif
|
||||
[PIOS_BOARD_IO_UART_COMBRIDGE] = {
|
||||
.com_id = &pios_com_bridge_id,
|
||||
.com_rx_buf_len = PIOS_COM_BRIDGE_RX_BUF_LEN,
|
||||
.com_tx_buf_len = PIOS_COM_BRIDGE_TX_BUF_LEN,
|
||||
},
|
||||
#ifdef PIOS_INCLUDE_RCVR
|
||||
# ifdef PIOS_INCLUDE_IBUS
|
||||
[PIOS_BOARD_IO_UART_IBUS] = {
|
||||
@ -505,19 +516,7 @@ void PIOS_BOARD_IO_Configure_GCSRCVR()
|
||||
|
||||
#ifdef PIOS_INCLUDE_RFM22B
|
||||
|
||||
#if defined(PIOS_INCLUDE_OPLINKRCVR) && defined(PIOS_INCLUDE_RCVR)
|
||||
static void PIOS_Board_PPM_callback(const int16_t *channels)
|
||||
{
|
||||
OPLinkReceiverData opl_rcvr;
|
||||
|
||||
for (uint8_t i = 0; i < OPLINKRECEIVER_CHANNEL_NUMELEM; ++i) {
|
||||
opl_rcvr.Channel[i] = (i < RFM22B_PPM_NUM_CHANNELS) ? channels[i] : PIOS_RCVR_TIMEOUT;
|
||||
}
|
||||
OPLinkReceiverSet(&opl_rcvr);
|
||||
}
|
||||
#endif /* PIOS_INCLUDE_OPLINKRCVR && PIOS_INCLUDE_RCVR */
|
||||
|
||||
void PIOS_BOARD_IO_Configure_RFM22B()
|
||||
void PIOS_BOARD_IO_Configure_RFM22B(uint32_t spi_id, PIOS_BOARD_IO_RADIOAUX_Function radioaux_function)
|
||||
{
|
||||
#if defined(PIOS_INCLUDE_RFM22B)
|
||||
OPLinkSettingsInitialize();
|
||||
@ -547,7 +546,6 @@ void PIOS_BOARD_IO_Configure_RFM22B()
|
||||
(oplinkSettings.LinkType == OPLINKSETTINGS_LINKTYPE_DATAANDCONTROL));
|
||||
bool ppm_mode = ((oplinkSettings.LinkType == OPLINKSETTINGS_LINKTYPE_CONTROL) ||
|
||||
(oplinkSettings.LinkType == OPLINKSETTINGS_LINKTYPE_DATAANDCONTROL));
|
||||
bool ppm_only = (oplinkSettings.LinkType == OPLINKSETTINGS_LINKTYPE_CONTROL);
|
||||
bool is_enabled = ((oplinkSettings.Protocol != OPLINKSETTINGS_PROTOCOL_DISABLED) &&
|
||||
((oplinkSettings.MaxRFPower != OPLINKSETTINGS_MAXRFPOWER_0) || openlrs));
|
||||
if (is_enabled) {
|
||||
@ -556,22 +554,22 @@ void PIOS_BOARD_IO_Configure_RFM22B()
|
||||
uint32_t openlrs_id;
|
||||
const struct pios_openlrs_cfg *openlrs_cfg = PIOS_BOARD_HW_DEFS_GetOpenLRSCfg(pios_board_info_blob.board_rev);
|
||||
|
||||
PIOS_OpenLRS_Init(&openlrs_id, PIOS_RFM22_SPI_PORT, 0, openlrs_cfg);
|
||||
{
|
||||
uint32_t openlrsrcvr_id;
|
||||
PIOS_OpenLRS_Rcvr_Init(&openlrsrcvr_id, openlrs_id);
|
||||
uint32_t openlrsrcvr_rcvr_id;
|
||||
if (PIOS_RCVR_Init(&openlrsrcvr_rcvr_id, &pios_openlrs_rcvr_driver, openlrsrcvr_id)) {
|
||||
PIOS_Assert(0);
|
||||
}
|
||||
pios_rcvr_group_map[MANUALCONTROLSETTINGS_CHANNELGROUPS_OPENLRS] = openlrsrcvr_rcvr_id;
|
||||
uint32_t openlrs_id;
|
||||
PIOS_OpenLRS_Init(&openlrs_id, spi_id, 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);
|
||||
}
|
||||
#endif /* PIOS_INCLUDE_OPENLRS_RCVR && PIOS_INCLUDE_RCVR */
|
||||
} else {
|
||||
/* Configure the RFM22B device. */
|
||||
const struct pios_rfm22b_cfg *rfm22b_cfg = PIOS_BOARD_HW_DEFS_GetRfm22Cfg(pios_board_info_blob.board_rev);
|
||||
|
||||
if (PIOS_RFM22B_Init(&pios_rfm22b_id, PIOS_RFM22_SPI_PORT, rfm22b_cfg->slave_num, rfm22b_cfg, oplinkSettings.RFBand)) {
|
||||
if (PIOS_RFM22B_Init(&pios_rfm22b_id, spi_id, rfm22b_cfg->slave_num, rfm22b_cfg, oplinkSettings.RFBand)) {
|
||||
PIOS_Assert(0);
|
||||
}
|
||||
|
||||
@ -622,12 +620,6 @@ void PIOS_BOARD_IO_Configure_RFM22B()
|
||||
PIOS_RFM22B_SetXtalCap(pios_rfm22b_id, oplinkSettings.RFXtalCap);
|
||||
PIOS_RFM22B_SetChannelConfig(pios_rfm22b_id, datarate, oplinkSettings.MinChannel, oplinkSettings.MaxChannel, is_coordinator, data_mode, ppm_mode);
|
||||
|
||||
#if defined(PIOS_INCLUDE_OPLINKRCVR) && defined(PIOS_INCLUDE_RCVR)
|
||||
/* Set the PPM callback if we should be receiving PPM. */
|
||||
if (ppm_mode || (ppm_only && !is_coordinator)) {
|
||||
PIOS_RFM22B_SetPPMCallback(pios_rfm22b_id, PIOS_Board_PPM_callback);
|
||||
}
|
||||
#endif
|
||||
/* Set the modem Tx power level */
|
||||
switch (oplinkSettings.MaxRFPower) {
|
||||
case OPLINKSETTINGS_MAXRFPOWER_125:
|
||||
@ -665,22 +657,32 @@ void PIOS_BOARD_IO_Configure_RFM22B()
|
||||
// TODO: this is in preparation for full mavlink support and is used by LP-368
|
||||
uint16_t mavlink_rx_size = PIOS_COM_MAVLINK_RX_BUF_LEN;
|
||||
|
||||
uint8_t hwsettings_radioaux;
|
||||
HwSettingsRadioAuxStreamGet(&hwsettings_radioaux);
|
||||
|
||||
switch (hwsettings_radioaux) {
|
||||
case HWSETTINGS_RADIOAUXSTREAM_DEBUGCONSOLE:
|
||||
case HWSETTINGS_RADIOAUXSTREAM_DISABLED:
|
||||
break;
|
||||
case HWSETTINGS_RADIOAUXSTREAM_MAVLINK:
|
||||
{
|
||||
switch (radioaux_function) {
|
||||
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,
|
||||
0, 0,
|
||||
0, PIOS_COM_DEBUGCONSOLE_TX_BUF_LEN)) {
|
||||
PIOS_Assert(0);
|
||||
}
|
||||
#endif
|
||||
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))
|
||||
{
|
||||
PIOS_Assert(0);
|
||||
}
|
||||
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,
|
||||
0, PIOS_COM_BRIDGE_TX_BUF_LEN)) {
|
||||
PIOS_Assert(0);
|
||||
}
|
||||
}
|
||||
}
|
||||
}
|
||||
} else {
|
||||
oplinkStatus.LinkState = OPLINKSTATUS_LINKSTATE_DISABLED;
|
||||
|
@ -331,11 +331,12 @@ const struct pios_usb_hid_cfg pios_usb_hid_cfg = {
|
||||
.data_rx_ep = 1,
|
||||
.data_tx_ep = 1,
|
||||
};
|
||||
|
||||
#ifdef PIOS_INCLUDE_USB_RCTX
|
||||
const struct pios_usb_rctx_cfg pios_usb_rctx_cfg = {
|
||||
.data_if = 2,
|
||||
.data_tx_ep = 1,
|
||||
};
|
||||
#endif
|
||||
|
||||
int32_t PIOS_USB_DESC_HID_CDC_Init(void)
|
||||
{
|
||||
|
@ -98,7 +98,8 @@ extern uint32_t pios_com_telem_rf_id;
|
||||
|
||||
/* RFM22B telemetry */
|
||||
#ifdef PIOS_INCLUDE_RFM22B
|
||||
extern uint32_t pios_com_rf_id;
|
||||
extern uint32_t pios_rfm22b_id; /* RFM22B handle */
|
||||
extern uint32_t pios_com_rf_id; /* oplink telemetry */
|
||||
# define PIOS_COM_RF (pios_com_rf_id)
|
||||
# ifndef PIOS_COM_RFM22B_RF_RX_BUF_LEN
|
||||
# define PIOS_COM_RFM22B_RF_RX_BUF_LEN 512
|
||||
@ -179,10 +180,34 @@ 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_Function;
|
||||
|
||||
typedef enum {
|
||||
PIOS_BOARD_IO_RADIOAUX_NONE,
|
||||
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_Function;
|
||||
|
||||
typedef enum {
|
||||
PIOS_BOARD_IO_USB_HID_NONE,
|
||||
PIOS_BOARD_IO_USB_HID_TELEMETRY,
|
||||
PIOS_BOARD_IO_USB_HID_RCTX,
|
||||
} PIOS_BOARD_IO_USB_HID_Function;
|
||||
|
||||
typedef enum {
|
||||
PIOS_BOARD_IO_USB_CDC_NONE,
|
||||
PIOS_BOARD_IO_USB_CDC_TELEMETRY,
|
||||
PIOS_BOARD_IO_USB_CDC_COMBRIDGE,
|
||||
PIOS_BOARD_IO_USB_CDC_MAVLINK,
|
||||
PIOS_BOARD_IO_USB_CDC_DEBUGCONSOLE,
|
||||
// PIOS_BOARD_IO_USB_CDC_MSP,
|
||||
} PIOS_BOARD_IO_USB_CDC_Function;
|
||||
|
||||
#ifdef PIOS_INCLUDE_USB
|
||||
void PIOS_BOARD_IO_Configure_USB();
|
||||
void PIOS_BOARD_IO_Configure_USB(PIOS_BOARD_IO_USB_HID_Function hid_function, PIOS_BOARD_IO_USB_CDC_Function cdc_function);
|
||||
# if defined(PIOS_INCLUDE_USB_HID)
|
||||
# include <pios_usb_hid_priv.h>
|
||||
extern const struct pios_usb_hid_cfg pios_usb_hid_cfg;
|
||||
@ -198,7 +223,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();
|
||||
void PIOS_BOARD_IO_Configure_RFM22B(uint32_t spi_id, PIOS_BOARD_IO_RADIOAUX_Function function);
|
||||
#endif
|
||||
|
||||
#ifdef PIOS_INCLUDE_I2C
|
||||
|
@ -33,13 +33,17 @@
|
||||
#include <stdint.h>
|
||||
#include <pios_usb_hid_priv.h>
|
||||
#include <pios_usb_cdc_priv.h>
|
||||
#include <pios_usb_rctx_priv.h>
|
||||
#ifdef PIOS_INCLUDE_USB_RCTX
|
||||
# include <pios_usb_rctx_priv.h>
|
||||
#endif
|
||||
|
||||
extern int32_t PIOS_USB_DESC_HID_CDC_Init(void);
|
||||
|
||||
extern const struct pios_usb_cdc_cfg pios_usb_cdc_cfg;
|
||||
extern const struct pios_usb_hid_cfg pios_usb_hid_cfg;
|
||||
#ifdef PIOS_INCLUDE_USB_RCTX
|
||||
extern const struct pios_usb_rctx_cfg pios_usb_rctx_cfg;
|
||||
#endif
|
||||
|
||||
#endif /* PIOS_USB_DESC_HID_CDC_PRIV_H */
|
||||
|
||||
|
@ -98,6 +98,11 @@ static const PIOS_BOARD_IO_UART_Function flexi_function_map[] = {
|
||||
[HWSETTINGS_RM_FLEXIPORT_MAVLINK] = PIOS_BOARD_IO_UART_MAVLINK,
|
||||
};
|
||||
|
||||
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,
|
||||
};
|
||||
|
||||
int32_t PIOS_BOARD_USART_Ioctl(uint32_t usart_id, uint32_t ctl, void *param)
|
||||
{
|
||||
@ -280,7 +285,12 @@ void PIOS_Board_Init(void)
|
||||
}
|
||||
|
||||
#if defined(PIOS_INCLUDE_RFM22B)
|
||||
PIOS_BOARD_IO_Configure_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]);
|
||||
}
|
||||
#endif /* PIOS_INCLUDE_RFM22B */
|
||||
|
||||
|
||||
|
@ -693,22 +693,6 @@ const struct pios_ppm_out_cfg pios_flexi_ppm_out_cfg = {
|
||||
*/
|
||||
static const struct pios_usart_cfg pios_usart_main_cfg = {
|
||||
.regs = USART1,
|
||||
.init = {
|
||||
.USART_BaudRate = 57600,
|
||||
.USART_WordLength = USART_WordLength_8b,
|
||||
.USART_Parity = USART_Parity_No,
|
||||
.USART_StopBits = USART_StopBits_1,
|
||||
.USART_HardwareFlowControl = USART_HardwareFlowControl_None,
|
||||
.USART_Mode = USART_Mode_Rx | USART_Mode_Tx,
|
||||
},
|
||||
.irq = {
|
||||
.init = {
|
||||
.NVIC_IRQChannel = USART1_IRQn,
|
||||
.NVIC_IRQChannelPreemptionPriority = PIOS_IRQ_PRIO_HIGH,
|
||||
.NVIC_IRQChannelSubPriority = 0,
|
||||
.NVIC_IRQChannelCmd = ENABLE,
|
||||
},
|
||||
},
|
||||
.rx = {
|
||||
.gpio = GPIOA,
|
||||
.init = {
|
||||
@ -729,22 +713,6 @@ static const struct pios_usart_cfg pios_usart_main_cfg = {
|
||||
|
||||
static const struct pios_usart_cfg pios_usart_flexi_cfg = {
|
||||
.regs = USART3,
|
||||
.init = {
|
||||
.USART_BaudRate = 57600,
|
||||
.USART_WordLength = USART_WordLength_8b,
|
||||
.USART_Parity = USART_Parity_No,
|
||||
.USART_StopBits = USART_StopBits_1,
|
||||
.USART_HardwareFlowControl = USART_HardwareFlowControl_None,
|
||||
.USART_Mode = USART_Mode_Rx | USART_Mode_Tx,
|
||||
},
|
||||
.irq = {
|
||||
.init = {
|
||||
.NVIC_IRQChannel = USART3_IRQn,
|
||||
.NVIC_IRQChannelPreemptionPriority = PIOS_IRQ_PRIO_MID,
|
||||
.NVIC_IRQChannelSubPriority = 0,
|
||||
.NVIC_IRQChannelCmd = ENABLE,
|
||||
},
|
||||
},
|
||||
.rx = {
|
||||
.gpio = GPIOB,
|
||||
.init = {
|
||||
@ -839,29 +807,6 @@ static const struct pios_usb_cfg pios_usb_main_cfg = {
|
||||
|
||||
#endif /* PIOS_INCLUDE_COM_MSG */
|
||||
|
||||
#if defined(PIOS_INCLUDE_USB_HID)
|
||||
#include <pios_usb_hid_priv.h>
|
||||
|
||||
const struct pios_usb_hid_cfg pios_usb_hid_cfg = {
|
||||
.data_if = 2,
|
||||
.data_rx_ep = 1,
|
||||
.data_tx_ep = 1,
|
||||
};
|
||||
#endif /* PIOS_INCLUDE_USB_HID */
|
||||
|
||||
#if defined(PIOS_INCLUDE_USB_CDC)
|
||||
#include <pios_usb_cdc_priv.h>
|
||||
|
||||
const struct pios_usb_cdc_cfg pios_usb_cdc_cfg = {
|
||||
.ctrl_if = 0,
|
||||
.ctrl_tx_ep = 2,
|
||||
|
||||
.data_if = 1,
|
||||
.data_rx_ep = 3,
|
||||
.data_tx_ep = 3,
|
||||
};
|
||||
#endif /* PIOS_INCLUDE_USB_CDC */
|
||||
|
||||
#if defined(PIOS_INCLUDE_FLASH_EEPROM)
|
||||
#include <pios_eeprom.h>
|
||||
|
||||
|
@ -97,6 +97,12 @@ static const PIOS_BOARD_IO_UART_Function flexi_function_map[] = {
|
||||
[HWSETTINGS_RM_FLEXIPORT_MAVLINK] = PIOS_BOARD_IO_UART_MAVLINK,
|
||||
};
|
||||
|
||||
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,
|
||||
};
|
||||
|
||||
|
||||
int32_t PIOS_BOARD_USART_Ioctl(uint32_t usart_id, uint32_t ctl, void *param)
|
||||
{
|
||||
@ -282,7 +288,12 @@ void PIOS_Board_Init(void)
|
||||
}
|
||||
|
||||
#if defined(PIOS_INCLUDE_RFM22B)
|
||||
PIOS_BOARD_IO_Configure_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]);
|
||||
}
|
||||
#endif /* PIOS_INCLUDE_RFM22B */
|
||||
|
||||
#if defined(PIOS_INCLUDE_PWM) || defined(PIOS_INCLUDE_PPM)
|
||||
|
@ -93,6 +93,12 @@ static const PIOS_BOARD_IO_UART_Function flexi_function_map[] = {
|
||||
[HWSETTINGS_SPK2_FLEXIPORT_MAVLINK] = PIOS_BOARD_IO_UART_MAVLINK,
|
||||
};
|
||||
|
||||
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,
|
||||
};
|
||||
|
||||
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);
|
||||
@ -258,7 +264,12 @@ void PIOS_Board_Init(void)
|
||||
}
|
||||
|
||||
#if defined(PIOS_INCLUDE_RFM22B)
|
||||
PIOS_BOARD_IO_Configure_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]);
|
||||
}
|
||||
#endif /* PIOS_INCLUDE_RFM22B */
|
||||
|
||||
/* Initialize inverter gpio and set it to off */
|
||||
|
@ -29,7 +29,7 @@
|
||||
<field name="MAVLinkSpeed" units="bps" type="enum" elements="1" options="2400,4800,9600,19200,38400,57600,115200" defaultvalue="57600"/>
|
||||
<field name="USB_HIDPort" units="function" type="enum" elements="1" options="USBTelemetry,RCTransmitter,Disabled" defaultvalue="USBTelemetry"/>
|
||||
<field name="USB_VCPPort" units="function" type="enum" elements="1" options="USBTelemetry,ComBridge,DebugConsole,Disabled,MAVLink" defaultvalue="Disabled"/>
|
||||
<field name="RadioAuxStream" units="function" type="enum" elements="1" options="DebugConsole,Disabled,MAVLink" defaultvalue="Disabled"/>
|
||||
<field name="RadioAuxStream" units="function" type="enum" elements="1" options="DebugConsole,Disabled,MAVLink,ComBridge" defaultvalue="Disabled"/>
|
||||
|
||||
<field name="OptionalModules" units="" type="enum" elementnames="CameraStab,CameraControl,GPS,Fault,Altitude,Airspeed,TxPID,Battery,Overo,MagBaro,OsdHk,AutoTune" options="Disabled,Enabled" defaultvalue="Disabled"/>
|
||||
<field name="ADCRouting" units="" type="enum" elementnames="adc0,adc1,adc2,adc3,adc4,adc5,adc6,adc7" options="Disabled,BatteryVoltage,BatteryCurrent,AnalogAirspeed,Generic" defaultvalue="Disabled"/>
|
||||
|
Loading…
x
Reference in New Issue
Block a user