mirror of
https://bitbucket.org/librepilot/librepilot.git
synced 2025-02-20 10:54:14 +01:00
LP-298 Port Ibus Input driver from dRonin - Not tested
This commit is contained in:
parent
d7ebf30b22
commit
5895468f08
@ -93,6 +93,7 @@ SRC += $(PIOSCOMMON)/pios_sbus.c
|
||||
SRC += $(PIOSCOMMON)/pios_hott.c
|
||||
SRC += $(PIOSCOMMON)/pios_srxl.c
|
||||
SRC += $(PIOSCOMMON)/pios_exbus.c
|
||||
SRC += $(PIOSCOMMON)/pios_ibus.c
|
||||
SRC += $(PIOSCOMMON)/pios_sdcard.c
|
||||
SRC += $(PIOSCOMMON)/pios_sensors.c
|
||||
SRC += $(PIOSCOMMON)/pios_openlrs.c
|
||||
|
@ -670,6 +670,9 @@ static bool updateRcvrActivityCompare(uint32_t rcvr_id, struct rcvr_activity_fsm
|
||||
case MANUALCONTROLSETTINGS_CHANNELGROUPS_SRXL:
|
||||
group = RECEIVERACTIVITY_ACTIVEGROUP_SRXL;
|
||||
break;
|
||||
case MANUALCONTROLSETTINGS_CHANNELGROUPS_IBUS:
|
||||
group = RECEIVERACTIVITY_ACTIVEGROUP_IBUS;
|
||||
break;
|
||||
case MANUALCONTROLSETTINGS_CHANNELGROUPS_GCS:
|
||||
group = RECEIVERACTIVITY_ACTIVEGROUP_GCS;
|
||||
break;
|
||||
|
256
flight/pios/common/pios_ibus.c
Normal file
256
flight/pios/common/pios_ibus.c
Normal file
@ -0,0 +1,256 @@
|
||||
/**
|
||||
******************************************************************************
|
||||
* @file pios_ibus.c
|
||||
* @author dRonin, http://dRonin.org/, Copyright (C) 2016
|
||||
* @addtogroup PIOS PIOS Core hardware abstraction layer
|
||||
* @{
|
||||
* @addtogroup PIOS_IBus PiOS IBus receiver driver
|
||||
* @{
|
||||
* @brief Receives and decodes IBus protocol reciever packets
|
||||
*****************************************************************************/
|
||||
/*
|
||||
* 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
|
||||
*
|
||||
* Additional note on redistribution: The copyright and license notices above
|
||||
* must be maintained in each individual source file that is a derivative work
|
||||
* of this source file; otherwise redistribution is prohibited.
|
||||
*/
|
||||
|
||||
#include "pios_ibus_priv.h"
|
||||
|
||||
#ifdef PIOS_INCLUDE_IBUS
|
||||
|
||||
// private
|
||||
#define PIOS_IBUS_CHANNELS 10
|
||||
// 1 sync byte, 1 unknown byte, 10x channels (uint16_t), 8 unknown bytes, 2 crc bytes
|
||||
#define PIOS_IBUS_BUFLEN (1 + 1 + PIOS_IBUS_CHANNELS * 2 + 8 + 2)
|
||||
#define PIOS_IBUS_SYNCBYTE 0x20
|
||||
#define PIOS_IBUS_MAGIC 0x84fd9a39
|
||||
|
||||
/**
|
||||
* @brief IBus receiver driver internal state data
|
||||
*/
|
||||
struct pios_ibus_dev {
|
||||
uint32_t magic;
|
||||
int buf_pos;
|
||||
int rx_timer;
|
||||
int failsafe_timer;
|
||||
uint16_t checksum;
|
||||
uint16_t channel_data[PIOS_IBUS_CHANNELS];
|
||||
uint8_t rx_buf[PIOS_IBUS_BUFLEN];
|
||||
};
|
||||
|
||||
/**
|
||||
* @brief Allocates a driver instance
|
||||
* @retval pios_ibus_dev pointer on success, NULL on failure
|
||||
*/
|
||||
static struct pios_ibus_dev *PIOS_IBUS_Alloc(void);
|
||||
/**
|
||||
* @brief Validate a driver instance
|
||||
* @param[in] dev device driver instance pointer
|
||||
* @retval true on success, false on failure
|
||||
*/
|
||||
static bool PIOS_IBUS_Validate(const struct pios_ibus_dev *ibus_dev);
|
||||
/**
|
||||
* @brief Read a channel from the last received frame
|
||||
* @param[in] id Driver instance
|
||||
* @param[in] channel 0-based channel index
|
||||
* @retval raw channel value, or error value (see pios_rcvr.h)
|
||||
*/
|
||||
static int32_t PIOS_IBUS_Read(uint32_t id, uint8_t channel);
|
||||
/**
|
||||
* @brief Set all channels in the last frame buffer to a given value
|
||||
* @param[in] dev Driver instance
|
||||
* @param[in] value channel value
|
||||
*/
|
||||
static void PIOS_IBUS_SetAllChannels(struct pios_ibus_dev *ibus_dev, uint16_t value);
|
||||
/**
|
||||
* @brief Serial receive callback
|
||||
* @param[in] context Driver instance handle
|
||||
* @param[in] buf Receive buffer
|
||||
* @param[in] buf_len Number of bytes available
|
||||
* @param[out] headroom Number of bytes remaining in internal buffer
|
||||
* @param[out] task_woken Did we awake a task?
|
||||
* @retval Number of bytes consumed from the buffer
|
||||
*/
|
||||
static uint16_t PIOS_IBUS_Receive(uint32_t context, uint8_t *buf, uint16_t buf_len,
|
||||
uint16_t *headroom, bool *task_woken);
|
||||
/**
|
||||
* @brief Reset the internal receive buffer state
|
||||
* @param[in] ibus_dev device driver instance pointer
|
||||
*/
|
||||
static void PIOS_IBUS_ResetBuffer(struct pios_ibus_dev *ibus_dev);
|
||||
/**
|
||||
* @brief Unpack a frame from the internal receive buffer to the channel buffer
|
||||
* @param[in] ibus_dev device driver instance pointer
|
||||
*/
|
||||
static void PIOS_IBUS_UnpackFrame(struct pios_ibus_dev *ibus_dev);
|
||||
/**
|
||||
* @brief RTC tick callback
|
||||
* @param[in] context Driver instance handle
|
||||
*/
|
||||
static void PIOS_IBUS_Supervisor(uint32_t context);
|
||||
|
||||
// public
|
||||
const struct pios_rcvr_driver pios_ibus_rcvr_driver = {
|
||||
.read = PIOS_IBUS_Read,
|
||||
};
|
||||
|
||||
|
||||
static struct pios_ibus_dev *PIOS_IBUS_Alloc(void)
|
||||
{
|
||||
struct pios_ibus_dev *ibus_dev;
|
||||
|
||||
ibus_dev = (struct pios_ibus_dev *)pios_malloc(sizeof(*ibus_dev));
|
||||
|
||||
if (!ibus_dev) {
|
||||
return NULL;
|
||||
}
|
||||
|
||||
memset(ibus_dev, 0, sizeof(*ibus_dev));
|
||||
ibus_dev->magic = PIOS_IBUS_MAGIC;
|
||||
|
||||
return ibus_dev;
|
||||
}
|
||||
|
||||
static bool PIOS_IBUS_Validate(const struct pios_ibus_dev *ibus_dev)
|
||||
{
|
||||
return ibus_dev && ibus_dev->magic == PIOS_IBUS_MAGIC;
|
||||
}
|
||||
|
||||
int32_t PIOS_IBUS_Init(uint32_t *ibus_id, const struct pios_com_driver *driver,
|
||||
uint32_t lower_id)
|
||||
{
|
||||
struct pios_ibus_dev *ibus_dev = PIOS_IBUS_Alloc();
|
||||
|
||||
if (!ibus_dev) {
|
||||
return -1;
|
||||
}
|
||||
|
||||
*ibus_id = (uint32_t)ibus_dev;
|
||||
|
||||
PIOS_IBUS_SetAllChannels(ibus_dev, PIOS_RCVR_INVALID);
|
||||
|
||||
if (!PIOS_RTC_RegisterTickCallback(PIOS_IBUS_Supervisor, *ibus_id)) {
|
||||
PIOS_Assert(0);
|
||||
}
|
||||
|
||||
(driver->bind_rx_cb)(lower_id, PIOS_IBUS_Receive, *ibus_id);
|
||||
|
||||
return 0;
|
||||
}
|
||||
|
||||
static int32_t PIOS_IBUS_Read(uint32_t context, uint8_t channel)
|
||||
{
|
||||
if (channel > PIOS_IBUS_CHANNELS) {
|
||||
return PIOS_RCVR_INVALID;
|
||||
}
|
||||
|
||||
struct pios_ibus_dev *ibus_dev = (struct pios_ibus_dev *)context;
|
||||
if (!PIOS_IBUS_Validate(ibus_dev)) {
|
||||
return PIOS_RCVR_NODRIVER;
|
||||
}
|
||||
|
||||
return ibus_dev->channel_data[channel];
|
||||
}
|
||||
|
||||
static void PIOS_IBUS_SetAllChannels(struct pios_ibus_dev *ibus_dev, uint16_t value)
|
||||
{
|
||||
for (int i = 0; i < PIOS_IBUS_CHANNELS; i++) {
|
||||
ibus_dev->channel_data[i] = value;
|
||||
}
|
||||
}
|
||||
|
||||
static uint16_t PIOS_IBUS_Receive(uint32_t context, uint8_t *buf, uint16_t buf_len,
|
||||
uint16_t *headroom, bool *task_woken)
|
||||
{
|
||||
struct pios_ibus_dev *ibus_dev = (struct pios_ibus_dev *)context;
|
||||
|
||||
if (!PIOS_IBUS_Validate(ibus_dev)) {
|
||||
goto out_fail;
|
||||
}
|
||||
|
||||
for (int i = 0; i < buf_len; i++) {
|
||||
if (ibus_dev->buf_pos == 0 && buf[i] != PIOS_IBUS_SYNCBYTE) {
|
||||
continue;
|
||||
}
|
||||
|
||||
ibus_dev->rx_buf[ibus_dev->buf_pos++] = buf[i];
|
||||
if (ibus_dev->buf_pos <= PIOS_IBUS_BUFLEN - 2) {
|
||||
ibus_dev->checksum -= buf[i];
|
||||
} else if (ibus_dev->buf_pos == PIOS_IBUS_BUFLEN) {
|
||||
PIOS_IBUS_UnpackFrame(ibus_dev);
|
||||
}
|
||||
}
|
||||
|
||||
ibus_dev->rx_timer = 0;
|
||||
|
||||
*headroom = PIOS_IBUS_BUFLEN - ibus_dev->buf_pos;
|
||||
*task_woken = false;
|
||||
return buf_len;
|
||||
|
||||
out_fail:
|
||||
*headroom = 0;
|
||||
*task_woken = false;
|
||||
return 0;
|
||||
}
|
||||
|
||||
static void PIOS_IBUS_ResetBuffer(struct pios_ibus_dev *ibus_dev)
|
||||
{
|
||||
ibus_dev->checksum = 0xffff;
|
||||
ibus_dev->buf_pos = 0;
|
||||
}
|
||||
|
||||
static void PIOS_IBUS_UnpackFrame(struct pios_ibus_dev *ibus_dev)
|
||||
{
|
||||
uint16_t rxsum = ibus_dev->rx_buf[PIOS_IBUS_BUFLEN - 1] << 8 |
|
||||
ibus_dev->rx_buf[PIOS_IBUS_BUFLEN - 2];
|
||||
|
||||
if (ibus_dev->checksum != rxsum) {
|
||||
goto out_fail;
|
||||
}
|
||||
|
||||
uint16_t *chan = (uint16_t *)&ibus_dev->rx_buf[2];
|
||||
for (int i = 0; i < PIOS_IBUS_CHANNELS; i++) {
|
||||
ibus_dev->channel_data[i] = *chan++;
|
||||
}
|
||||
|
||||
ibus_dev->failsafe_timer = 0;
|
||||
|
||||
out_fail:
|
||||
PIOS_IBUS_ResetBuffer(ibus_dev);
|
||||
}
|
||||
|
||||
static void PIOS_IBUS_Supervisor(uint32_t context)
|
||||
{
|
||||
struct pios_ibus_dev *ibus_dev = (struct pios_ibus_dev *)context;
|
||||
|
||||
PIOS_Assert(PIOS_IBUS_Validate(ibus_dev));
|
||||
|
||||
if (++ibus_dev->rx_timer > 3) {
|
||||
PIOS_IBUS_ResetBuffer(ibus_dev);
|
||||
}
|
||||
|
||||
if (++ibus_dev->failsafe_timer > 32) {
|
||||
PIOS_IBUS_SetAllChannels(ibus_dev, PIOS_RCVR_TIMEOUT);
|
||||
}
|
||||
}
|
||||
|
||||
#endif // PIOS_INCLUDE_IBUS
|
||||
|
||||
/**
|
||||
* @}
|
||||
* @}
|
||||
*/
|
38
flight/pios/inc/pios_ibus.h
Normal file
38
flight/pios/inc/pios_ibus.h
Normal file
@ -0,0 +1,38 @@
|
||||
/**
|
||||
******************************************************************************
|
||||
*
|
||||
* @file pios_ibus.h
|
||||
* @author The LibrePilot Project, http://www.librepilot.org Copyright (C) 2016.
|
||||
* dRonin, http://dRonin.org/, Copyright (C) 2016
|
||||
* @brief FlySky IBus functions header.
|
||||
* @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_IBUS_H
|
||||
#define PIOS_IBUS_H
|
||||
|
||||
/* Global Types */
|
||||
|
||||
/* Public Functions */
|
||||
|
||||
#endif /* PIOS_IBUS_H */
|
||||
|
||||
/**
|
||||
* @}
|
||||
* @}
|
||||
*/
|
51
flight/pios/inc/pios_ibus_priv.h
Normal file
51
flight/pios/inc/pios_ibus_priv.h
Normal file
@ -0,0 +1,51 @@
|
||||
/**
|
||||
******************************************************************************
|
||||
* @file pios_ibus_priv.h
|
||||
* @author The LibrePilot Project, http://www.librepilot.org Copyright (C) 2016.
|
||||
* dRonin, http://dRonin.org/, Copyright (C) 2016
|
||||
* @addtogroup PIOS PIOS Core hardware abstraction layer
|
||||
* @{
|
||||
* @addtogroup PIOS_IBus IBus receiver functions
|
||||
* @{
|
||||
* @brief Receives and decodes IBus protocol receiver packets
|
||||
*****************************************************************************/
|
||||
/*
|
||||
* 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
|
||||
*
|
||||
* Additional note on redistribution: The copyright and license notices above
|
||||
* must be maintained in each individual source file that is a derivative work
|
||||
* of this source file; otherwise redistribution is prohibited.
|
||||
*/
|
||||
|
||||
|
||||
#ifndef PIOS_IBUS_PRIV_H
|
||||
#define PIOS_IBUS_PRIV_H
|
||||
|
||||
#include <pios.h>
|
||||
#include <pios_usart_priv.h>
|
||||
|
||||
/* IBUS receiver instance configuration */
|
||||
extern const struct pios_rcvr_driver pios_ibus_rcvr_driver;
|
||||
|
||||
extern int32_t PIOS_IBUS_Init(uint32_t *ibus_id,
|
||||
const struct pios_com_driver *driver,
|
||||
uint32_t lower_id);
|
||||
|
||||
#endif // PIOS_IBUS_PRIV_H
|
||||
|
||||
/**
|
||||
* @}
|
||||
* @}
|
||||
*/
|
@ -241,6 +241,10 @@ extern "C" {
|
||||
#include <pios_srxl.h>
|
||||
#endif
|
||||
|
||||
#ifdef PIOS_INCLUDE_IBUS
|
||||
#include <pios_ibus.h>
|
||||
#endif
|
||||
|
||||
/* PIOS abstract receiver interface */
|
||||
#ifdef PIOS_INCLUDE_RCVR
|
||||
#include <pios_rcvr.h>
|
||||
|
@ -1151,6 +1151,50 @@ static const struct pios_usart_cfg pios_usart_srxl_flexi_cfg = {
|
||||
|
||||
#endif /* PIOS_INCLUDE_SRXL */
|
||||
|
||||
#if defined(PIOS_INCLUDE_IBUS)
|
||||
/*
|
||||
* IBUS USART
|
||||
*/
|
||||
#include <pios_ibus_priv.h>
|
||||
|
||||
static const struct pios_usart_cfg pios_usart_ibus_flexi_cfg = {
|
||||
.regs = USART3,
|
||||
.init = {
|
||||
.USART_BaudRate = 115200,
|
||||
.USART_WordLength = USART_WordLength_8b,
|
||||
.USART_Parity = USART_Parity_No,
|
||||
.USART_StopBits = USART_StopBits_1,
|
||||
.USART_HardwareFlowControl = USART_HardwareFlowControl_None,
|
||||
.USART_Mode = USART_Mode_Rx,
|
||||
},
|
||||
.irq = {
|
||||
.init = {
|
||||
.NVIC_IRQChannel = USART3_IRQn,
|
||||
.NVIC_IRQChannelPreemptionPriority = PIOS_IRQ_PRIO_HIGH,
|
||||
.NVIC_IRQChannelSubPriority = 0,
|
||||
.NVIC_IRQChannelCmd = ENABLE,
|
||||
},
|
||||
},
|
||||
.rx = {
|
||||
.gpio = GPIOB,
|
||||
.init = {
|
||||
.GPIO_Pin = GPIO_Pin_11,
|
||||
.GPIO_Speed = GPIO_Speed_2MHz,
|
||||
.GPIO_Mode = GPIO_Mode_IPU,
|
||||
},
|
||||
},
|
||||
.tx = {
|
||||
.gpio = GPIOB,
|
||||
.init = {
|
||||
.GPIO_Pin = GPIO_Pin_10,
|
||||
.GPIO_Speed = GPIO_Speed_2MHz,
|
||||
.GPIO_Mode = GPIO_Mode_IN_FLOATING,
|
||||
},
|
||||
},
|
||||
};
|
||||
|
||||
#endif /* PIOS_INCLUDE_IBUS */
|
||||
|
||||
#if defined(PIOS_INCLUDE_SBUS)
|
||||
/*
|
||||
* S.Bus USART
|
||||
|
@ -106,6 +106,7 @@
|
||||
#define PIOS_INCLUDE_EXBUS
|
||||
#define PIOS_INCLUDE_SRXL
|
||||
#define PIOS_INCLUDE_HOTT
|
||||
#define PIOS_INCLUDE_IBUS
|
||||
/* #define PIOS_INCLUDE_GCSRCVR */
|
||||
/* #define PIOS_INCLUDE_OPLINKRCVR */
|
||||
|
||||
|
@ -382,7 +382,6 @@ void PIOS_Board_Init(void)
|
||||
break;
|
||||
case HWSETTINGS_USB_VCPPORT_USBTELEMETRY:
|
||||
#if defined(PIOS_INCLUDE_COM)
|
||||
|
||||
{
|
||||
uint32_t pios_usb_cdc_id;
|
||||
if (PIOS_USB_CDC_Init(&pios_usb_cdc_id, &pios_usb_cdc_cfg, pios_usb_id)) {
|
||||
@ -670,6 +669,28 @@ void PIOS_Board_Init(void)
|
||||
#endif /* PIOS_INCLUDE_SRXL */
|
||||
break;
|
||||
|
||||
case HWSETTINGS_CC_FLEXIPORT_IBUS:
|
||||
#if defined(PIOS_INCLUDE_IBUS)
|
||||
{
|
||||
uint32_t pios_usart_ibus_id;
|
||||
if (PIOS_USART_Init(&pios_usart_ibus_id, &pios_usart_ibus_flexi_cfg)) {
|
||||
PIOS_Assert(0);
|
||||
}
|
||||
|
||||
uint32_t pios_ibus_id;
|
||||
if (PIOS_IBUS_Init(&pios_ibus_id, &pios_usart_com_driver, pios_usart_ibus_id)) {
|
||||
PIOS_Assert(0);
|
||||
}
|
||||
|
||||
uint32_t pios_ibus_rcvr_id;
|
||||
if (PIOS_RCVR_Init(&pios_ibus_rcvr_id, &pios_ibus_rcvr_driver, pios_ibus_id)) {
|
||||
PIOS_Assert(0);
|
||||
}
|
||||
pios_rcvr_group_map[MANUALCONTROLSETTINGS_CHANNELGROUPS_IBUS] = pios_ibus_rcvr_id;
|
||||
}
|
||||
#endif /* PIOS_INCLUDE_IBUS */
|
||||
break;
|
||||
|
||||
case HWSETTINGS_CC_FLEXIPORT_DEBUGCONSOLE:
|
||||
#if defined(PIOS_INCLUDE_COM)
|
||||
#if defined(PIOS_INCLUDE_DEBUG_CONSOLE)
|
||||
|
@ -272,6 +272,12 @@ extern uint32_t pios_com_mavlink_id;
|
||||
#define PIOS_SRXL_MAX_DEVS 1
|
||||
#define PIOS_SRXL_NUM_INPUTS 16
|
||||
|
||||
// -------------------------
|
||||
// Receiver FlySky IBus input
|
||||
// -------------------------
|
||||
#define PIOS_IBUS_MAX_DEVS 1
|
||||
#define PIOS_IBUS_NUM_INPUTS 10
|
||||
|
||||
// -------------------------
|
||||
// Servo outputs
|
||||
// -------------------------
|
||||
|
@ -1171,6 +1171,55 @@ static const struct pios_usart_cfg pios_usart_hott_flexi_cfg = {
|
||||
|
||||
#endif /* PIOS_INCLUDE_HOTT */
|
||||
|
||||
#if defined(PIOS_INCLUDE_IBUS)
|
||||
/*
|
||||
* IBUS USART
|
||||
*/
|
||||
#include <pios_ibus_priv.h>
|
||||
|
||||
static const struct pios_usart_cfg pios_usart_ibus_flexi_cfg = {
|
||||
.regs = USART3,
|
||||
.remap = GPIO_AF_USART3,
|
||||
.init = {
|
||||
.USART_BaudRate = 115200,
|
||||
.USART_WordLength = USART_WordLength_8b,
|
||||
.USART_Parity = USART_Parity_No,
|
||||
.USART_StopBits = USART_StopBits_1,
|
||||
.USART_HardwareFlowControl = USART_HardwareFlowControl_None,
|
||||
.USART_Mode = USART_Mode_Rx,
|
||||
},
|
||||
.irq = {
|
||||
.init = {
|
||||
.NVIC_IRQChannel = USART3_IRQn,
|
||||
.NVIC_IRQChannelPreemptionPriority = PIOS_IRQ_PRIO_HIGH,
|
||||
.NVIC_IRQChannelSubPriority = 0,
|
||||
.NVIC_IRQChannelCmd = ENABLE,
|
||||
},
|
||||
},
|
||||
.rx = {
|
||||
.gpio = GPIOB,
|
||||
.init = {
|
||||
.GPIO_Pin = GPIO_Pin_11,
|
||||
.GPIO_Speed = GPIO_Speed_2MHz,
|
||||
.GPIO_Mode = GPIO_Mode_AF,
|
||||
.GPIO_OType = GPIO_OType_PP,
|
||||
.GPIO_PuPd = GPIO_PuPd_UP
|
||||
},
|
||||
},
|
||||
.tx = {
|
||||
.gpio = GPIOB,
|
||||
.init = {
|
||||
.GPIO_Pin = GPIO_Pin_10,
|
||||
.GPIO_Speed = GPIO_Speed_2MHz,
|
||||
.GPIO_Mode = GPIO_Mode_OUT,
|
||||
.GPIO_OType = GPIO_OType_PP,
|
||||
.GPIO_PuPd = GPIO_PuPd_UP
|
||||
},
|
||||
},
|
||||
};
|
||||
|
||||
#endif /* PIOS_INCLUDE_IBUS */
|
||||
|
||||
#if defined(PIOS_INCLUDE_EXBUS)
|
||||
/*
|
||||
* EXBUS USART
|
||||
|
@ -107,6 +107,7 @@
|
||||
#define PIOS_INCLUDE_SRXL
|
||||
#define PIOS_INCLUDE_HOTT
|
||||
#define PIOS_INCLUDE_EXBUS
|
||||
#define PIOS_INCLUDE_IBUS
|
||||
#define PIOS_INCLUDE_GCSRCVR
|
||||
#define PIOS_INCLUDE_OPLINKRCVR
|
||||
#define PIOS_INCLUDE_OPENLRS_RCVR
|
||||
|
@ -586,6 +586,28 @@ void PIOS_Board_Init(void)
|
||||
#endif /* PIOS_INCLUDE_SRXL */
|
||||
break;
|
||||
|
||||
case HWSETTINGS_RM_FLEXIPORT_IBUS:
|
||||
#if defined(PIOS_INCLUDE_IBUS)
|
||||
{
|
||||
uint32_t pios_usart_ibus_id;
|
||||
if (PIOS_USART_Init(&pios_usart_ibus_id, &pios_usart_ibus_flexi_cfg)) {
|
||||
PIOS_Assert(0);
|
||||
}
|
||||
|
||||
uint32_t pios_ibus_id;
|
||||
if (PIOS_IBUS_Init(&pios_ibus_id, &pios_usart_com_driver, pios_usart_ibus_id)) {
|
||||
PIOS_Assert(0);
|
||||
}
|
||||
|
||||
uint32_t pios_ibus_rcvr_id;
|
||||
if (PIOS_RCVR_Init(&pios_ibus_rcvr_id, &pios_ibus_rcvr_driver, pios_ibus_id)) {
|
||||
PIOS_Assert(0);
|
||||
}
|
||||
pios_rcvr_group_map[MANUALCONTROLSETTINGS_CHANNELGROUPS_IBUS] = pios_ibus_rcvr_id;
|
||||
}
|
||||
#endif /* PIOS_INCLUDE_IBUS */
|
||||
break;
|
||||
|
||||
case HWSETTINGS_RM_FLEXIPORT_HOTTSUMD:
|
||||
case HWSETTINGS_RM_FLEXIPORT_HOTTSUMH:
|
||||
#if defined(PIOS_INCLUDE_HOTT)
|
||||
|
@ -634,6 +634,55 @@ static const struct pios_usart_cfg pios_usart_srxl_flexi_cfg = {
|
||||
|
||||
#endif /* PIOS_INCLUDE_SRXL */
|
||||
|
||||
#if defined(PIOS_INCLUDE_IBUS)
|
||||
/*
|
||||
* IBUS USART
|
||||
*/
|
||||
#include <pios_ibus_priv.h>
|
||||
|
||||
static const struct pios_usart_cfg pios_usart_ibus_flexi_cfg = {
|
||||
.regs = FLEXI_USART_REGS,
|
||||
.remap = FLEXI_USART_REMAP,
|
||||
.init = {
|
||||
.USART_BaudRate = 115200,
|
||||
.USART_WordLength = USART_WordLength_8b,
|
||||
.USART_Parity = USART_Parity_No,
|
||||
.USART_StopBits = USART_StopBits_1,
|
||||
.USART_HardwareFlowControl = USART_HardwareFlowControl_None,
|
||||
.USART_Mode = USART_Mode_Rx,
|
||||
},
|
||||
.irq = {
|
||||
.init = {
|
||||
.NVIC_IRQChannel = FLEXI_USART_IRQ,
|
||||
.NVIC_IRQChannelPreemptionPriority = PIOS_IRQ_PRIO_HIGH,
|
||||
.NVIC_IRQChannelSubPriority = 0,
|
||||
.NVIC_IRQChannelCmd = ENABLE,
|
||||
},
|
||||
},
|
||||
.rx = {
|
||||
.gpio = FLEXI_USART_RX_GPIO,
|
||||
.init = {
|
||||
.GPIO_Pin = FLEXI_USART_RX_PIN,
|
||||
.GPIO_Speed = GPIO_Speed_2MHz,
|
||||
.GPIO_Mode = GPIO_Mode_AF,
|
||||
.GPIO_OType = GPIO_OType_PP,
|
||||
.GPIO_PuPd = GPIO_PuPd_UP
|
||||
},
|
||||
},
|
||||
.tx = {
|
||||
.gpio = FLEXI_USART_TX_GPIO,
|
||||
.init = {
|
||||
.GPIO_Pin = FLEXI_USART_TX_PIN,
|
||||
.GPIO_Speed = GPIO_Speed_2MHz,
|
||||
.GPIO_Mode = GPIO_Mode_OUT,
|
||||
.GPIO_OType = GPIO_OType_PP,
|
||||
.GPIO_PuPd = GPIO_PuPd_UP
|
||||
},
|
||||
},
|
||||
};
|
||||
|
||||
#endif /* PIOS_INCLUDE_IBUS */
|
||||
|
||||
#if defined(PIOS_INCLUDE_EXBUS)
|
||||
/*
|
||||
* EXBUS USART
|
||||
@ -681,8 +730,8 @@ static const struct pios_usart_cfg pios_usart_exbus_flexi_cfg = {
|
||||
},
|
||||
};
|
||||
|
||||
|
||||
#endif /* PIOS_INCLUDE_EXBUS */
|
||||
|
||||
/*
|
||||
* HK OSD
|
||||
*/
|
||||
|
@ -733,7 +733,29 @@ void PIOS_Board_Init(void)
|
||||
}
|
||||
pios_rcvr_group_map[MANUALCONTROLSETTINGS_CHANNELGROUPS_SRXL] = pios_srxl_rcvr_id;
|
||||
}
|
||||
#endif
|
||||
#endif /* PIOS_INCLUDE_SRXL */
|
||||
break;
|
||||
|
||||
case HWSETTINGS_RM_FLEXIPORT_IBUS:
|
||||
#if defined(PIOS_INCLUDE_IBUS)
|
||||
{
|
||||
uint32_t pios_usart_ibus_id;
|
||||
if (PIOS_USART_Init(&pios_usart_ibus_id, &pios_usart_ibus_flexi_cfg)) {
|
||||
PIOS_Assert(0);
|
||||
}
|
||||
|
||||
uint32_t pios_ibus_id;
|
||||
if (PIOS_IBUS_Init(&pios_ibus_id, &pios_usart_com_driver, pios_usart_ibus_id)) {
|
||||
PIOS_Assert(0);
|
||||
}
|
||||
|
||||
uint32_t pios_ibus_rcvr_id;
|
||||
if (PIOS_RCVR_Init(&pios_ibus_rcvr_id, &pios_ibus_rcvr_driver, pios_ibus_id)) {
|
||||
PIOS_Assert(0);
|
||||
}
|
||||
pios_rcvr_group_map[MANUALCONTROLSETTINGS_CHANNELGROUPS_IBUS] = pios_ibus_rcvr_id;
|
||||
}
|
||||
#endif /* PIOS_INCLUDE_IBUS */
|
||||
break;
|
||||
|
||||
case HWSETTINGS_RM_FLEXIPORT_HOTTSUMD:
|
||||
|
@ -838,6 +838,86 @@ static const struct pios_usart_cfg pios_usart_srxl_rcvr_cfg = {
|
||||
|
||||
#endif /* PIOS_INCLUDE_SRXL */
|
||||
|
||||
#if defined(PIOS_INCLUDE_IBUS)
|
||||
/*
|
||||
* IBUS USART
|
||||
*/
|
||||
#include <pios_ibus_priv.h>
|
||||
|
||||
static const struct pios_usart_cfg pios_usart_ibus_flexi_cfg = {
|
||||
.regs = USART3,
|
||||
.remap = GPIO_AF_USART3,
|
||||
.init = {
|
||||
.USART_BaudRate = 115200,
|
||||
.USART_WordLength = USART_WordLength_8b,
|
||||
.USART_Parity = USART_Parity_No,
|
||||
.USART_StopBits = USART_StopBits_1,
|
||||
.USART_HardwareFlowControl = USART_HardwareFlowControl_None,
|
||||
.USART_Mode = USART_Mode_Rx,
|
||||
},
|
||||
.irq = {
|
||||
.init = {
|
||||
.NVIC_IRQChannel = USART3_IRQn,
|
||||
.NVIC_IRQChannelPreemptionPriority = PIOS_IRQ_PRIO_HIGH,
|
||||
.NVIC_IRQChannelSubPriority = 0,
|
||||
.NVIC_IRQChannelCmd = ENABLE,
|
||||
},
|
||||
},
|
||||
.rx = {
|
||||
.gpio = GPIOB,
|
||||
.init = {
|
||||
.GPIO_Pin = GPIO_Pin_11,
|
||||
.GPIO_Speed = GPIO_Speed_2MHz,
|
||||
.GPIO_Mode = GPIO_Mode_AF,
|
||||
.GPIO_OType = GPIO_OType_PP,
|
||||
.GPIO_PuPd = GPIO_PuPd_UP
|
||||
},
|
||||
},
|
||||
.tx = {
|
||||
.gpio = GPIOB,
|
||||
.init = {
|
||||
.GPIO_Pin = GPIO_Pin_10,
|
||||
.GPIO_Speed = GPIO_Speed_2MHz,
|
||||
.GPIO_Mode = GPIO_Mode_OUT,
|
||||
.GPIO_OType = GPIO_OType_PP,
|
||||
.GPIO_PuPd = GPIO_PuPd_UP
|
||||
},
|
||||
},
|
||||
};
|
||||
|
||||
static const struct pios_usart_cfg pios_usart_ibus_rcvr_cfg = {
|
||||
.regs = USART6,
|
||||
.remap = GPIO_AF_USART6,
|
||||
.init = {
|
||||
.USART_BaudRate = 115200,
|
||||
.USART_WordLength = USART_WordLength_8b,
|
||||
.USART_Parity = USART_Parity_No,
|
||||
.USART_StopBits = USART_StopBits_1,
|
||||
.USART_HardwareFlowControl = USART_HardwareFlowControl_None,
|
||||
.USART_Mode = USART_Mode_Rx,
|
||||
},
|
||||
.irq = {
|
||||
.init = {
|
||||
.NVIC_IRQChannel = USART6_IRQn,
|
||||
.NVIC_IRQChannelPreemptionPriority = PIOS_IRQ_PRIO_HIGH,
|
||||
.NVIC_IRQChannelSubPriority = 0,
|
||||
.NVIC_IRQChannelCmd = ENABLE,
|
||||
},
|
||||
},
|
||||
.rx = {
|
||||
.gpio = GPIOC,
|
||||
.init = {
|
||||
.GPIO_Pin = GPIO_Pin_7,
|
||||
.GPIO_Speed = GPIO_Speed_2MHz,
|
||||
.GPIO_Mode = GPIO_Mode_AF,
|
||||
.GPIO_OType = GPIO_OType_PP,
|
||||
.GPIO_PuPd = GPIO_PuPd_UP
|
||||
},
|
||||
},
|
||||
};
|
||||
|
||||
#endif /* PIOS_INCLUDE_IBUS */
|
||||
|
||||
// these were copied from Revo support
|
||||
// they might need to be further modified for Sparky2 support
|
||||
#if defined(PIOS_INCLUDE_HOTT)
|
||||
|
@ -111,6 +111,7 @@
|
||||
#define PIOS_INCLUDE_SRXL
|
||||
#define PIOS_INCLUDE_HOTT
|
||||
#define PIOS_INCLUDE_EXBUS
|
||||
#define PIOS_INCLUDE_IBUS
|
||||
#define PIOS_INCLUDE_GCSRCVR
|
||||
#define PIOS_INCLUDE_OPLINKRCVR
|
||||
#define PIOS_INCLUDE_OPENLRS_RCVR
|
||||
|
@ -327,6 +327,27 @@ static void PIOS_Board_configure_srxl(const struct pios_usart_cfg *usart_cfg)
|
||||
pios_rcvr_group_map[MANUALCONTROLSETTINGS_CHANNELGROUPS_SRXL] = pios_srxl_rcvr_id;
|
||||
}
|
||||
|
||||
static void PIOS_Board_configure_ibus(const struct pios_usart_cfg *usart_cfg)
|
||||
{
|
||||
uint32_t pios_usart_ibus_id;
|
||||
|
||||
if (PIOS_USART_Init(&pios_usart_ibus_id, usart_cfg)) {
|
||||
PIOS_Assert(0);
|
||||
}
|
||||
|
||||
uint32_t pios_ibus_id;
|
||||
if (PIOS_IBUS_Init(&pios_ibus_id, &pios_usart_com_driver, pios_usart_ibus_id)) {
|
||||
PIOS_Assert(0);
|
||||
}
|
||||
|
||||
uint32_t pios_ibus_rcvr_id;
|
||||
if (PIOS_RCVR_Init(&pios_ibus_rcvr_id, &pios_ibus_rcvr_driver, pios_ibus_id)) {
|
||||
PIOS_Assert(0);
|
||||
}
|
||||
|
||||
pios_rcvr_group_map[MANUALCONTROLSETTINGS_CHANNELGROUPS_IBUS] = pios_ibus_rcvr_id;
|
||||
}
|
||||
|
||||
|
||||
static void PIOS_Board_configure_exbus(const struct pios_usart_cfg *usart_cfg)
|
||||
{
|
||||
@ -582,6 +603,12 @@ void PIOS_Board_Init(void)
|
||||
#endif /* PIOS_INCLUDE_SRXL */
|
||||
break;
|
||||
|
||||
case HWSETTINGS_SPK2_FLEXIPORT_IBUS:
|
||||
#if defined(PIOS_INCLUDE_IBUS)
|
||||
PIOS_Board_configure_ibus(&pios_usart_ibus_flexi_cfg);
|
||||
#endif /* PIOS_INCLUDE_IBUS */
|
||||
break;
|
||||
|
||||
case HWSETTINGS_SPK2_FLEXIPORT_HOTTSUMD:
|
||||
case HWSETTINGS_SPK2_FLEXIPORT_HOTTSUMH:
|
||||
#if defined(PIOS_INCLUDE_HOTT)
|
||||
@ -926,7 +953,7 @@ void PIOS_Board_Init(void)
|
||||
|
||||
// Configure the receiver port
|
||||
// Sparky2 receiver input on PC7 TIM8 CH2
|
||||
// include PPM,S.Bus,DSM,SRXL,EX.Bus,HoTT SUMD,HoTT SUMH
|
||||
// include PPM,S.Bus,DSM,SRXL,IBus,EX.Bus,HoTT SUMD,HoTT SUMH
|
||||
uint8_t hwsettings_rcvrport;
|
||||
HwSettingsSPK2_RcvrPortGet(&hwsettings_rcvrport);
|
||||
|
||||
@ -962,6 +989,11 @@ void PIOS_Board_Init(void)
|
||||
PIOS_Board_configure_srxl(&pios_usart_srxl_rcvr_cfg);
|
||||
#endif /* PIOS_INCLUDE_SRXL */
|
||||
break;
|
||||
case HWSETTINGS_SPK2_RCVRPORT_IBUS:
|
||||
#if defined(PIOS_INCLUDE_IBUS)
|
||||
PIOS_Board_configure_ibus(&pios_usart_ibus_rcvr_cfg);
|
||||
#endif /* PIOS_INCLUDE_IBUS */
|
||||
break;
|
||||
case HWSETTINGS_SPK2_RCVRPORT_HOTTSUMD:
|
||||
case HWSETTINGS_SPK2_RCVRPORT_HOTTSUMH:
|
||||
#if defined(PIOS_INCLUDE_HOTT)
|
||||
|
@ -146,6 +146,9 @@ void InputChannelForm::groupUpdated()
|
||||
case ManualControlSettings::CHANNELGROUPS_OPLINK:
|
||||
count = 8; // Need to make this 6 for CC
|
||||
break;
|
||||
case ManualControlSettings::CHANNELGROUPS_IBUS:
|
||||
count = 10;
|
||||
break;
|
||||
case ManualControlSettings::CHANNELGROUPS_DSMMAINPORT:
|
||||
case ManualControlSettings::CHANNELGROUPS_DSMFLEXIPORT:
|
||||
case ManualControlSettings::CHANNELGROUPS_DSMRCVRPORT:
|
||||
|
@ -3,7 +3,7 @@
|
||||
<description>Selection of optional hardware configurations.</description>
|
||||
<field name="CC_RcvrPort" units="function" type="enum" elements="1" options="Disabled+OneShot,PWM+NoOneShot,PPM+NoOneShot,PPM+PWM+NoOneShot,PPM+Outputs+NoOneShot,PPM_PIN8+OneShot, Outputs+OneShot" defaultvalue="PWM+NoOneShot"/>
|
||||
<field name="CC_MainPort" units="function" type="enum" elements="1" options="Disabled,Telemetry,GPS,S.Bus,DSM,DebugConsole,ComBridge,OsdHk,MSP,MAVLink" defaultvalue="Telemetry"/>
|
||||
<field name="CC_FlexiPort" units="function" type="enum" elements="1" options="Disabled,Telemetry,GPS,I2C,PPM,DSM,EX.Bus,HoTT SUMD,HoTT SUMH,SRXL,DebugConsole,ComBridge,OsdHk,MSP,MAVLink" defaultvalue="Disabled"/>
|
||||
<field name="CC_FlexiPort" units="function" type="enum" elements="1" options="Disabled,Telemetry,GPS,I2C,PPM,DSM,EX.Bus,HoTT SUMD,HoTT SUMH,SRXL,IBus,DebugConsole,ComBridge,OsdHk,MSP,MAVLink" defaultvalue="Disabled"/>
|
||||
<field name="RV_RcvrPort" units="function" type="enum" elements="1" options="Disabled,PWM,PPM,PPM+Outputs,Outputs" defaultvalue="PWM"/>
|
||||
<field name="RV_AuxPort" units="function" type="enum" elements="1" options="Disabled,Telemetry,DSM,ComAux,ComBridge,OsdHk,MSP,MAVLink" defaultvalue="Disabled"/>
|
||||
<field name="RV_AuxSBusPort" units="function" type="enum" elements="1" options="Disabled,S.Bus,DSM,ComAux,ComBridge,OsdHk,MSP,MAVLink" defaultvalue="Disabled"/>
|
||||
@ -15,11 +15,11 @@
|
||||
defaultvalue="PWM"
|
||||
limits="%0905NE:PPM+PWM:PPM+Telemetry:Telemetry:ComBridge:MSP:MAVLink;"/>
|
||||
<field name="RM_MainPort" units="function" type="enum" elements="1" options="Disabled,Telemetry,GPS,S.Bus,DSM,DebugConsole,ComBridge,OsdHk,MSP,MAVLink" defaultvalue="Disabled"/>
|
||||
<field name="RM_FlexiPort" units="function" type="enum" elements="1" options="Disabled,Telemetry,GPS,I2C,DSM,EX.Bus,HoTT SUMD,HoTT SUMH,SRXL,DebugConsole,ComBridge,OsdHk,MSP,MAVLink" defaultvalue="Disabled"/>
|
||||
<field name="RM_FlexiPort" units="function" type="enum" elements="1" options="Disabled,Telemetry,GPS,I2C,DSM,EX.Bus,HoTT SUMD,HoTT SUMH,SRXL,IBus,DebugConsole,ComBridge,OsdHk,MSP,MAVLink" defaultvalue="Disabled"/>
|
||||
|
||||
<field name="SPK2_RcvrPort" units="function" type="enum" elements="1" options="Disabled,PPM,S.Bus,DSM,SRXL,EX.Bus,HoTT SUMD,HoTT SUMH" defaultvalue="PPM"/>
|
||||
<field name="SPK2_RcvrPort" units="function" type="enum" elements="1" options="Disabled,PPM,S.Bus,DSM,SRXL,IBus,EX.Bus,HoTT SUMD,HoTT SUMH" defaultvalue="PPM"/>
|
||||
<field name="SPK2_MainPort" units="function" type="enum" elements="1" options="Disabled,Telemetry,GPS,DSM,DebugConsole,ComBridge,OsdHk,MSP,MAVLink" defaultvalue="Disabled"/>
|
||||
<field name="SPK2_FlexiPort" units="function" type="enum" elements="1" options="Disabled,Telemetry,GPS,I2C,DSM,EX.Bus,HoTT SUMD,HoTT SUMH,SRXL,DebugConsole,ComBridge,OsdHk,MSP,MAVLink" defaultvalue="Disabled"/>
|
||||
<field name="SPK2_FlexiPort" units="function" type="enum" elements="1" options="Disabled,Telemetry,GPS,I2C,DSM,EX.Bus,HoTT SUMD,HoTT SUMH,SRXL,IBus,DebugConsole,ComBridge,OsdHk,MSP,MAVLink" defaultvalue="Disabled"/>
|
||||
<field name="SPK2_I2CPort" units="function" type="enum" elements="1" options="Disabled,I2C" defaultvalue="Disabled"/>
|
||||
|
||||
<field name="TelemetrySpeed" units="bps" type="enum" elements="1" options="2400,4800,9600,19200,38400,57600,115200" defaultvalue="57600"/>
|
||||
|
@ -3,7 +3,7 @@
|
||||
<description>Settings to indicate how to decode receiver input by @ref ManualControlModule.</description>
|
||||
<field name="ChannelGroups" units="Channel Group" type="enum"
|
||||
elementnames="Throttle,Roll,Pitch,Yaw,FlightMode,Collective,Accessory0,Accessory1,Accessory2,Accessory3"
|
||||
options="PWM,PPM,DSM (MainPort),DSM (FlexiPort),DSM (RcvrPort),S.Bus,EX.Bus,HoTT,SRXL,GCS,OPLink,OpenLRS,None" defaultvalue="None"/>
|
||||
options="PWM,PPM,DSM (MainPort),DSM (FlexiPort),DSM (RcvrPort),S.Bus,EX.Bus,HoTT,SRXL,IBus,GCS,OPLink,OpenLRS,None" defaultvalue="None"/>
|
||||
<field name="ChannelNumber" units="channel" type="uint8" defaultvalue="0"
|
||||
elementnames="Throttle,Roll,Pitch,Yaw,FlightMode,Collective,Accessory0,Accessory1,Accessory2,Accessory3"/>
|
||||
<field name="ChannelMin" units="us" type="int16" defaultvalue="1000"
|
||||
|
@ -2,7 +2,7 @@
|
||||
<object name="ReceiverActivity" singleinstance="true" settings="false" category="System">
|
||||
<description>Monitors which receiver channels have been active within the last second.</description>
|
||||
<field name="ActiveGroup" units="Channel Group" type="enum" elements="1"
|
||||
options="PWM,PPM,DSM (MainPort),DSM (FlexiPort),DSM (RcvrPort),S.Bus,EX.Bus,HoTT,SRXL,GCS,OPLink,OpenLRS,None"
|
||||
options="PWM,PPM,DSM (MainPort),DSM (FlexiPort),DSM (RcvrPort),S.Bus,EX.Bus,HoTT,SRXL,IBus,GCS,OPLink,OpenLRS,None"
|
||||
defaultvalue="None"/>
|
||||
<field name="ActiveChannel" units="channel" type="uint8" elements="1"
|
||||
defaultvalue="255"/>
|
||||
|
Loading…
x
Reference in New Issue
Block a user