1
0
mirror of https://bitbucket.org/librepilot/librepilot.git synced 2025-01-19 04:52:12 +01:00

LP-480 Removed RadioAuxStream function from PIOS_BOARD_IO_Configure_RFM22B(), added another function to configure radioaux from hwsettings (revo & sparky2 only).

This commit is contained in:
Vladimir Zidar 2017-04-24 16:10:18 +02:00
parent bb68ed2c5a
commit 3d876d7035
13 changed files with 142 additions and 340 deletions

View File

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

View File

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

View File

@ -84,7 +84,8 @@ uint32_t pios_com_telem_rf_id; /* Serial port telemetry */
#ifdef PIOS_INCLUDE_RFM22B
uint32_t pios_rfm22b_id; /* RFM22B handle */
uint32_t pios_com_rf_id; /* RFM22B telemetry */
uint32_t pios_com_pri_radio_id; /* oplink primary com stream */
uint32_t pios_com_aux_radio_id; /* oplink aux com stream */
#endif
#ifdef PIOS_INCLUDE_OPENLRS
@ -402,6 +403,24 @@ static const struct uart_function uart_function_map[] = {
#endif /* PIOS_INCLUDE_RCVR */
};
void PIOS_BOARD_IO_Configure_UART_COM(const struct pios_usart_cfg *hw_config,
uint16_t rx_buf_len,
uint16_t tx_buf_len,
uint32_t *com_id)
{
uint32_t usart_id;
if (PIOS_USART_Init(&usart_id, hw_config)) {
PIOS_Assert(0);
}
if (PIOS_COM_Init(com_id, &pios_usart_com_driver, usart_id,
0, rx_buf_len,
0, tx_buf_len)) {
PIOS_Assert(0);
}
}
void PIOS_BOARD_IO_Configure_UART(const struct pios_usart_cfg *hw_config, PIOS_BOARD_IO_UART_Function function)
{
if (function >= NELEMENTS(uart_function_map)) {
@ -409,17 +428,10 @@ void PIOS_BOARD_IO_Configure_UART(const struct pios_usart_cfg *hw_config, PIOS_B
}
if (uart_function_map[function].com_id) {
uint32_t usart_id;
if (PIOS_USART_Init(&usart_id, hw_config)) {
PIOS_Assert(0);
}
if (PIOS_COM_Init(uart_function_map[function].com_id, &pios_usart_com_driver, usart_id,
0, uart_function_map[function].com_rx_buf_len,
0, uart_function_map[function].com_tx_buf_len)) {
PIOS_Assert(0);
}
PIOS_BOARD_IO_Configure_UART_COM(hw_config,
uart_function_map[function].com_rx_buf_len,
uart_function_map[function].com_tx_buf_len,
uart_function_map[function].com_id);
}
#ifdef PIOS_INCLUDE_RCVR
else if (uart_function_map[function].rcvr_init) {
@ -446,7 +458,7 @@ void PIOS_BOARD_IO_Configure_UART(const struct pios_usart_cfg *hw_config, PIOS_B
}
#ifdef PIOS_INCLUDE_PWM
void PIOS_BOARD_IO_Configure_PWM(const struct pios_pwm_cfg *pwm_cfg)
void PIOS_BOARD_IO_Configure_PWM_RCVR(const struct pios_pwm_cfg *pwm_cfg)
{
/* Set up the receiver port. Later this should be optional */
uint32_t pios_pwm_id;
@ -462,7 +474,7 @@ void PIOS_BOARD_IO_Configure_PWM(const struct pios_pwm_cfg *pwm_cfg)
#endif /* PIOS_INCLUDE_PWM */
#ifdef PIOS_INCLUDE_PPM
void PIOS_BOARD_IO_Configure_PPM(const struct pios_ppm_cfg *ppm_cfg)
void PIOS_BOARD_IO_Configure_PPM_RCVR(const struct pios_ppm_cfg *ppm_cfg)
{
uint32_t pios_ppm_id;
@ -477,7 +489,7 @@ void PIOS_BOARD_IO_Configure_PPM(const struct pios_ppm_cfg *ppm_cfg)
#endif /* PIOS_INCLUDE_PPM */
#ifdef PIOS_INCLUDE_GCSRCVR
void PIOS_BOARD_IO_Configure_GCSRCVR()
void PIOS_BOARD_IO_Configure_GCS_RCVR()
{
GCSReceiverInitialize();
uint32_t pios_gcsrcvr_id;
@ -492,7 +504,7 @@ void PIOS_BOARD_IO_Configure_GCSRCVR()
#ifdef PIOS_INCLUDE_RFM22B
void PIOS_BOARD_IO_Configure_RFM22B(PIOS_BOARD_IO_RADIOAUX_Function radioaux_function)
void PIOS_BOARD_IO_Configure_RFM22B()
{
#if defined(PIOS_INCLUDE_RFM22B)
OPLinkSettingsInitialize();
@ -558,9 +570,16 @@ void PIOS_BOARD_IO_Configure_RFM22B(PIOS_BOARD_IO_RADIOAUX_Function radioaux_fun
#endif /* PIOS_INCLUDE_OPLINKRCVR && PIOS_INCLUDE_RCVR */
/* Configure the radio com interface */
if (PIOS_COM_Init(&pios_com_rf_id, &pios_rfm22b_com_driver, pios_rfm22b_id,
0, PIOS_COM_RFM22B_RF_RX_BUF_LEN,
0, PIOS_COM_RFM22B_RF_TX_BUF_LEN)) {
if (PIOS_COM_Init(&pios_com_pri_radio_id, &pios_rfm22b_com_driver, pios_rfm22b_id,
0, PIOS_COM_PRI_RADIO_RX_BUF_LEN,
0, PIOS_COM_PRI_RADIO_TX_BUF_LEN)) {
PIOS_Assert(0);
}
// Initialize the aux radio com interface
if (PIOS_COM_Init(&pios_com_aux_radio_id, &pios_rfm22b_aux_com_driver, pios_rfm22b_id,
0, PIOS_COM_AUX_RADIO_RX_BUF_LEN,
0, PIOS_COM_AUX_RADIO_TX_BUF_LEN)) {
PIOS_Assert(0);
}
@ -637,35 +656,6 @@ void PIOS_BOARD_IO_Configure_RFM22B(PIOS_BOARD_IO_RADIOAUX_Function radioaux_fun
/* Reinitialize the modem. */
PIOS_RFM22B_Reinit(pios_rfm22b_id);
// TODO: this is in preparation for full mavlink support and is used by LP-368
uint16_t mavlink_rx_size = PIOS_COM_MAVLINK_RX_BUF_LEN;
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;
@ -673,4 +663,24 @@ void PIOS_BOARD_IO_Configure_RFM22B(PIOS_BOARD_IO_RADIOAUX_Function radioaux_fun
OPLinkStatusSet(&oplinkStatus);
}
void PIOS_BOARD_IO_Configure_RadioAuxStream(HwSettingsRadioAuxStreamOptions radioaux)
{
switch (radioaux) {
case HWSETTINGS_RADIOAUXSTREAM_DEBUGCONSOLE:
#ifdef PIOS_INCLUDE_DEBUG_CONSOLE
pios_com_debug_id = pios_com_aux_radio_id;
#endif
break;
case HWSETTINGS_RADIOAUXSTREAM_MAVLINK:
pios_com_mavlink_id = pios_com_aux_radio_id;
break;
case HWSETTINGS_RADIOAUXSTREAM_COMBRIDGE:
pios_com_bridge_id = pios_com_aux_radio_id;
break;
case HWSETTINGS_RADIOAUXSTREAM_DISABLED:
break;
}
}
#endif /* ifdef PIOS_INCLUDE_RFM22B */

View File

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

View File

@ -91,22 +91,31 @@ extern uint32_t pios_com_telem_usb_id;
extern uint32_t pios_com_telem_rf_id;
#define PIOS_COM_TELEM_RF (pios_com_telem_rf_id)
#ifndef PIOS_COM_TELEM_RF_RX_BUF_LEN
# define PIOS_COM_TELEM_RF_RX_BUF_LEN 512
# define PIOS_COM_TELEM_RF_RX_BUF_LEN 128
#endif
#ifndef PIOS_COM_TELEM_RF_TX_BUF_LEN
# define PIOS_COM_TELEM_RF_TX_BUF_LEN 512
# define PIOS_COM_TELEM_RF_TX_BUF_LEN 128
#endif
/* RFM22B telemetry */
#ifdef PIOS_INCLUDE_RFM22B
extern uint32_t pios_rfm22b_id; /* RFM22B handle */
extern uint32_t pios_com_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
extern uint32_t pios_com_pri_radio_id; /* oplink primary com stream */
extern uint32_t pios_com_aux_radio_id; /* oplink aux com stream */
# define PIOS_COM_RF (pios_com_pri_radio_id)
# define PIOS_COM_PRI_RADIO (pios_com_pri_radio_id)
# define PIOS_COM_AUX_RADIO (pios_com_aux_radio_id)
# ifndef PIOS_COM_PRI_RADIO_RX_BUF_LEN
# define PIOS_COM_PRI_RADIO_RX_BUF_LEN 128
# endif
# ifndef PIOS_COM_RFM22B_RF_TX_BUF_LEN
# define PIOS_COM_RFM22B_RF_TX_BUF_LEN 512
# ifndef PIOS_COM_PRI_RADIO_TX_BUF_LEN
# define PIOS_COM_PRI_RADIO_TX_BUF_LEN 128
# endif
# ifndef PIOS_COM_AUX_RADIO_RX_BUF_LEN
# define PIOS_COM_AUX_RADIO_RX_BUF_LEN 128
# endif
# ifndef PIOS_COM_AUX_RADIO_TX_BUF_LEN
# define PIOS_COM_AUX_RADIO_TX_BUF_LEN 128
# endif
#endif
@ -201,13 +210,6 @@ typedef enum {
PIOS_BOARD_IO_UART_HOTT_BRIDGE, /* com */
} PIOS_BOARD_IO_UART_Function;
typedef enum {
PIOS_BOARD_IO_RADIOAUX_NONE = 0,
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;
#ifdef PIOS_INCLUDE_USB
# ifndef BOOTLOADER
@ -234,22 +236,26 @@ void PIOS_BOARD_IO_Configure_USB_Function(PIOS_BOARD_IO_USB_HID_Function hid_fun
# endif // ifndef BOOTLOADER
#endif // ifdef PIOS_INCLUDE_USB
#ifdef PIOS_INCLUDE_PWM
void PIOS_BOARD_IO_Configure_PWM(const struct pios_pwm_cfg *pwm_cfg);
void PIOS_BOARD_IO_Configure_PWM_RCVR(const struct pios_pwm_cfg *pwm_cfg);
#endif
#ifdef PIOS_INCLUDE_PPM
void PIOS_BOARD_IO_Configure_PPM(const struct pios_ppm_cfg *ppm_cfg);
void PIOS_BOARD_IO_Configure_PPM_RCVR(const struct pios_ppm_cfg *ppm_cfg);
#endif
#ifdef PIOS_INCLUDE_USART
void PIOS_BOARD_IO_Configure_UART(const struct pios_usart_cfg *usart_cfg, PIOS_BOARD_IO_UART_Function function);
void PIOS_BOARD_IO_Configure_UART_COM(const struct pios_usart_cfg *hw_config,
uint16_t rx_buf_len,
uint16_t tx_buf_len,
uint32_t *com_id);
#endif
#ifdef PIOS_INCLUDE_RFM22B
void PIOS_BOARD_IO_Configure_RFM22B(PIOS_BOARD_IO_RADIOAUX_Function function);
void PIOS_BOARD_IO_Configure_RFM22B();
void PIOS_BOARD_IO_Configure_RadioAuxStream(HwSettingsRadioAuxStreamOptions radioaux); /* not for OPLM */
#endif
#ifdef PIOS_INCLUDE_GCSRCVR
void PIOS_BOARD_IO_Configure_GCSRCVR();
void PIOS_BOARD_IO_Configure_GCS_RCVR();
#endif
#endif /* PIOS_BOARD_IO_H */

View File

@ -246,7 +246,7 @@ void PIOS_Board_Init(void)
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_RCVR(&pios_ppm_flexi_cfg);
#endif /* PIOS_INCLUDE_PPM_FLEXI */
break;
}
@ -289,23 +289,23 @@ void PIOS_Board_Init(void)
break;
case HWSETTINGS_CC_RCVRPORT_PWMNOONESHOT:
#if defined(PIOS_INCLUDE_PWM)
PIOS_BOARD_IO_Configure_PWM(&pios_pwm_cfg);
PIOS_BOARD_IO_Configure_PWM_RCVR(&pios_pwm_cfg);
#endif /* PIOS_INCLUDE_PWM */
break;
case HWSETTINGS_CC_RCVRPORT_PPMNOONESHOT:
case HWSETTINGS_CC_RCVRPORT_PPMOUTPUTSNOONESHOT:
case HWSETTINGS_CC_RCVRPORT_PPM_PIN8ONESHOT:
#if defined(PIOS_INCLUDE_PPM)
PIOS_BOARD_IO_Configure_PPM((hwsettings_rcvrport == HWSETTINGS_CC_RCVRPORT_PPM_PIN8ONESHOT) ? &pios_ppm_pin8_cfg : &pios_ppm_cfg);
PIOS_BOARD_IO_Configure_PPM_RCVR((hwsettings_rcvrport == HWSETTINGS_CC_RCVRPORT_PPM_PIN8ONESHOT) ? &pios_ppm_pin8_cfg : &pios_ppm_cfg);
#endif /* PIOS_INCLUDE_PPM */
break;
case HWSETTINGS_CC_RCVRPORT_PPMPWMNOONESHOT:
/* This is a combination of PPM and PWM inputs */
#if defined(PIOS_INCLUDE_PPM)
PIOS_BOARD_IO_Configure_PPM(&pios_ppm_cfg);
PIOS_BOARD_IO_Configure_PPM_RCVR(&pios_ppm_cfg);
#endif /* PIOS_INCLUDE_PPM */
#if defined(PIOS_INCLUDE_PWM)
PIOS_BOARD_IO_Configure_PWM(&pios_pwm_with_ppm_cfg);
PIOS_BOARD_IO_Configure_PWM_RCVR(&pios_pwm_with_ppm_cfg);
#endif /* PIOS_INCLUDE_PWM */
break;
case HWSETTINGS_CC_RCVRPORT_OUTPUTSONESHOT:
@ -313,7 +313,7 @@ void PIOS_Board_Init(void)
}
#ifdef PIOS_INCLUDE_GCSRCVR
PIOS_BOARD_IO_Configure_GCSRCVR();
PIOS_BOARD_IO_Configure_GCS_RCVR();
#endif
/* Remap AFIO pin for PB4 (Servo 5 Out)*/

View File

@ -99,12 +99,6 @@ 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)
{
const struct pios_usart_cfg *usart_cfg = PIOS_USART_GetConfig(usart_id);
@ -287,12 +281,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]);
}
PIOS_BOARD_IO_Configure_RadioAuxStream(hwsettings_radioaux);
#endif /* PIOS_INCLUDE_RFM22B */
@ -316,7 +310,7 @@ void PIOS_Board_Init(void)
case HWSETTINGS_RM_RCVRPORT_PWM:
#if defined(PIOS_INCLUDE_PWM)
/* Set up the receiver port. Later this should be optional */
PIOS_BOARD_IO_Configure_PWM(&pios_pwm_cfg);
PIOS_BOARD_IO_Configure_PWM_RCVR(&pios_pwm_cfg);
#endif /* PIOS_INCLUDE_PWM */
break;
case HWSETTINGS_RM_RCVRPORT_PPM:
@ -329,7 +323,7 @@ void PIOS_Board_Init(void)
case HWSETTINGS_RM_RCVRPORT_PPMMAVLINK:
case HWSETTINGS_RM_RCVRPORT_PPMGPS:
#if defined(PIOS_INCLUDE_PPM)
PIOS_BOARD_IO_Configure_PPM(&pios_ppm_cfg);
PIOS_BOARD_IO_Configure_PPM_RCVR(&pios_ppm_cfg);
if (hwsettings_rcvrport == HWSETTINGS_RM_RCVRPORT_PPMOUTPUTS) {
// configure servo outputs and the remaining 5 inputs as outputs
@ -338,7 +332,7 @@ void PIOS_Board_Init(void)
// enable pwm on the remaining channels
if (hwsettings_rcvrport == HWSETTINGS_RM_RCVRPORT_PPMPWM) {
PIOS_BOARD_IO_Configure_PWM(&pios_pwm_ppm_cfg);
PIOS_BOARD_IO_Configure_PWM_RCVR(&pios_pwm_ppm_cfg);
}
break;
@ -349,7 +343,7 @@ void PIOS_Board_Init(void)
break;
}
#ifdef PIOS_INCLUDE_GCSRCVR
PIOS_BOARD_IO_Configure_GCSRCVR();
PIOS_BOARD_IO_Configure_GCS_RCVR();
#endif
#ifndef PIOS_ENABLE_DEBUG_PINS

View File

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

View File

@ -172,7 +172,13 @@ extern uint32_t pios_i2c_flexi_adapter_id;
//
// See also pios_board.c
// -------------------------
#define PIOS_COM_MAX_DEVS 5
#define PIOS_COM_MAX_DEVS 5
#define PIOS_COM_TELEM_USB_RX_BUF_LEN 128
#define PIOS_COM_TELEM_USB_TX_BUF_LEN 128
#define PIOS_COM_TELEM_VCP_RX_BUF_LEN 128
#define PIOS_COM_TELEM_VCP_TX_BUF_LEN 128
// The direct com ports
extern uint32_t pios_com_hid_id;
@ -192,7 +198,6 @@ extern uint32_t pios_com_pri_radio_out_id;
// The destination port for the auxiliary radio port.
extern uint32_t pios_com_aux_radio_out_id;
// The PPM IDs
extern uint32_t pios_ppm_rcvr_id;
extern uint32_t pios_ppm_out_id;
#define PIOS_COM_HID (pios_com_hid_id)
#define PIOS_COM_VCP (pios_com_vcp_id)
@ -205,7 +210,6 @@ extern uint32_t pios_ppm_out_id;
#define PIOS_COM_GCS (pios_com_gcs_id)
#define PIOS_COM_GCS_OUT (pios_com_gcs_out_id)
#define PIOS_COM_BRIDGE (pios_com_bridge_id)
#define PIOS_PPM_RECEIVER (pios_ppm_rcvr_id)
#define PIOS_PPM_OUTPUT (pios_ppm_out_id)
#define RFM22_DEBUG 1

View File

@ -98,13 +98,6 @@ 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)
{
const struct pios_usart_cfg *usart_cfg = PIOS_USART_GetConfig(usart_id);
@ -287,12 +280,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(radioaux_function_map[hwsettings_radioaux]);
}
PIOS_BOARD_IO_Configure_RadioAuxStream(hwsettings_radioaux);
#endif /* PIOS_INCLUDE_RFM22B */
#if defined(PIOS_INCLUDE_PWM) || defined(PIOS_INCLUDE_PPM)
@ -314,7 +307,7 @@ void PIOS_Board_Init(void)
case HWSETTINGS_RM_RCVRPORT_PWM:
#if defined(PIOS_INCLUDE_PWM)
/* Set up the receiver port. Later this should be optional */
PIOS_BOARD_IO_Configure_PWM(&pios_pwm_cfg);
PIOS_BOARD_IO_Configure_PWM_RCVR(&pios_pwm_cfg);
#endif /* PIOS_INCLUDE_PWM */
break;
case HWSETTINGS_RM_RCVRPORT_PPM:
@ -328,7 +321,7 @@ void PIOS_Board_Init(void)
case HWSETTINGS_RM_RCVRPORT_PPMGPS:
case HWSETTINGS_RM_RCVRPORT_PPMHOTTTELEMETRY:
#if defined(PIOS_INCLUDE_PPM)
PIOS_BOARD_IO_Configure_PPM(&pios_ppm_cfg);
PIOS_BOARD_IO_Configure_PPM_RCVR(&pios_ppm_cfg);
if (hwsettings_rcvrport == HWSETTINGS_RM_RCVRPORT_PPMOUTPUTS) {
// configure servo outputs and the remaining 5 inputs as outputs
@ -337,7 +330,7 @@ void PIOS_Board_Init(void)
// enable pwm on the remaining channels
if (hwsettings_rcvrport == HWSETTINGS_RM_RCVRPORT_PPMPWM) {
PIOS_BOARD_IO_Configure_PWM(&pios_pwm_ppm_cfg);
PIOS_BOARD_IO_Configure_PWM_RCVR(&pios_pwm_ppm_cfg);
}
break;
@ -348,7 +341,7 @@ void PIOS_Board_Init(void)
break;
}
#ifdef PIOS_INCLUDE_GCSRCVR
PIOS_BOARD_IO_Configure_GCSRCVR();
PIOS_BOARD_IO_Configure_GCS_RCVR();
#endif
#ifndef PIOS_ENABLE_DEBUG_PINS

View File

@ -263,7 +263,7 @@ void PIOS_Board_Init(void)
case HWSETTINGS_RM_RCVRPORT_PWM:
#if defined(PIOS_INCLUDE_PWM)
/* Set up the receiver port. Later this should be optional */
PIOS_BOARD_IO_Configure_PWM(&pios_pwm_cfg);
PIOS_BOARD_IO_Configure_PWM_RCVR(&pios_pwm_cfg);
#endif /* PIOS_INCLUDE_PWM */
break;
case HWSETTINGS_RM_RCVRPORT_PPM:
@ -275,7 +275,7 @@ void PIOS_Board_Init(void)
pios_servo_cfg = &pios_servo_cfg_out_in_ppm;
}
PIOS_BOARD_IO_Configure_PPM(&pios_ppm_cfg);
PIOS_BOARD_IO_Configure_PPM_RCVR(&pios_ppm_cfg);
break;
#endif /* PIOS_INCLUDE_PPM */
@ -287,7 +287,7 @@ void PIOS_Board_Init(void)
#ifdef PIOS_INCLUDE_GCSRCVR
PIOS_BOARD_IO_Configure_GCSRCVR();
PIOS_BOARD_IO_Configure_GCS_RCVR();
#endif
#ifdef PIOS_INCLUDE_WS2811

View File

@ -313,13 +313,13 @@ void PIOS_Board_Init(void)
break;
case HWSETTINGS_RV_RCVRPORT_PWM:
#if defined(PIOS_INCLUDE_PWM)
PIOS_BOARD_IO_Configure_PWM(&pios_pwm_cfg);
PIOS_BOARD_IO_Configure_PWM_RCVR(&pios_pwm_cfg);
#endif /* PIOS_INCLUDE_PWM */
break;
case HWSETTINGS_RV_RCVRPORT_PPM:
case HWSETTINGS_RV_RCVRPORT_PPMOUTPUTS:
#if defined(PIOS_INCLUDE_PPM)
PIOS_BOARD_IO_Configure_PPM(&pios_ppm_cfg);
PIOS_BOARD_IO_Configure_PPM_RCVR(&pios_ppm_cfg);
#endif /* PIOS_INCLUDE_PPM */
case HWSETTINGS_RV_RCVRPORT_OUTPUTS:
@ -359,7 +359,7 @@ void PIOS_Board_Init(void)
#endif
#ifdef PIOS_INCLUDE_GCSRCVR
PIOS_BOARD_IO_Configure_GCSRCVR();
PIOS_BOARD_IO_Configure_GCS_RCVR();
#endif
#ifndef PIOS_ENABLE_DEBUG_PINS

View File

@ -93,12 +93,6 @@ 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);
@ -263,12 +257,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(radioaux_function_map[hwsettings_radioaux]);
}
PIOS_BOARD_IO_Configure_RadioAuxStream(hwsettings_radioaux);
#endif /* PIOS_INCLUDE_RFM22B */
/* Initialize inverter gpio and set it to off */
@ -301,12 +295,12 @@ void PIOS_Board_Init(void)
#if defined(PIOS_INCLUDE_PPM)
if (hwsettings_rcvrport == HWSETTINGS_SPK2_RCVRPORT_PPM) {
PIOS_BOARD_IO_Configure_PPM(&pios_ppm_cfg);
PIOS_BOARD_IO_Configure_PPM_RCVR(&pios_ppm_cfg);
}
#endif
#ifdef PIOS_INCLUDE_GCSRCVR
PIOS_BOARD_IO_Configure_GCSRCVR();
PIOS_BOARD_IO_Configure_GCS_RCVR();
#endif
#ifndef PIOS_ENABLE_DEBUG_PINS