mirror of
https://bitbucket.org/librepilot/librepilot.git
synced 2025-03-16 08:29:15 +01:00
LP-72 get sbus and maybe ppm working on rcvr input
This commit is contained in:
parent
9bb95e3a84
commit
2286dbcdc2
@ -878,6 +878,49 @@ static const struct pios_usart_cfg pios_usart_sbus_main_cfg = {
|
|||||||
},
|
},
|
||||||
};
|
};
|
||||||
|
|
||||||
|
static const struct pios_usart_cfg pios_usart_sbus_rcvrport_cfg = {
|
||||||
|
.regs = USART6,
|
||||||
|
.remap = GPIO_AF_USART6,
|
||||||
|
.init = {
|
||||||
|
.USART_BaudRate = 100000,
|
||||||
|
.USART_WordLength = USART_WordLength_8b,
|
||||||
|
.USART_Parity = USART_Parity_Even,
|
||||||
|
.USART_StopBits = USART_StopBits_2,
|
||||||
|
.USART_HardwareFlowControl = USART_HardwareFlowControl_None,
|
||||||
|
.USART_Mode = USART_Mode_Rx,
|
||||||
|
},
|
||||||
|
.irq = {
|
||||||
|
.init = {
|
||||||
|
.NVIC_IRQChannel = USART6_IRQn,
|
||||||
|
.NVIC_IRQChannelPreemptionPriority = PIOS_IRQ_PRIO_HIGH,
|
||||||
|
.NVIC_IRQChannelSubPriority = 0,
|
||||||
|
.NVIC_IRQChannelCmd = ENABLE,
|
||||||
|
},
|
||||||
|
},
|
||||||
|
.rx = {
|
||||||
|
.gpio = GPIOC,
|
||||||
|
.init = {
|
||||||
|
.GPIO_Pin = GPIO_Pin_7,
|
||||||
|
.GPIO_Speed = GPIO_Speed_2MHz,
|
||||||
|
.GPIO_Mode = GPIO_Mode_AF,
|
||||||
|
.GPIO_OType = GPIO_OType_PP,
|
||||||
|
.GPIO_PuPd = GPIO_PuPd_UP
|
||||||
|
},
|
||||||
|
},
|
||||||
|
#if 0
|
||||||
|
.tx = {
|
||||||
|
.gpio = GPIOA,
|
||||||
|
.init = {
|
||||||
|
.GPIO_Pin = GPIO_Pin_9,
|
||||||
|
.GPIO_Speed = GPIO_Speed_2MHz,
|
||||||
|
.GPIO_Mode = GPIO_Mode_OUT,
|
||||||
|
.GPIO_OType = GPIO_OType_PP,
|
||||||
|
.GPIO_PuPd = GPIO_PuPd_NOPULL
|
||||||
|
},
|
||||||
|
},
|
||||||
|
#endif
|
||||||
|
};
|
||||||
|
|
||||||
#endif /* PIOS_INCLUDE_SBUS */
|
#endif /* PIOS_INCLUDE_SBUS */
|
||||||
|
|
||||||
// Need this defined regardless to be able to turn it off
|
// Need this defined regardless to be able to turn it off
|
||||||
@ -886,7 +929,7 @@ static const struct pios_sbus_cfg pios_sbus_cfg = {
|
|||||||
.inv = {
|
.inv = {
|
||||||
.gpio = GPIOC,
|
.gpio = GPIOC,
|
||||||
.init = {
|
.init = {
|
||||||
.GPIO_Pin = GPIO_Pin_0,
|
.GPIO_Pin = GPIO_Pin_6, // GPIO_Pin_6 Sparky2 has external inverter on PC6, Revo=PC0
|
||||||
.GPIO_Speed = GPIO_Speed_2MHz,
|
.GPIO_Speed = GPIO_Speed_2MHz,
|
||||||
.GPIO_Mode = GPIO_Mode_OUT,
|
.GPIO_Mode = GPIO_Mode_OUT,
|
||||||
.GPIO_OType = GPIO_OType_PP,
|
.GPIO_OType = GPIO_OType_PP,
|
||||||
@ -1814,6 +1857,7 @@ const struct pios_servo_cfg pios_servo_cfg_out_in = {
|
|||||||
#if defined(PIOS_INCLUDE_PWM) || defined(PIOS_INCLUDE_PPM)
|
#if defined(PIOS_INCLUDE_PWM) || defined(PIOS_INCLUDE_PPM)
|
||||||
#include <pios_pwm_priv.h>
|
#include <pios_pwm_priv.h>
|
||||||
static const struct pios_tim_channel pios_tim_rcvrport_all_channels[] = {
|
static const struct pios_tim_channel pios_tim_rcvrport_all_channels[] = {
|
||||||
|
#if 0
|
||||||
{
|
{
|
||||||
.timer = TIM12,
|
.timer = TIM12,
|
||||||
.timer_chan = TIM_Channel_1,
|
.timer_chan = TIM_Channel_1,
|
||||||
@ -1910,8 +1954,29 @@ static const struct pios_tim_channel pios_tim_rcvrport_all_channels[] = {
|
|||||||
},
|
},
|
||||||
.remap = GPIO_AF_TIM8,
|
.remap = GPIO_AF_TIM8,
|
||||||
},
|
},
|
||||||
|
#else
|
||||||
|
// Sparky2 has one pin from RC receiver input and this is it
|
||||||
|
// Sparky2 will not do PWM from RC receiver
|
||||||
|
{
|
||||||
|
.timer = TIM8,
|
||||||
|
.timer_chan = TIM_Channel_2,
|
||||||
|
.pin = {
|
||||||
|
.gpio = GPIOC,
|
||||||
|
.init = {
|
||||||
|
.GPIO_Pin = GPIO_Pin_7,
|
||||||
|
.GPIO_Speed = GPIO_Speed_2MHz,
|
||||||
|
.GPIO_Mode = GPIO_Mode_AF,
|
||||||
|
.GPIO_OType = GPIO_OType_PP,
|
||||||
|
.GPIO_PuPd = GPIO_PuPd_UP
|
||||||
|
},
|
||||||
|
.pin_source = GPIO_PinSource7,
|
||||||
|
},
|
||||||
|
.remap = GPIO_AF_TIM8,
|
||||||
|
},
|
||||||
|
#endif
|
||||||
};
|
};
|
||||||
|
|
||||||
|
#if 0
|
||||||
const struct pios_pwm_cfg pios_pwm_cfg = {
|
const struct pios_pwm_cfg pios_pwm_cfg = {
|
||||||
.tim_ic_init = {
|
.tim_ic_init = {
|
||||||
.TIM_ICPolarity = TIM_ICPolarity_Rising,
|
.TIM_ICPolarity = TIM_ICPolarity_Rising,
|
||||||
@ -1933,6 +1998,7 @@ const struct pios_pwm_cfg pios_pwm_ppm_cfg = {
|
|||||||
.channels = &pios_tim_rcvrport_all_channels[1],
|
.channels = &pios_tim_rcvrport_all_channels[1],
|
||||||
.num_channels = NELEMENTS(pios_tim_rcvrport_all_channels) - 1,
|
.num_channels = NELEMENTS(pios_tim_rcvrport_all_channels) - 1,
|
||||||
};
|
};
|
||||||
|
#endif
|
||||||
|
|
||||||
#endif /* if defined(PIOS_INCLUDE_PWM) || defined(PIOS_INCLUDE_PPM) */
|
#endif /* if defined(PIOS_INCLUDE_PWM) || defined(PIOS_INCLUDE_PPM) */
|
||||||
|
|
||||||
|
@ -313,20 +313,6 @@ static void PIOS_Board_configure_dsm(const struct pios_usart_cfg *pios_usart_dsm
|
|||||||
pios_rcvr_group_map[channelgroup] = pios_dsm_rcvr_id;
|
pios_rcvr_group_map[channelgroup] = pios_dsm_rcvr_id;
|
||||||
}
|
}
|
||||||
|
|
||||||
static void PIOS_Board_configure_pwm(const struct pios_pwm_cfg *pwm_cfg)
|
|
||||||
{
|
|
||||||
/* Set up the receiver port. Later this should be optional */
|
|
||||||
uint32_t pios_pwm_id;
|
|
||||||
|
|
||||||
PIOS_PWM_Init(&pios_pwm_id, pwm_cfg);
|
|
||||||
|
|
||||||
uint32_t pios_pwm_rcvr_id;
|
|
||||||
if (PIOS_RCVR_Init(&pios_pwm_rcvr_id, &pios_pwm_rcvr_driver, pios_pwm_id)) {
|
|
||||||
PIOS_Assert(0);
|
|
||||||
}
|
|
||||||
pios_rcvr_group_map[MANUALCONTROLSETTINGS_CHANNELGROUPS_PWM] = pios_pwm_rcvr_id;
|
|
||||||
}
|
|
||||||
|
|
||||||
static void PIOS_Board_configure_ppm(const struct pios_ppm_cfg *ppm_cfg)
|
static void PIOS_Board_configure_ppm(const struct pios_ppm_cfg *ppm_cfg)
|
||||||
{
|
{
|
||||||
uint32_t pios_ppm_id;
|
uint32_t pios_ppm_id;
|
||||||
@ -678,6 +664,7 @@ void PIOS_Board_Init(void)
|
|||||||
HwSettingsRM_MainPortGet(&hwsettings_mainport);
|
HwSettingsRM_MainPortGet(&hwsettings_mainport);
|
||||||
switch (hwsettings_mainport) {
|
switch (hwsettings_mainport) {
|
||||||
case HWSETTINGS_RM_MAINPORT_DISABLED:
|
case HWSETTINGS_RM_MAINPORT_DISABLED:
|
||||||
|
case HWSETTINGS_RM_MAINPORT_SBUS:
|
||||||
break;
|
break;
|
||||||
case HWSETTINGS_RM_MAINPORT_TELEMETRY:
|
case HWSETTINGS_RM_MAINPORT_TELEMETRY:
|
||||||
PIOS_Board_configure_com(&pios_usart_main_cfg, PIOS_COM_TELEM_RF_RX_BUF_LEN, PIOS_COM_TELEM_RF_TX_BUF_LEN, &pios_usart_com_driver, &pios_com_telem_rf_id);
|
PIOS_Board_configure_com(&pios_usart_main_cfg, PIOS_COM_TELEM_RF_RX_BUF_LEN, PIOS_COM_TELEM_RF_TX_BUF_LEN, &pios_usart_com_driver, &pios_com_telem_rf_id);
|
||||||
@ -685,27 +672,6 @@ void PIOS_Board_Init(void)
|
|||||||
case HWSETTINGS_RM_MAINPORT_GPS:
|
case HWSETTINGS_RM_MAINPORT_GPS:
|
||||||
PIOS_Board_configure_com(&pios_usart_main_cfg, PIOS_COM_GPS_RX_BUF_LEN, PIOS_COM_GPS_TX_BUF_LEN, &pios_usart_com_driver, &pios_com_gps_id);
|
PIOS_Board_configure_com(&pios_usart_main_cfg, PIOS_COM_GPS_RX_BUF_LEN, PIOS_COM_GPS_TX_BUF_LEN, &pios_usart_com_driver, &pios_com_gps_id);
|
||||||
break;
|
break;
|
||||||
case HWSETTINGS_RM_MAINPORT_SBUS:
|
|
||||||
#if defined(PIOS_INCLUDE_SBUS)
|
|
||||||
{
|
|
||||||
uint32_t pios_usart_sbus_id;
|
|
||||||
if (PIOS_USART_Init(&pios_usart_sbus_id, &pios_usart_sbus_main_cfg)) {
|
|
||||||
PIOS_Assert(0);
|
|
||||||
}
|
|
||||||
|
|
||||||
uint32_t pios_sbus_id;
|
|
||||||
if (PIOS_SBus_Init(&pios_sbus_id, &pios_sbus_cfg, &pios_usart_com_driver, pios_usart_sbus_id)) {
|
|
||||||
PIOS_Assert(0);
|
|
||||||
}
|
|
||||||
|
|
||||||
uint32_t pios_sbus_rcvr_id;
|
|
||||||
if (PIOS_RCVR_Init(&pios_sbus_rcvr_id, &pios_sbus_rcvr_driver, pios_sbus_id)) {
|
|
||||||
PIOS_Assert(0);
|
|
||||||
}
|
|
||||||
pios_rcvr_group_map[MANUALCONTROLSETTINGS_CHANNELGROUPS_SBUS] = pios_sbus_rcvr_id;
|
|
||||||
}
|
|
||||||
#endif
|
|
||||||
break;
|
|
||||||
case HWSETTINGS_RM_MAINPORT_DSM:
|
case HWSETTINGS_RM_MAINPORT_DSM:
|
||||||
// Force binding to zero on the main port
|
// Force binding to zero on the main port
|
||||||
hwsettings_DSMxBind = 0;
|
hwsettings_DSMxBind = 0;
|
||||||
@ -729,11 +695,6 @@ void PIOS_Board_Init(void)
|
|||||||
break;
|
break;
|
||||||
} /* hwsettings_rm_mainport */
|
} /* hwsettings_rm_mainport */
|
||||||
|
|
||||||
if (hwsettings_mainport != HWSETTINGS_RM_MAINPORT_SBUS) {
|
|
||||||
GPIO_Init(pios_sbus_cfg.inv.gpio, &pios_sbus_cfg.inv.init);
|
|
||||||
GPIO_WriteBit(pios_sbus_cfg.inv.gpio, pios_sbus_cfg.inv.init.GPIO_Pin, pios_sbus_cfg.gpio_inv_disable);
|
|
||||||
}
|
|
||||||
|
|
||||||
|
|
||||||
/* Initalize the RFM22B radio COM device. */
|
/* Initalize the RFM22B radio COM device. */
|
||||||
#if defined(PIOS_INCLUDE_RFM22B)
|
#if defined(PIOS_INCLUDE_RFM22B)
|
||||||
@ -855,53 +816,59 @@ void PIOS_Board_Init(void)
|
|||||||
#endif
|
#endif
|
||||||
|
|
||||||
/* Configure the receiver port*/
|
/* Configure the receiver port*/
|
||||||
|
// Revo Flex-IO Port Functions
|
||||||
|
// 1: GND
|
||||||
|
// 2: VCC_UNREG
|
||||||
|
// 3: PB12 = SPI2 NSS, CAN2 RX
|
||||||
|
// 4: PB13 = SPI2 SCK, CAN2 TX, USART3 CTS
|
||||||
|
// 5: PB14 = SPI2 MISO, TIM12 CH1, USART3 RTS
|
||||||
|
// 6: PB15 = SPI2 MOSI, TIM12 CH2
|
||||||
|
// 7: PC6 = TIM8 CH1, USART6 TX
|
||||||
|
// 8: PC7 = TIM8 CH2, USART6 RX
|
||||||
|
// 9: PC8 = TIM8 CH3
|
||||||
|
// 10: PC9 = TIM8 CH4
|
||||||
|
//
|
||||||
|
// Sparky2 receiver input on PC7 TIM8 CH2
|
||||||
|
// that appears to include PPM, DSM, DSM-HSUM, SBUS
|
||||||
uint8_t hwsettings_rcvrport;
|
uint8_t hwsettings_rcvrport;
|
||||||
HwSettingsRM_RcvrPortGet(&hwsettings_rcvrport);
|
HwSettingsRM_RcvrPortGet(&hwsettings_rcvrport);
|
||||||
//
|
//
|
||||||
switch (hwsettings_rcvrport) {
|
switch (hwsettings_rcvrport) {
|
||||||
case HWSETTINGS_RM_RCVRPORT_DISABLED:
|
|
||||||
break;
|
|
||||||
case HWSETTINGS_RM_RCVRPORT_PWM:
|
|
||||||
#if defined(PIOS_INCLUDE_PWM)
|
|
||||||
/* Set up the receiver port. Later this should be optional */
|
|
||||||
PIOS_Board_configure_pwm(&pios_pwm_cfg);
|
|
||||||
#endif /* PIOS_INCLUDE_PWM */
|
|
||||||
break;
|
|
||||||
case HWSETTINGS_RM_RCVRPORT_PPM:
|
case HWSETTINGS_RM_RCVRPORT_PPM:
|
||||||
case HWSETTINGS_RM_RCVRPORT_PPMOUTPUTS:
|
|
||||||
case HWSETTINGS_RM_RCVRPORT_PPMPWM:
|
|
||||||
case HWSETTINGS_RM_RCVRPORT_PPMTELEMETRY:
|
|
||||||
#if defined(PIOS_INCLUDE_PPM)
|
#if defined(PIOS_INCLUDE_PPM)
|
||||||
PIOS_Board_configure_ppm(&pios_ppm_cfg);
|
PIOS_Board_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_configure_pwm(&pios_pwm_ppm_cfg);
|
|
||||||
}
|
|
||||||
|
|
||||||
if (hwsettings_rcvrport == HWSETTINGS_RM_RCVRPORT_PPMTELEMETRY) {
|
|
||||||
PIOS_Board_configure_com(&pios_usart_rcvrport_cfg, PIOS_COM_TELEM_RF_RX_BUF_LEN, PIOS_COM_TELEM_RF_TX_BUF_LEN, &pios_usart_com_driver, &pios_com_telem_rf_id);
|
|
||||||
}
|
|
||||||
|
|
||||||
break;
|
break;
|
||||||
#endif /* PIOS_INCLUDE_PPM */
|
#endif /* PIOS_INCLUDE_PPM */
|
||||||
case HWSETTINGS_RM_RCVRPORT_OUTPUTS:
|
case HWSETTINGS_RM_RCVRPORT_SBUS:
|
||||||
// configure only the servo outputs
|
#if defined(PIOS_INCLUDE_SBUS)
|
||||||
pios_servo_cfg = &pios_servo_cfg_out_in;
|
{
|
||||||
|
uint32_t pios_usart_sbus_id;
|
||||||
|
if (PIOS_USART_Init(&pios_usart_sbus_id, &pios_usart_sbus_rcvrport_cfg)) {
|
||||||
|
PIOS_Assert(0);
|
||||||
|
}
|
||||||
|
|
||||||
|
uint32_t pios_sbus_id;
|
||||||
|
if (PIOS_SBus_Init(&pios_sbus_id, &pios_sbus_cfg, &pios_usart_com_driver, pios_usart_sbus_id)) {
|
||||||
|
PIOS_Assert(0);
|
||||||
|
}
|
||||||
|
|
||||||
|
uint32_t pios_sbus_rcvr_id;
|
||||||
|
if (PIOS_RCVR_Init(&pios_sbus_rcvr_id, &pios_sbus_rcvr_driver, pios_sbus_id)) {
|
||||||
|
PIOS_Assert(0);
|
||||||
|
}
|
||||||
|
pios_rcvr_group_map[MANUALCONTROLSETTINGS_CHANNELGROUPS_SBUS] = pios_sbus_rcvr_id;
|
||||||
|
}
|
||||||
|
#endif
|
||||||
break;
|
break;
|
||||||
case HWSETTINGS_RM_RCVRPORT_TELEMETRY:
|
default:
|
||||||
PIOS_Board_configure_com(&pios_usart_rcvrport_cfg, PIOS_COM_TELEM_RF_RX_BUF_LEN, PIOS_COM_TELEM_RF_TX_BUF_LEN, &pios_usart_com_driver, &pios_com_telem_rf_id);
|
|
||||||
break;
|
|
||||||
case HWSETTINGS_RM_RCVRPORT_COMBRIDGE:
|
|
||||||
PIOS_Board_configure_com(&pios_usart_rcvrport_cfg, PIOS_COM_BRIDGE_RX_BUF_LEN, PIOS_COM_BRIDGE_TX_BUF_LEN, &pios_usart_com_driver, &pios_com_bridge_id);
|
|
||||||
break;
|
break;
|
||||||
}
|
}
|
||||||
|
|
||||||
|
if (hwsettings_rcvrport != HWSETTINGS_RM_RCVRPORT_SBUS) {
|
||||||
|
GPIO_Init(pios_sbus_cfg.inv.gpio, &pios_sbus_cfg.inv.init);
|
||||||
|
GPIO_WriteBit(pios_sbus_cfg.inv.gpio, pios_sbus_cfg.inv.init.GPIO_Pin, pios_sbus_cfg.gpio_inv_disable);
|
||||||
|
}
|
||||||
|
|
||||||
#if defined(PIOS_INCLUDE_GCSRCVR)
|
#if defined(PIOS_INCLUDE_GCSRCVR)
|
||||||
GCSReceiverInitialize();
|
GCSReceiverInitialize();
|
||||||
uint32_t pios_gcsrcvr_id;
|
uint32_t pios_gcsrcvr_id;
|
||||||
@ -954,8 +921,13 @@ void PIOS_Board_Init(void)
|
|||||||
PIOS_MPU9250_MagRegister();
|
PIOS_MPU9250_MagRegister();
|
||||||
#endif
|
#endif
|
||||||
|
|
||||||
|
PIOS_WDG_Clear();
|
||||||
|
|
||||||
#if defined(PIOS_INCLUDE_HMC5X83)
|
#if defined(PIOS_INCLUDE_HMC5X83)
|
||||||
|
// on board mag is in the MPU9250
|
||||||
|
// this hmc5x83 mag is an external mag
|
||||||
i2c_port_mag = PIOS_HMC5x83_Init(&pios_hmc5x83_cfg, pios_i2c_mag_pressure_adapter_id, 0);
|
i2c_port_mag = PIOS_HMC5x83_Init(&pios_hmc5x83_cfg, pios_i2c_mag_pressure_adapter_id, 0);
|
||||||
|
PIOS_WDG_Clear();
|
||||||
PIOS_HMC5x83_Register(i2c_port_mag);
|
PIOS_HMC5x83_Register(i2c_port_mag);
|
||||||
#endif
|
#endif
|
||||||
|
|
||||||
|
@ -11,7 +11,7 @@
|
|||||||
<field name="RV_TelemetryPort" units="function" type="enum" elements="1" options="Disabled,Telemetry,ComAux,ComBridge,MSP" defaultvalue="Telemetry"/>
|
<field name="RV_TelemetryPort" units="function" type="enum" elements="1" options="Disabled,Telemetry,ComAux,ComBridge,MSP" defaultvalue="Telemetry"/>
|
||||||
<field name="RV_GPSPort" units="function" type="enum" elements="1" options="Disabled,Telemetry,GPS,ComAux,ComBridge,MSP" defaultvalue="GPS"/>
|
<field name="RV_GPSPort" units="function" type="enum" elements="1" options="Disabled,Telemetry,GPS,ComAux,ComBridge,MSP" defaultvalue="GPS"/>
|
||||||
|
|
||||||
<field name="RM_RcvrPort" units="function" type="enum" elements="1" options="Disabled,PWM,PPM,PPM+PWM,PPM+Telemetry,PPM+Outputs,Outputs,Telemetry,ComBridge,MSP"
|
<field name="RM_RcvrPort" units="function" type="enum" elements="1" options="Disabled,PWM,PPM,PPM+PWM,PPM+Telemetry,PPM+Outputs,Outputs,S.Bus,Telemetry,ComBridge,MSP"
|
||||||
defaultvalue="PWM"
|
defaultvalue="PWM"
|
||||||
limits="%0905NE:PPM+PWM:PPM+Telemetry:Telemetry:ComBridge;"/>
|
limits="%0905NE:PPM+PWM:PPM+Telemetry:Telemetry:ComBridge;"/>
|
||||||
<field name="RM_MainPort" units="function" type="enum" elements="1" options="Disabled,Telemetry,GPS,S.Bus,DSM,DebugConsole,ComBridge,OsdHk,MSP" defaultvalue="Disabled"/>
|
<field name="RM_MainPort" units="function" type="enum" elements="1" options="Disabled,Telemetry,GPS,S.Bus,DSM,DebugConsole,ComBridge,OsdHk,MSP" defaultvalue="Disabled"/>
|
||||||
|
Loading…
x
Reference in New Issue
Block a user