1
0
mirror of https://bitbucket.org/librepilot/librepilot.git synced 2025-01-18 03:52:11 +01:00

Merge branch 'thread/LP-104_LP-196_HoTT_and_Ex.Bus_Support_15.09' into thread/LP-104_LP-196_HoTT_and_Ex.Bus_Support

This commit is contained in:
Fredrik Arvidsson 2016-01-09 19:18:48 +01:00
commit d32cc0e7fb
25 changed files with 1550 additions and 22 deletions

View File

@ -34,7 +34,7 @@ FLIGHTLIBINC = $(FLIGHTLIB)/inc
OPUAVOBJINC = $(OPUAVOBJ)/inc
OPUAVTALKINC = $(OPUAVTALK)/inc
## PID
## PID
PIDLIB =$(FLIGHTLIB)/pid
PIDLIBINC =$(FLIGHTLIB)/pid
@ -86,7 +86,9 @@ SRC += $(PIOSCOMMON)/pios_rfm22b.c
SRC += $(PIOSCOMMON)/pios_rfm22b_com.c
SRC += $(PIOSCOMMON)/pios_rcvr.c
SRC += $(PIOSCOMMON)/pios_sbus.c
SRC += $(PIOSCOMMON)/pios_hott.c
SRC += $(PIOSCOMMON)/pios_srxl.c
SRC += $(PIOSCOMMON)/pios_exbus.c
SRC += $(PIOSCOMMON)/pios_sdcard.c
SRC += $(PIOSCOMMON)/pios_sensors.c

View File

@ -655,9 +655,15 @@ static bool updateRcvrActivityCompare(uint32_t rcvr_id, struct rcvr_activity_fsm
case MANUALCONTROLSETTINGS_CHANNELGROUPS_DSMFLEXIPORT:
group = RECEIVERACTIVITY_ACTIVEGROUP_DSMFLEXIPORT;
break;
case MANUALCONTROLSETTINGS_CHANNELGROUPS_EXBUS:
group = RECEIVERACTIVITY_ACTIVEGROUP_EXBUS;
break;
case MANUALCONTROLSETTINGS_CHANNELGROUPS_SBUS:
group = RECEIVERACTIVITY_ACTIVEGROUP_SBUS;
break;
case MANUALCONTROLSETTINGS_CHANNELGROUPS_HOTT:
group = RECEIVERACTIVITY_ACTIVEGROUP_HOTT;
break;
case MANUALCONTROLSETTINGS_CHANNELGROUPS_SRXL:
group = RECEIVERACTIVITY_ACTIVEGROUP_SRXL;
break;

View File

@ -0,0 +1,439 @@
/**
******************************************************************************
* @file pios_exbus.c
* @author The LibrePilot Project, http://www.librepilot.org Copyright (C) 2015.
* Tau Labs, http://taulabs.org, Copyright (C) 2013
* @addtogroup PIOS PIOS Core hardware abstraction layer
* @{
* @addtogroup PIOS_EXBUS Jeti EX Bus receiver functions
* @{
* @brief Jeti EX Bus receiver functions
*****************************************************************************/
/*
* 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
*/
/* Project Includes */
#include "pios_exbus_priv.h"
#if defined(PIOS_INCLUDE_EXBUS)
#if !defined(PIOS_INCLUDE_RTC)
#error PIOS_INCLUDE_RTC must be used to use EXBUS
#endif
/**
* Based on Jeti EX Bus protocol version 1.21
* Available at http://www.jetimodel.com/en/Telemetry-Protocol/
*/
/* EXBUS frame size and contents definitions */
#define EXBUS_HEADER_LENGTH 4
#define EXBUS_CRC_LENGTH 2
#define EXBUS_MAX_CHANNELS 16
#define EXBUS_OVERHEAD_LENGTH (EXBUS_HEADER_LENGTH + EXBUS_CRC_LENGTH)
#define EXBUS_MAX_FRAME_LENGTH (EXBUS_MAX_CHANNELS*2+10 + EXBUS_OVERHEAD_LENGTH)
#define EXBUS_SYNC_CHANNEL 0x3E
#define EXBUS_SYNC_TELEMETRY 0x3D
#define EXBUS_BYTE_REQ 0x01
#define EXBUS_BYTE_NOREQ 0x03
#define EXBUS_DATA_CHANNEL 0x31
#define EXBUS_DATA_TELEMETRY 0x3A
#define EXBUS_DATA_JETIBOX 0x3B
#define EXBUS_LOW_BAUD_RATE 125000
#define EXBUS_HIGH_BAUD_RATE 250000
#define EXBUS_BAUD_RATE_LIMIT 64
/* Forward Declarations */
static int32_t PIOS_EXBUS_Get(uint32_t rcvr_id, uint8_t channel);
static uint16_t PIOS_EXBUS_RxInCallback(uint32_t context,
uint8_t *buf,
uint16_t buf_len,
uint16_t *headroom,
bool *need_yield);
static void PIOS_EXBUS_Supervisor(uint32_t exbus_id);
static uint16_t PIOS_EXBUS_CRC_Update(uint16_t crc, uint8_t data);
/* Local Variables */
const struct pios_rcvr_driver pios_exbus_rcvr_driver = {
.read = PIOS_EXBUS_Get,
};
enum pios_exbus_dev_magic {
PIOS_EXBUS_DEV_MAGIC = 0x485355FF,
};
enum pios_exbus_frame_state {
EXBUS_STATE_SYNC,
EXBUS_STATE_REQ,
EXBUS_STATE_LEN,
EXBUS_STATE_PACKET_ID,
EXBUS_STATE_DATA_ID,
EXBUS_STATE_SUBLEN,
EXBUS_STATE_DATA
};
struct pios_exbus_state {
uint16_t channel_data[PIOS_EXBUS_NUM_INPUTS];
uint8_t received_data[EXBUS_MAX_FRAME_LENGTH];
uint8_t receive_timer;
uint8_t failsafe_timer;
uint8_t failsafe_count;
uint8_t byte_count;
uint8_t frame_length;
uint16_t crc;
bool high_baud_rate;
bool frame_found;
};
struct pios_exbus_dev {
enum pios_exbus_dev_magic magic;
uint32_t com_port_id;
const struct pios_com_driver *driver;
struct pios_exbus_state state;
};
/* Allocate EXBUS device descriptor */
#if defined(PIOS_INCLUDE_FREERTOS)
static struct pios_exbus_dev *PIOS_EXBUS_Alloc(void)
{
struct pios_exbus_dev *exbus_dev;
exbus_dev = (struct pios_exbus_dev *)pios_malloc(sizeof(*exbus_dev));
if (!exbus_dev)
return NULL;
exbus_dev->magic = PIOS_EXBUS_DEV_MAGIC;
return exbus_dev;
}
#else
static struct pios_exbus_dev pios_exbus_devs[PIOS_EXBUS_MAX_DEVS];
static uint8_t pios_exbus_num_devs;
static struct pios_exbus_dev *PIOS_EXBUS_Alloc(void)
{
struct pios_exbus_dev *exbus_dev;
if (pios_exbus_num_devs >= PIOS_EXBUS_MAX_DEVS)
return NULL;
exbus_dev = &pios_exbus_devs[pios_exbus_num_devs++];
exbus_dev->magic = PIOS_EXBUS_DEV_MAGIC;
return exbus_dev;
}
#endif
/* Validate EXBUS device descriptor */
static bool PIOS_EXBUS_Validate(struct pios_exbus_dev *exbus_dev)
{
return (exbus_dev->magic == PIOS_EXBUS_DEV_MAGIC);
}
/* Reset channels in case of lost signal or explicit failsafe receiver flag */
static void PIOS_EXBUS_ResetChannels(struct pios_exbus_dev *exbus_dev)
{
struct pios_exbus_state *state = &(exbus_dev->state);
for (int i = 0; i < PIOS_EXBUS_NUM_INPUTS; i++) {
state->channel_data[i] = PIOS_RCVR_TIMEOUT;
}
}
/* Reset EXBUS receiver state */
static void PIOS_EXBUS_ResetState(struct pios_exbus_dev *exbus_dev)
{
struct pios_exbus_state *state = &(exbus_dev->state);
state->receive_timer = 0;
state->failsafe_timer = 0;
state->failsafe_count = 0;
state->high_baud_rate = false;
state->frame_found = false;
PIOS_EXBUS_ResetChannels(exbus_dev);
}
/**
* Check and unroll complete frame data.
* \output 0 frame data accepted
* \output -1 frame error found
*/
static int PIOS_EXBUS_UnrollChannels(struct pios_exbus_dev *exbus_dev)
{
struct pios_exbus_state *state = &(exbus_dev->state);
if(state->crc != 0) {
/* crc failed */
DEBUG_PRINTF(2, "Jeti CRC error!%d\r\n");
return -1;
}
enum pios_exbus_frame_state exbus_state = EXBUS_STATE_SYNC;
uint8_t *byte = state->received_data;
uint8_t sub_length;
uint8_t n_channels = 0;
uint8_t channel = 0;
while((byte - state->received_data) < state->frame_length) {
switch(exbus_state) {
case EXBUS_STATE_SYNC:
/* sync byte */
if(*byte == EXBUS_SYNC_CHANNEL) {
exbus_state = EXBUS_STATE_REQ;
}
else {
return -1;
}
byte += sizeof(uint8_t);
break;
case EXBUS_STATE_REQ:
/*
* tells us whether the rx is requesting a reply or not,
* currently nothing is actually done with this information...
*/
if(*byte == EXBUS_BYTE_REQ) {
exbus_state = EXBUS_STATE_LEN;
}
else if(*byte == EXBUS_BYTE_NOREQ) {
exbus_state = EXBUS_STATE_LEN;
}
else {
return -1;
}
byte += sizeof(uint8_t);
break;
case EXBUS_STATE_LEN:
/* total frame length */
exbus_state = EXBUS_STATE_PACKET_ID;
byte += sizeof(uint8_t);
break;
case EXBUS_STATE_PACKET_ID:
/* packet id */
exbus_state = EXBUS_STATE_DATA_ID;
byte += sizeof(uint8_t);
break;
case EXBUS_STATE_DATA_ID:
/* checks the type of data, ignore non-rc data */
if(*byte == EXBUS_DATA_CHANNEL) {
exbus_state = EXBUS_STATE_SUBLEN;
}
else {
return -1;
}
byte += sizeof(uint8_t);
break;
case EXBUS_STATE_SUBLEN:
sub_length = *byte;
n_channels = sub_length / 2;
exbus_state = EXBUS_STATE_DATA;
byte += sizeof(uint8_t);
break;
case EXBUS_STATE_DATA:
if(channel < n_channels) {
/* 1 lsb = 1/8 us */
state->channel_data[channel++] = (byte[1] << 8 | byte[0]) / 8;
}
byte += sizeof(uint16_t);
break;
}
}
return 0;
}
/* Update decoder state processing input byte from the stream */
static void PIOS_EXBUS_UpdateState(struct pios_exbus_dev *exbus_dev, uint8_t byte)
{
struct pios_exbus_state *state = &(exbus_dev->state);
if(!state->frame_found) {
if(byte == EXBUS_SYNC_CHANNEL) {
state->frame_found = true;
state->byte_count = 0;
state->frame_length = EXBUS_MAX_FRAME_LENGTH;
state->crc = PIOS_EXBUS_CRC_Update(0, byte);
state->received_data[state->byte_count++] = byte;
}
}
else if(state->byte_count < EXBUS_MAX_FRAME_LENGTH) {
state->crc = PIOS_EXBUS_CRC_Update(state->crc, byte);
state->received_data[state->byte_count++] = byte;
if(state->byte_count == 3) {
state->frame_length = byte;
}
if(state->byte_count == state->frame_length) {
if (!PIOS_EXBUS_UnrollChannels(exbus_dev)) {
/* data looking good */
state->failsafe_timer = 0;
state->failsafe_count = 0;
}
/* get ready for the next frame */
state->frame_found = false;
}
}
else {
state->frame_found = false;
}
}
/* Initialise EX Bus receiver interface */
int32_t PIOS_EXBUS_Init(uint32_t *exbus_id,
const struct pios_com_driver *driver,
uint32_t lower_id)
{
PIOS_DEBUG_Assert(exbus_id);
PIOS_DEBUG_Assert(driver);
struct pios_exbus_dev *exbus_dev;
exbus_dev = (struct pios_exbus_dev *)PIOS_EXBUS_Alloc();
if (!exbus_dev)
return -1;
PIOS_EXBUS_ResetState(exbus_dev);
*exbus_id = (uint32_t)exbus_dev;
/* Set comm driver callback */
(driver->bind_rx_cb)(lower_id, PIOS_EXBUS_RxInCallback, *exbus_id);
if (!PIOS_RTC_RegisterTickCallback(PIOS_EXBUS_Supervisor, *exbus_id)) {
PIOS_DEBUG_Assert(0);
}
exbus_dev->driver = driver;
exbus_dev->com_port_id = lower_id;
return 0;
}
/* Comm byte received callback */
static uint16_t PIOS_EXBUS_RxInCallback(uint32_t context,
uint8_t *buf,
uint16_t buf_len,
uint16_t *headroom,
bool *need_yield)
{
struct pios_exbus_dev *exbus_dev = (struct pios_exbus_dev *)context;
bool valid = PIOS_EXBUS_Validate(exbus_dev);
PIOS_Assert(valid);
/* process byte(s) and clear receive timer */
for (uint8_t i = 0; i < buf_len; i++) {
PIOS_EXBUS_UpdateState(exbus_dev, buf[i]);
exbus_dev->state.receive_timer = 0;
}
/* Always signal that we can accept more data */
if (headroom)
*headroom = EXBUS_MAX_FRAME_LENGTH;
/* We never need a yield */
*need_yield = false;
/* Always indicate that all bytes were consumed */
return buf_len;
}
/**
* Get the value of an input channel
* \param[in] channel Number of the channel desired (zero based)
* \output PIOS_RCVR_INVALID channel not available
* \output PIOS_RCVR_TIMEOUT failsafe condition or missing receiver
* \output >=0 channel value
*/
static int32_t PIOS_EXBUS_Get(uint32_t rcvr_id, uint8_t channel)
{
struct pios_exbus_dev *exbus_dev = (struct pios_exbus_dev *)rcvr_id;
if (!PIOS_EXBUS_Validate(exbus_dev))
return PIOS_RCVR_INVALID;
/* return error if channel is not available */
if (channel >= PIOS_EXBUS_NUM_INPUTS)
return PIOS_RCVR_INVALID;
/* may also be PIOS_RCVR_TIMEOUT set by other function */
return exbus_dev->state.channel_data[channel];
}
static void PIOS_EXBUS_Change_BaudRate(struct pios_exbus_dev *device) {
struct pios_exbus_state *state = &(device->state);
if (++state->failsafe_count >= EXBUS_BAUD_RATE_LIMIT) {
state->high_baud_rate = !state->high_baud_rate;
(device->driver->set_baud) (device->com_port_id,
state->high_baud_rate ? EXBUS_HIGH_BAUD_RATE : EXBUS_LOW_BAUD_RATE);
state->failsafe_count = 0;
}
}
/**
* Input data supervisor is called periodically and provides
* two functions: frame syncing and failsafe triggering.
*
* EX.Bus frames come at 20ms or 10ms rate at 125 or 250 kbaud.
* RTC timer is running at 625Hz (1.6ms). So with divider 5 it gives
* 8ms pause between frames which is good for both EX.Bus frame rates.
*
* Data receive function must clear the receive_timer to confirm new
* data reception. If no new data received in 100ms, we must call the
* failsafe function which clears all channels.
*/
static void PIOS_EXBUS_Supervisor(uint32_t exbus_id)
{
struct pios_exbus_dev *exbus_dev = (struct pios_exbus_dev *)exbus_id;
bool valid = PIOS_EXBUS_Validate(exbus_dev);
PIOS_Assert(valid);
struct pios_exbus_state *state = &(exbus_dev->state);
/* waiting for new frame if no bytes were received in 8ms */
if (++state->receive_timer > 4) {
state->frame_found = false;
state->byte_count = 0;
state->receive_timer = 0;
state->frame_length = EXBUS_MAX_FRAME_LENGTH;
}
/* activate failsafe if no frames have arrived in 102.4ms */
if (++state->failsafe_timer > 64) {
PIOS_EXBUS_ResetChannels(exbus_dev);
state->failsafe_timer = 0;
PIOS_EXBUS_Change_BaudRate(exbus_dev);
}
}
static uint16_t PIOS_EXBUS_CRC_Update(uint16_t crc, uint8_t data)
{
data ^= (uint8_t)crc & (uint8_t)0xFF;
data ^= data << 4;
crc = ((((uint16_t)data << 8) | ((crc & 0xFF00) >> 8))
^ (uint8_t)(data >> 4) ^ ((uint16_t)data << 3));
return crc;
}
#endif /* PIOS_INCLUDE_EXBUS */
/**
* @}
* @}
*/

View File

@ -0,0 +1,419 @@
/**
******************************************************************************
* @file pios_hott.c
* @author The LibrePilot Project, http://www.librepilot.org, Copyright (c) 2015
* @author Tau Labs, http://taulabs.org, Copyright (C) 2013-2014
* @addtogroup PIOS PIOS Core hardware abstraction layer
* @{
* @addtogroup PIOS_HOTT Graupner HoTT receiver functions
* @{
* @brief Graupner HoTT receiver functions for SUMD/H
*****************************************************************************/
/*
* 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
*/
/* Project Includes */
#include "pios_hott_priv.h"
#if defined(PIOS_INCLUDE_HOTT)
#if !defined(PIOS_INCLUDE_RTC)
#error PIOS_INCLUDE_RTC must be used to use HOTT
#endif
/**
* HOTT protocol documentation
*
* Currently known Graupner HoTT serial port settings:
* 115200bps serial stream, 8 bits, no parity, 1 stop bit
* size of each frame: 11..37 bytes
* data resolution: 14 bit
* frame period: 11ms or 22ms
*
* Currently known SUMD/SUMH frame structure:
* Section Byte_Number Byte_Name Byte_Value Remark
* Header 0 Vendor_ID 0xA8 Graupner
* Header 1 Status 0x00 valid and live SUMH data frame
* 0x01 valid and live SUMD data frame
* 0x81 valid SUMD/H data frame with
* transmitter in fail safe condition
* others invalid frame
* Header 2 N_Channels 0x02..0x20 number of transmitted channels
* Data n*2+1 Channel n MSB 0x00..0xff High Byte of channel n data
* Data n*2+2 Channel n LSB 0x00..0xff Low Byte of channel n data
* SUMD_CRC (N_Channels+1)*2+1 CRC High Byte 0x00..0xff High Byte of 16 Bit CRC
* SUMD_CRC (N_Channels+1)*2+2 CRC Low Byte 0x00..0xff Low Byte of 16 Bit CRC
* SUMH_Telemetry (N_Channels+1)*2+1 Telemetry_Req 0x00..0xff 0x00 no telemetry request
* SUMH_CRC (N_Channels+1)*2+2 CRC Byte 0x00..0xff Low Byte of all added data bytes
* Channel Data Interpretation
* Stick Positon Channel Data Remark
* ext. low (-150%) 0x1c20 900µs
* low (-100%) 0x2260 1100µs
* neutral (0%) 0x2ee0 1500µs
* high (100%) 0x3b60 1900µs
* ext. high(150%) 0x41a0 2100µs
* Channel Mapping (not sure)
* 1 Pitch
* 2 Aileron
* 3 Elevator
* 4 Yaw
* 5 Aux/Gyro on MX-12
* 6 ESC
* 7 Aux/Gyr
*/
/* HOTT frame size and contents definitions */
#define HOTT_HEADER_LENGTH 3
#define HOTT_CRC_LENGTH 2
#define HOTT_MAX_CHANNELS_PER_FRAME 32
#define HOTT_OVERHEAD_LENGTH (HOTT_HEADER_LENGTH+HOTT_CRC_LENGTH)
#define HOTT_MAX_FRAME_LENGTH (HOTT_MAX_CHANNELS_PER_FRAME*2+HOTT_OVERHEAD_LENGTH)
#define HOTT_GRAUPNER_ID 0xA8
#define HOTT_STATUS_LIVING_SUMH 0x00
#define HOTT_STATUS_LIVING_SUMD 0x01
#define HOTT_STATUS_FAILSAFE 0x81
/* Forward Declarations */
static int32_t PIOS_HOTT_Get(uint32_t rcvr_id, uint8_t channel);
static uint16_t PIOS_HOTT_RxInCallback(uint32_t context,
uint8_t *buf,
uint16_t buf_len,
uint16_t *headroom,
bool *need_yield);
static void PIOS_HOTT_Supervisor(uint32_t hott_id);
/* Local Variables */
const struct pios_rcvr_driver pios_hott_rcvr_driver = {
.read = PIOS_HOTT_Get,
};
enum pios_hott_dev_magic {
PIOS_HOTT_DEV_MAGIC = 0x4853554D,
};
struct pios_hott_state {
uint16_t channel_data[PIOS_HOTT_NUM_INPUTS];
uint8_t received_data[HOTT_MAX_FRAME_LENGTH];
uint8_t receive_timer;
uint8_t failsafe_timer;
uint8_t frame_found;
uint8_t tx_connected;
uint8_t byte_count;
uint8_t frame_length;
};
struct pios_hott_dev {
enum pios_hott_dev_magic magic;
const struct pios_hott_cfg *cfg;
enum pios_hott_proto proto;
struct pios_hott_state state;
};
/* Allocate HOTT device descriptor */
#if defined(PIOS_INCLUDE_FREERTOS)
static struct pios_hott_dev *PIOS_HOTT_Alloc(void)
{
struct pios_hott_dev *hott_dev;
hott_dev = (struct pios_hott_dev *)pios_malloc(sizeof(*hott_dev));
if (!hott_dev)
return NULL;
hott_dev->magic = PIOS_HOTT_DEV_MAGIC;
return hott_dev;
}
#else
static struct pios_hott_dev pios_hott_devs[PIOS_HOTT_MAX_DEVS];
static uint8_t pios_hott_num_devs;
static struct pios_hott_dev *PIOS_HOTT_Alloc(void)
{
struct pios_hott_dev *hott_dev;
if (pios_hott_num_devs >= PIOS_HOTT_MAX_DEVS)
return NULL;
hott_dev = &pios_hott_devs[pios_hott_num_devs++];
hott_dev->magic = PIOS_HOTT_DEV_MAGIC;
return hott_dev;
}
#endif
/* Validate HOTT device descriptor */
static bool PIOS_HOTT_Validate(struct pios_hott_dev *hott_dev)
{
return (hott_dev->magic == PIOS_HOTT_DEV_MAGIC);
}
/* Reset channels in case of lost signal or explicit failsafe receiver flag */
static void PIOS_HOTT_ResetChannels(struct pios_hott_state *state)
{
for (int i = 0; i < PIOS_HOTT_NUM_INPUTS; i++) {
state->channel_data[i] = PIOS_RCVR_TIMEOUT;
}
}
/* Reset HOTT receiver state */
static void PIOS_HOTT_ResetState(struct pios_hott_state *state)
{
state->receive_timer = 0;
state->failsafe_timer = 0;
state->frame_found = 0;
state->tx_connected = 0;
PIOS_HOTT_ResetChannels(state);
}
/**
* Check and unroll complete frame data.
* \output 0 frame data accepted
* \output -1 frame error found
*/
static int PIOS_HOTT_UnrollChannels(struct pios_hott_dev *hott_dev)
{
struct pios_hott_state *state = &(hott_dev->state);
/* check the header and crc for a valid HoTT SUM stream */
uint8_t vendor = state->received_data[0];
uint8_t status = state->received_data[1];
if (vendor != HOTT_GRAUPNER_ID)
/* Graupner ID was expected */
goto stream_error;
switch (status) {
case HOTT_STATUS_LIVING_SUMH:
case HOTT_STATUS_LIVING_SUMD:
case HOTT_STATUS_FAILSAFE:
/* check crc before processing */
if (hott_dev->proto == PIOS_HOTT_PROTO_SUMD) {
/* SUMD has 16 bit CCITT CRC */
uint16_t crc = 0;
uint8_t *s = &(state->received_data[0]);
int len = state->byte_count - 2;
for (int n = 0; n < len; n++) {
crc ^= (uint16_t)s[n] << 8;
for (int i = 0; i < 8; i++)
crc = (crc & 0x8000) ? (crc << 1) ^ 0x1021 : (crc << 1);
}
if (crc ^ (((uint16_t)s[len] << 8) | s[len + 1]))
/* wrong crc checksum found */
goto stream_error;
}
if (hott_dev->proto == PIOS_HOTT_PROTO_SUMH) {
/* SUMH has only 8 bit added CRC */
uint8_t crc = 0;
uint8_t *s = &(state->received_data[0]);
int len = state->byte_count - 1;
for (int n = 0; n < len; n++)
crc += s[n];
if (crc ^ s[len])
/* wrong crc checksum found */
goto stream_error;
}
/* check for a living connect */
state->tx_connected |= (status != HOTT_STATUS_FAILSAFE);
break;
default:
/* wrong header format */
goto stream_error;
}
/* check initial connection since reset or timeout */
if (!(state->tx_connected)) {
/* these are failsafe data without a first connect. ignore it */
PIOS_HOTT_ResetChannels(state);
return 0;
}
/* unroll channels */
uint8_t n_channels = state->received_data[2];
uint8_t *s = &(state->received_data[3]);
uint16_t word;
for (int i = 0; i < HOTT_MAX_CHANNELS_PER_FRAME; i++) {
if (i < n_channels) {
word = ((uint16_t)s[0] << 8) | s[1];
s += sizeof(uint16_t);
/* save the channel value */
if (i < PIOS_HOTT_NUM_INPUTS) {
/* floating version. channel limits from -100..+100% are mapped to 1000..2000 */
state->channel_data[i] = (uint16_t)(word / 6.4f - 375);
}
} else
/* this channel was not received */
state->channel_data[i] = PIOS_RCVR_INVALID;
}
/* all channels processed */
return 0;
stream_error:
/* either SUMD selected with SUMH stream found, or vice-versa */
return -1;
}
/* Update decoder state processing input byte from the HoTT stream */
static void PIOS_HOTT_UpdateState(struct pios_hott_dev *hott_dev, uint8_t byte)
{
struct pios_hott_state *state = &(hott_dev->state);
if (state->frame_found) {
/* receiving the data frame */
if (state->byte_count < HOTT_MAX_FRAME_LENGTH) {
/* store next byte */
state->received_data[state->byte_count++] = byte;
if (state->byte_count == HOTT_HEADER_LENGTH) {
/* 3rd byte contains the number of channels. calculate frame size */
state->frame_length = HOTT_OVERHEAD_LENGTH + 2 * byte;
}
if (state->byte_count == state->frame_length) {
/* full frame received - process and wait for new one */
if (!PIOS_HOTT_UnrollChannels(hott_dev))
/* data looking good */
state->failsafe_timer = 0;
/* prepare for the next frame */
state->frame_found = 0;
}
}
}
}
/* Initialise HoTT receiver interface */
int32_t PIOS_HOTT_Init(uint32_t *hott_id,
const struct pios_com_driver *driver,
uint32_t lower_id,
enum pios_hott_proto proto)
{
PIOS_DEBUG_Assert(hott_id);
PIOS_DEBUG_Assert(driver);
struct pios_hott_dev *hott_dev;
hott_dev = (struct pios_hott_dev *)PIOS_HOTT_Alloc();
if (!hott_dev)
return -1;
/* Bind the configuration to the device instance */
hott_dev->proto = proto;
PIOS_HOTT_ResetState(&(hott_dev->state));
*hott_id = (uint32_t)hott_dev;
/* Set comm driver callback */
(driver->bind_rx_cb)(lower_id, PIOS_HOTT_RxInCallback, *hott_id);
if (!PIOS_RTC_RegisterTickCallback(PIOS_HOTT_Supervisor, *hott_id)) {
PIOS_DEBUG_Assert(0);
}
return 0;
}
/* Comm byte received callback */
static uint16_t PIOS_HOTT_RxInCallback(uint32_t context,
uint8_t *buf,
uint16_t buf_len,
uint16_t *headroom,
bool *need_yield)
{
struct pios_hott_dev *hott_dev = (struct pios_hott_dev *)context;
bool valid = PIOS_HOTT_Validate(hott_dev);
PIOS_Assert(valid);
/* process byte(s) and clear receive timer */
for (uint8_t i = 0; i < buf_len; i++) {
PIOS_HOTT_UpdateState(hott_dev, buf[i]);
hott_dev->state.receive_timer = 0;
}
/* Always signal that we can accept more data */
if (headroom)
*headroom = HOTT_MAX_FRAME_LENGTH;
/* We never need a yield */
*need_yield = false;
/* Always indicate that all bytes were consumed */
return buf_len;
}
/**
* Get the value of an input channel
* \param[in] channel Number of the channel desired (zero based)
* \output PIOS_RCVR_INVALID channel not available
* \output PIOS_RCVR_TIMEOUT failsafe condition or missing receiver
* \output >=0 channel value
*/
static int32_t PIOS_HOTT_Get(uint32_t rcvr_id, uint8_t channel)
{
struct pios_hott_dev *hott_dev = (struct pios_hott_dev *)rcvr_id;
if (!PIOS_HOTT_Validate(hott_dev))
return PIOS_RCVR_INVALID;
/* return error if channel is not available */
if (channel >= PIOS_HOTT_NUM_INPUTS)
return PIOS_RCVR_INVALID;
/* may also be PIOS_RCVR_TIMEOUT set by other function */
return hott_dev->state.channel_data[channel];
}
/**
* Input data supervisor is called periodically and provides
* two functions: frame syncing and failsafe triggering.
*
* HOTT frames come at 11ms or 22ms rate at 115200bps.
* RTC timer is running at 625Hz (1.6ms). So with divider 5 it gives
* 8ms pause between frames which is good for both HOTT frame rates.
*
* Data receive function must clear the receive_timer to confirm new
* data reception. If no new data received in 100ms, we must call the
* failsafe function which clears all channels.
*/
static void PIOS_HOTT_Supervisor(uint32_t hott_id)
{
struct pios_hott_dev *hott_dev = (struct pios_hott_dev *)hott_id;
bool valid = PIOS_HOTT_Validate(hott_dev);
PIOS_Assert(valid);
struct pios_hott_state *state = &(hott_dev->state);
/* waiting for new frame if no bytes were received in 8ms */
if (++state->receive_timer > 4) {
state->frame_found = 1;
state->byte_count = 0;
state->receive_timer = 0;
state->frame_length = HOTT_MAX_FRAME_LENGTH;
}
/* activate failsafe if no frames have arrived in 102.4ms */
if (++state->failsafe_timer > 64) {
PIOS_HOTT_ResetChannels(state);
state->failsafe_timer = 0;
state->tx_connected = 0;
}
}
#endif /* PIOS_INCLUDE_HOTT */
/**
* @}
* @}
*/

View File

@ -0,0 +1,43 @@
/**
******************************************************************************
* @addtogroup PIOS PIOS Core hardware abstraction layer
* @{
* @addtogroup PIOS_SBus Futaba S.Bus receiver functions
* @{
*
* @file pios_sbus.h
* @author The LibrePilot Project, http://www.librepilot.org Copyright (C) 2015.
* Tau Labs, http://taulabs.org, Copyright (C) 2013
* @brief Futaba S.Bus 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_EXBUS_H
#define PIOS_EXBUS_H
/* Global Types */
/* Public Functions */
#endif /* PIOS_EXBUS_H */
/**
* @}
* @}
*/

View File

@ -0,0 +1,47 @@
/**
******************************************************************************
* @file pios_exbus_priv.h
* @author The LibrePilot Project, http://www.librepilot.org Copyright (C) 2015.
* Tau Labs, http://taulabs.org, Copyright (C) 2013
* @addtogroup PIOS PIOS Core hardware abstraction layer
* @{
* @addtogroup PIOS_EXBUS Jeti EX Bus receiver functions
* @{
* @brief Jeti EX Bus receiver functions
*****************************************************************************/
/*
* 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_EXBUS_PRIV_H
#define PIOS_EXBUS_PRIV_H
#include <pios.h>
#include <pios_usart_priv.h>
/* EXBUS receiver instance configuration */
extern const struct pios_rcvr_driver pios_exbus_rcvr_driver;
extern int32_t PIOS_EXBUS_Init(uint32_t *exbus_id,
const struct pios_com_driver *driver,
uint32_t lower_id);
#endif /* PIOS_EXBUS_PRIV_H */
/**
* @}
* @}
*/

View File

@ -0,0 +1,36 @@
/**
******************************************************************************
* @file pios_hott.h
* @author The LibrePilot Project, http://www.librepilot.org, Copyright (c) 2015
* @author Tau Labs, http://taulabs.org, Copyright (C) 2013
* @addtogroup PIOS PIOS Core hardware abstraction layer
* @{
* @addtogroup PIOS_HOTT Graupner HoTT receiver functions
* @{
* @brief Graupner HoTT receiver functions for SUMD/H
*****************************************************************************/
/*
* 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_HOTT_H
#define PIOS_HOTT_H
#endif /* PIOS_HOTT_H */
/**
* @}
* @}
*/

View File

@ -0,0 +1,53 @@
/**
******************************************************************************
* @file pios_hott_private.h
* @author The LibrePilot Project, http://www.librepilot.org, Copyright (c) 2015
* @author Tau Labs, http://taulabs.org, Copyright (C) 2013
* @addtogroup PIOS PIOS Core hardware abstraction layer
* @{
* @addtogroup PIOS_HOTT Graupner HoTT receiver functions
* @{
* @brief Graupner HoTT receiver functions for SUMD/H
*****************************************************************************/
/*
* 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_HOTT_PRIV_H
#define PIOS_HOTT_PRIV_H
#include <pios.h>
#include <pios_usart_priv.h>
/* HOTT protocol variations */
enum pios_hott_proto {
PIOS_HOTT_PROTO_SUMD,
PIOS_HOTT_PROTO_SUMH,
};
/* HOTT receiver instance configuration */
extern const struct pios_rcvr_driver pios_hott_rcvr_driver;
extern int32_t PIOS_HOTT_Init(uint32_t *hott_id,
const struct pios_com_driver *driver,
uint32_t lower_id,
enum pios_hott_proto proto);
#endif /* PIOS_HOTT_PRIV_H */
/**
* @}
* @}
*/

View File

@ -1,6 +1,7 @@
/**
******************************************************************************
* @file pios.h
* @author The LibrePilot Project, http://www.librepilot.org, Copyright (c) 2015
* @author The OpenPilot Team, http://www.openpilot.org Copyright (C) 2010-2013
* @author PhoenixPilot, http://github.com/PhoenixPilot, Copyright (C) 2012
* @brief Main PiOS header.
@ -228,6 +229,10 @@ extern "C" {
#include <pios_sbus.h>
#endif
#ifdef PIOS_INCLUDE_HOTT
#include <pios_hott.h>
#endif
#ifdef PIOS_INCLUDE_SRXL
#include <pios_srxl.h>
#endif

View File

@ -1021,6 +1021,92 @@ static const struct pios_dsm_cfg pios_dsm_flexi_cfg = {
#endif /* PIOS_INCLUDE_DSM */
#if defined(PIOS_INCLUDE_HOTT)
/*
* HOTT USART
*/
#include <pios_hott_priv.h>
static const struct pios_usart_cfg pios_usart_hott_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_HOTT */
#if defined(PIOS_INCLUDE_EXBUS)
/*
* EXBUS USART
*/
#include <pios_exbus_priv.h>
static const struct pios_usart_cfg pios_usart_exbus_flexi_cfg = {
.regs = USART3,
.init = {
.USART_BaudRate = 125000,
.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_EXBUS */
#if defined(PIOS_INCLUDE_SRXL)
/*
* SRXL USART

View File

@ -101,7 +101,9 @@
#define PIOS_INCLUDE_PPM_FLEXI
#define PIOS_INCLUDE_DSM
#define PIOS_INCLUDE_SBUS
#define PIOS_INCLUDE_EXBUS
#define PIOS_INCLUDE_SRXL
#define PIOS_INCLUDE_HOTT
/* #define PIOS_INCLUDE_GCSRCVR */
/* #define PIOS_INCLUDE_OPLINKRCVR */

View File

@ -674,6 +674,53 @@ void PIOS_Board_Init(void)
}
#endif /* PIOS_INCLUDE_DSM */
break;
case HWSETTINGS_CC_FLEXIPORT_HOTTSUMD:
case HWSETTINGS_CC_FLEXIPORT_HOTTSUMH:
#if defined(PIOS_INCLUDE_HOTT)
{
uint32_t pios_usart_hott_id;
if (PIOS_USART_Init(&pios_usart_hott_id, &pios_usart_hott_flexi_cfg)) {
PIOS_Assert(0);
}
uint32_t pios_hott_id;
if (PIOS_HOTT_Init(&pios_hott_id, &pios_usart_com_driver, pios_usart_hott_id,
hwsettings_cc_flexiport == HWSETTINGS_CC_FLEXIPORT_HOTTSUMD ? PIOS_HOTT_PROTO_SUMD : PIOS_HOTT_PROTO_SUMH)) {
PIOS_Assert(0);
}
uint32_t pios_hott_rcvr_id;
if (PIOS_RCVR_Init(&pios_hott_rcvr_id, &pios_hott_rcvr_driver, pios_hott_id)) {
PIOS_Assert(0);
}
pios_rcvr_group_map[MANUALCONTROLSETTINGS_CHANNELGROUPS_HOTT] = pios_hott_rcvr_id;
}
#endif /* PIOS_INCLUDE_HOTT */
break;
case HWSETTINGS_CC_FLEXIPORT_EXBUS:
#if defined(PIOS_INCLUDE_EXBUS)
{
uint32_t pios_usart_exbus_id;
if (PIOS_USART_Init(&pios_usart_exbus_id, &pios_usart_exbus_flexi_cfg)) {
PIOS_Assert(0);
}
uint32_t pios_exbus_id;
if (PIOS_EXBUS_Init(&pios_exbus_id, &pios_usart_com_driver, pios_usart_exbus_id)) {
PIOS_Assert(0);
}
uint32_t pios_exbus_rcvr_id;
if (PIOS_RCVR_Init(&pios_exbus_rcvr_id, &pios_exbus_rcvr_driver, pios_exbus_id)) {
PIOS_Assert(0);
}
pios_rcvr_group_map[MANUALCONTROLSETTINGS_CHANNELGROUPS_EXBUS] = pios_exbus_rcvr_id;
}
#endif /* PIOS_INCLUDE_EXBUS */
break;
case HWSETTINGS_CC_FLEXIPORT_SRXL:
#if defined(PIOS_INCLUDE_SRXL)
{

View File

@ -248,6 +248,18 @@ extern uint32_t pios_com_hkosd_id;
#define PIOS_SBUS_MAX_DEVS 1
#define PIOS_SBUS_NUM_INPUTS (16 + 2)
//-------------------------
// Receiver HSUM input
//-------------------------
#define PIOS_HOTT_MAX_DEVS 1
#define PIOS_HOTT_NUM_INPUTS 32
// -------------------------
// Receiver EX.Bus input
// -------------------------
#define PIOS_EXBUS_MAX_DEVS 1
#define PIOS_EXBUS_NUM_INPUTS 16
// -------------------------
// Receiver Multiplex SRXL input
// -------------------------

View File

@ -1,8 +1,9 @@
/**
******************************************************************************
* @file board_hw_defs.c
* @author The OpenPilot Team, http://www.openpilot.org Copyright (C) 2012.
* @author PhoenixPilot, http://github.com/PhoenixPilot, Copyright (C) 2012
* @author The LibrePilot Project, http://www.librepilot.org Copyright (C) 2015.
* The OpenPilot Team, http://www.openpilot.org Copyright (C) 2012.
* PhoenixPilot, http://github.com/PhoenixPilot, Copyright (C) 2012
* @addtogroup OpenPilotSystem OpenPilot System
* @{
* @addtogroup OpenPilotCore OpenPilot Core
@ -1054,6 +1055,105 @@ static const struct pios_usart_cfg pios_usart_srxl_flexi_cfg = {
};
#endif /* PIOS_INCLUDE_SRXL */
#if defined(PIOS_INCLUDE_HOTT)
/*
* HOTT USART
*/
#include <pios_hott_priv.h>
static const struct pios_usart_cfg pios_usart_hott_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_HOTT */
#if defined(PIOS_INCLUDE_EXBUS)
/*
* EXBUS USART
*/
#include <pios_exbus_priv.h>
static const struct pios_usart_cfg pios_usart_exbus_flexi_cfg = {
.regs = USART3,
.remap = GPIO_AF_USART3,
.init = {
.USART_BaudRate = 125000,
.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_EXBUS */
/*
* HK OSD
*/

View File

@ -5,7 +5,8 @@
* @addtogroup OpenPilotCore OpenPilot Core
* @{
* @file pios_config.h
* @author The OpenPilot Team, http://www.openpilot.org Copyright (C) 2010-2013.
* @author The LibrePilot Project, http://www.librepilot.org Copyright (C) 2015.
* The OpenPilot Team, http://www.openpilot.org Copyright (C) 2010-2013.
* @brief PiOS configuration header, the compile time config file for the PIOS.
* Defines which PiOS libraries and features are included in the firmware.
* @see The GNU Public License (GPL) Version 3
@ -104,6 +105,8 @@
#define PIOS_INCLUDE_DSM
#define PIOS_INCLUDE_SBUS
#define PIOS_INCLUDE_SRXL
#define PIOS_INCLUDE_HOTT
#define PIOS_INCLUDE_EXBUS
#define PIOS_INCLUDE_GCSRCVR
#define PIOS_INCLUDE_OPLINKRCVR

View File

@ -1,8 +1,9 @@
/**
******************************************************************************
* @file pios_board.c
* @author The OpenPilot Team, http://www.openpilot.org Copyright (C) 2011.
* @author PhoenixPilot, http://github.com/PhoenixPilot, Copyright (C) 2012
* @author The LibrePilot Project, http://www.librepilot.org Copyright (C) 2015.
* The OpenPilot Team, http://www.openpilot.org Copyright (C) 2011.
* PhoenixPilot, http://github.com/PhoenixPilot, Copyright (C) 2012
* @addtogroup OpenPilotSystem OpenPilot System
* @{
* @addtogroup OpenPilotCore OpenPilot Core
@ -547,6 +548,7 @@ void PIOS_Board_Init(void)
case HWSETTINGS_RM_FLEXIPORT_OSDHK:
PIOS_Board_configure_com(&pios_usart_hkosd_flexi_cfg, PIOS_COM_HKOSD_RX_BUF_LEN, PIOS_COM_HKOSD_TX_BUF_LEN, &pios_usart_com_driver, &pios_com_hkosd_id);
break;
case HWSETTINGS_RM_FLEXIPORT_SRXL:
#if defined(PIOS_INCLUDE_SRXL)
{
@ -566,8 +568,55 @@ 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_HOTTSUMD:
case HWSETTINGS_RM_FLEXIPORT_HOTTSUMH:
#if defined(PIOS_INCLUDE_HOTT)
{
uint32_t pios_usart_hott_id;
if (PIOS_USART_Init(&pios_usart_hott_id, &pios_usart_hott_flexi_cfg)) {
PIOS_Assert(0);
}
uint32_t pios_hott_id;
if (PIOS_HOTT_Init(&pios_hott_id, &pios_usart_com_driver, pios_usart_hott_id,
hwsettings_flexiport == HWSETTINGS_RM_FLEXIPORT_HOTTSUMD ? PIOS_HOTT_PROTO_SUMD : PIOS_HOTT_PROTO_SUMH)) {
PIOS_Assert(0);
}
uint32_t pios_hott_rcvr_id;
if (PIOS_RCVR_Init(&pios_hott_rcvr_id, &pios_hott_rcvr_driver, pios_hott_id)) {
PIOS_Assert(0);
}
pios_rcvr_group_map[MANUALCONTROLSETTINGS_CHANNELGROUPS_HOTT] = pios_hott_rcvr_id;
}
#endif /* PIOS_INCLUDE_HOTT */
break;
case HWSETTINGS_RM_FLEXIPORT_EXBUS:
#if defined(PIOS_INCLUDE_EXBUS)
{
uint32_t pios_usart_exbus_id;
if (PIOS_USART_Init(&pios_usart_exbus_id, &pios_usart_exbus_flexi_cfg)) {
PIOS_Assert(0);
}
uint32_t pios_exbus_id;
if (PIOS_EXBUS_Init(&pios_exbus_id, &pios_usart_com_driver, pios_usart_exbus_id)) {
PIOS_Assert(0);
}
uint32_t pios_exbus_rcvr_id;
if (PIOS_RCVR_Init(&pios_exbus_rcvr_id, &pios_exbus_rcvr_driver, pios_exbus_id)) {
PIOS_Assert(0);
}
pios_rcvr_group_map[MANUALCONTROLSETTINGS_CHANNELGROUPS_EXBUS] = pios_exbus_rcvr_id;
}
#endif /* PIOS_INCLUDE_EXBUS */
break;
} /* hwsettings_rm_flexiport */
/* Moved this here to allow binding on flexiport */

View File

@ -5,7 +5,8 @@
* @addtogroup OpenPilotCore OpenPilot Core
* @{
* @file pios_board.h
* @author The OpenPilot Team, http://www.openpilot.org Copyright (C) 2012.
* @author The LibrePilot Project, http://www.librepilot.org Copyright (C) 2015.
* The OpenPilot Team, http://www.openpilot.org Copyright (C) 2012.
* @brief Defines board hardware for the OpenPilot Version 1.1 hardware.
* @see The GNU Public License (GPL) Version 3
*
@ -257,6 +258,18 @@ extern uint32_t pios_packet_handler;
#define PIOS_SBUS_MAX_DEVS 1
#define PIOS_SBUS_NUM_INPUTS (16 + 2)
//-------------------------
// Receiver HSUM input
//-------------------------
#define PIOS_HOTT_MAX_DEVS 1
#define PIOS_HOTT_NUM_INPUTS 32
// -------------------------
// Receiver EX.Bus input
// -------------------------
#define PIOS_EXBUS_MAX_DEVS 1
#define PIOS_EXBUS_NUM_INPUTS 16
// -------------------------
// Receiver Multiplex SRXL input
// -------------------------

View File

@ -1,7 +1,8 @@
/**
******************************************************************************
* @file board_hw_defs.c
* @author The OpenPilot Team, http://www.openpilot.org Copyright (C) 2014.
* @author The LibrePilot Project, http://www.librepilot.org Copyright (C) 2015.
* The OpenPilot Team, http://www.openpilot.org Copyright (C) 2014.
* @addtogroup OpenPilotSystem OpenPilot System
* @{
* @addtogroup OpenPilotCore OpenPilot Core
@ -535,6 +536,55 @@ static const struct pios_dsm_cfg pios_dsm_flexi_cfg = {
#endif /* PIOS_INCLUDE_DSM */
#if defined(PIOS_INCLUDE_HOTT)
/*
* HOTT USART
*/
#include <pios_hott_priv.h>
static const struct pios_usart_cfg pios_usart_hott_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_HOTT */
#if defined(PIOS_INCLUDE_SRXL)
/*
* SRXL USART
@ -583,6 +633,56 @@ static const struct pios_usart_cfg pios_usart_srxl_flexi_cfg = {
};
#endif /* PIOS_INCLUDE_SRXL */
#if defined(PIOS_INCLUDE_EXBUS)
/*
* EXBUS USART
*/
#include <pios_exbus_priv.h>
static const struct pios_usart_cfg pios_usart_exbus_flexi_cfg = {
.regs = FLEXI_USART_REGS,
.remap = FLEXI_USART_REMAP,
.init = {
.USART_BaudRate = 125000,
.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_EXBUS */
/*
* HK OSD
*/

View File

@ -5,7 +5,8 @@
* @addtogroup OpenPilotCore OpenPilot Core
* @{
* @file pios_config.h
* @author The OpenPilot Team, http://www.openpilot.org Copyright (C) 2010-2013.
* @author The LibrePilot Project, http://www.librepilot.org Copyright (C) 2015.
* The OpenPilot Team, http://www.openpilot.org Copyright (C) 2010-2013.
* @brief PiOS configuration header, the compile time config file for the PIOS.
* Defines which PiOS libraries and features are included in the firmware.
* @see The GNU Public License (GPL) Version 3
@ -108,6 +109,8 @@
#define PIOS_INCLUDE_DSM
#define PIOS_INCLUDE_SBUS
#define PIOS_INCLUDE_SRXL
#define PIOS_INCLUDE_HOTT
#define PIOS_INCLUDE_EXBUS
#define PIOS_INCLUDE_GCSRCVR
// #define PIOS_INCLUDE_OPLINKRCVR

View File

@ -1,8 +1,9 @@
/**
******************************************************************************
* @file pios_board.c
* @author The OpenPilot Team, http://www.openpilot.org Copyright (C) 2011.
* @author PhoenixPilot, http://github.com/PhoenixPilot, Copyright (C) 2012
* @author The LibrePilot Project, http://www.librepilot.org Copyright (C) 2015.
* The OpenPilot Team, http://www.openpilot.org Copyright (C) 2011.
* PhoenixPilot, http://github.com/PhoenixPilot, Copyright (C) 2012
* @addtogroup OpenPilotSystem OpenPilot System
* @{
* @addtogroup OpenPilotCore OpenPilot Core
@ -714,6 +715,53 @@ void PIOS_Board_Init(void)
}
#endif
break;
case HWSETTINGS_RM_FLEXIPORT_HOTTSUMD:
case HWSETTINGS_RM_FLEXIPORT_HOTTSUMH:
#if defined(PIOS_INCLUDE_HOTT)
{
uint32_t pios_usart_hott_id;
if (PIOS_USART_Init(&pios_usart_hott_id, &pios_usart_hott_flexi_cfg)) {
PIOS_Assert(0);
}
uint32_t pios_hott_id;
if (PIOS_HOTT_Init(&pios_hott_id, &pios_usart_com_driver, pios_usart_hott_id,
hwsettings_flexiport == HWSETTINGS_RM_FLEXIPORT_HOTTSUMD ? PIOS_HOTT_PROTO_SUMD : PIOS_HOTT_PROTO_SUMH)) {
PIOS_Assert(0);
}
uint32_t pios_hott_rcvr_id;
if (PIOS_RCVR_Init(&pios_hott_rcvr_id, &pios_hott_rcvr_driver, pios_hott_id)) {
PIOS_Assert(0);
}
pios_rcvr_group_map[MANUALCONTROLSETTINGS_CHANNELGROUPS_HOTT] = pios_hott_rcvr_id;
}
#endif /* PIOS_INCLUDE_HOTT */
break;
case HWSETTINGS_RM_FLEXIPORT_EXBUS:
#if defined(PIOS_INCLUDE_EXBUS)
{
uint32_t pios_usart_exbus_id;
if (PIOS_USART_Init(&pios_usart_exbus_id, &pios_usart_exbus_flexi_cfg)) {
PIOS_Assert(0);
}
uint32_t pios_exbus_id;
if (PIOS_EXBUS_Init(&pios_exbus_id, &pios_usart_com_driver, pios_usart_exbus_id)) {
PIOS_Assert(0);
}
uint32_t pios_exbus_rcvr_id;
if (PIOS_RCVR_Init(&pios_exbus_rcvr_id, &pios_exbus_rcvr_driver, pios_exbus_id)) {
PIOS_Assert(0);
}
pios_rcvr_group_map[MANUALCONTROLSETTINGS_CHANNELGROUPS_EXBUS] = pios_exbus_rcvr_id;
}
#endif /* PIOS_INCLUDE_EXBUS */
break;
} /* hwsettings_rm_flexiport */

View File

@ -5,7 +5,8 @@
* @addtogroup OpenPilotCore OpenPilot Core
* @{
* @file pios_board.h
* @author The OpenPilot Team, http://www.openpilot.org Copyright (C) 2012.
* @author The LibrePilot Project, http://www.librepilot.org Copyright (C) 2015.
* The OpenPilot Team, http://www.openpilot.org Copyright (C) 2012.
* @brief Defines board hardware for the OpenPilot Version 1.1 hardware.
* @see The GNU Public License (GPL) Version 3
*
@ -257,6 +258,18 @@ extern uint32_t pios_packet_handler;
#define PIOS_SBUS_MAX_DEVS 1
#define PIOS_SBUS_NUM_INPUTS (16 + 2)
//-------------------------
// Receiver HSUM input
//-------------------------
#define PIOS_HOTT_MAX_DEVS 1
#define PIOS_HOTT_NUM_INPUTS 32
// -------------------------
// Receiver EX.Bus input
// -------------------------
#define PIOS_EXBUS_MAX_DEVS 1
#define PIOS_EXBUS_NUM_INPUTS 16
// -------------------------
// Receiver Multiplex SRXL input
// -------------------------

View File

@ -151,11 +151,15 @@ void InputChannelForm::groupUpdated()
case ManualControlSettings::CHANNELGROUPS_DSMFLEXIPORT:
count = 12;
break;
case ManualControlSettings::CHANNELGROUPS_SRXL:
case ManualControlSettings::CHANNELGROUPS_EXBUS:
count = 16;
break;
case ManualControlSettings::CHANNELGROUPS_SBUS:
count = 18;
break;
case ManualControlSettings::CHANNELGROUPS_SRXL:
count = 16;
case ManualControlSettings::CHANNELGROUPS_HOTT:
count = 32;
break;
case ManualControlSettings::CHANNELGROUPS_GCS:
count = GCSReceiver::CHANNEL_NUMELEM;

View File

@ -3,8 +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" defaultvalue="Telemetry"/>
<field name="CC_FlexiPort" units="function" type="enum" elements="1" options="Disabled,Telemetry,GPS,I2C,PPM,DSM,SRXL,DebugConsole,ComBridge,OsdHk" 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,DebugConsole,ComBridge,OsdHk" 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" defaultvalue="Disabled"/>
<field name="RV_AuxSBusPort" units="function" type="enum" elements="1" options="Disabled,S.Bus,DSM,ComAux,ComBridge,OsdHk" defaultvalue="Disabled"/>
@ -15,9 +14,8 @@
<field name="RM_RcvrPort" units="function" type="enum" elements="1" options="Disabled,PWM,PPM,PPM+PWM,PPM+Telemetry,PPM+Outputs,Outputs,Telemetry,ComBridge"
defaultvalue="PWM"
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" defaultvalue="Disabled"/>
<field name="RM_FlexiPort" units="function" type="enum" elements="1" options="Disabled,Telemetry,GPS,I2C,DSM,SRXL,DebugConsole,ComBridge,OsdHk" defaultvalue="Disabled"/>
<field name="RM_MainPort" units="function" type="enum" elements="1" options="Disabled,Telemetry,GPS,S.Bus,DSM,DebugConsole,ComBridge,OsdHk" 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" defaultvalue="Disabled"/>
<field name="TelemetrySpeed" units="bps" type="enum" elements="1" options="2400,4800,9600,19200,38400,57600,115200" defaultvalue="57600"/>
<field name="GPSSpeed" units="bps" type="enum" elements="1" options="2400,4800,9600,19200,38400,57600,115200,230400" defaultvalue="57600"/>
<field name="ComUsbBridgeSpeed" units="bps" type="enum" elements="1" options="2400,4800,9600,19200,38400,57600,115200" defaultvalue="57600"/>

View File

@ -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),S.Bus,SRXL,GCS,OPLink,None" defaultvalue="None"/>
options="PWM,PPM,DSM (MainPort),DSM (FlexiPort),S.Bus,EX.Bus,HoTT,SRXL,GCS,OPLink,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"

View File

@ -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),S.Bus,SRXL,GCS,OPLink,None"
options="PWM,PPM,DSM (MainPort),DSM (FlexiPort),S.Bus,EX.Bus,HoTT,SRXL,GCS,OPLink,None"
defaultvalue="None"/>
<field name="ActiveChannel" units="channel" type="uint8" elements="1"
defaultvalue="255"/>