2018-01-17 15:31:11 -04:00
|
|
|
/*
|
|
|
|
SBUS decoder, based on src/modules/px4iofirmware/sbus.c from PX4Firmware
|
|
|
|
modified for use in AP_HAL_* by Andrew Tridgell
|
|
|
|
*/
|
|
|
|
/****************************************************************************
|
|
|
|
*
|
|
|
|
* Copyright (c) 2012-2014 PX4 Development Team. All rights reserved.
|
|
|
|
*
|
|
|
|
* Redistribution and use in source and binary forms, with or without
|
|
|
|
* modification, are permitted provided that the following conditions
|
|
|
|
* are met:
|
|
|
|
*
|
|
|
|
* 1. Redistributions of source code must retain the above copyright
|
|
|
|
* notice, this list of conditions and the following disclaimer.
|
|
|
|
* 2. Redistributions in binary form must reproduce the above copyright
|
|
|
|
* notice, this list of conditions and the following disclaimer in
|
|
|
|
* the documentation and/or other materials provided with the
|
|
|
|
* distribution.
|
|
|
|
* 3. Neither the name PX4 nor the names of its contributors may be
|
|
|
|
* used to endorse or promote products derived from this software
|
|
|
|
* without specific prior written permission.
|
|
|
|
*
|
|
|
|
* THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
|
|
|
|
* "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
|
|
|
|
* LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
|
|
|
|
* FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
|
|
|
|
* COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
|
|
|
|
* INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
|
|
|
|
* BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS
|
|
|
|
* OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED
|
|
|
|
* AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
|
|
|
|
* LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
|
|
|
|
* ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
|
|
|
|
* POSSIBILITY OF SUCH DAMAGE.
|
|
|
|
*
|
|
|
|
****************************************************************************/
|
|
|
|
/*
|
|
|
|
* This file 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 file 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, see <http://www.gnu.org/licenses/>.
|
2018-07-20 01:25:40 -03:00
|
|
|
*
|
2018-01-17 15:31:11 -04:00
|
|
|
* Code by Andrew Tridgell and Siddharth Bharat Purohit
|
|
|
|
*/
|
|
|
|
|
|
|
|
#include "AP_RCProtocol_SBUS.h"
|
|
|
|
|
2023-04-27 21:38:54 -03:00
|
|
|
#include "AP_RCProtocol_config.h"
|
|
|
|
|
|
|
|
#if AP_RCPROTOCOL_SBUS_ENABLED
|
|
|
|
|
2018-01-17 15:31:11 -04:00
|
|
|
#define SBUS_FRAME_SIZE 25
|
|
|
|
#define SBUS_INPUT_CHANNELS 16
|
|
|
|
#define SBUS_FLAGS_BYTE 23
|
|
|
|
#define SBUS_FAILSAFE_BIT 3
|
|
|
|
#define SBUS_FRAMELOST_BIT 2
|
|
|
|
|
|
|
|
/* define range mapping here, -+100% -> 1000..2000 */
|
2020-04-30 16:34:51 -03:00
|
|
|
#define SBUS_RANGE_MIN 200
|
|
|
|
#define SBUS_RANGE_MAX 1800
|
|
|
|
#define SBUS_RANGE_RANGE (SBUS_RANGE_MAX - SBUS_RANGE_MIN)
|
2018-01-17 15:31:11 -04:00
|
|
|
|
2020-04-30 16:34:51 -03:00
|
|
|
#define SBUS_TARGET_MIN 1000
|
|
|
|
#define SBUS_TARGET_MAX 2000
|
|
|
|
#define SBUS_TARGET_RANGE (SBUS_TARGET_MAX - SBUS_TARGET_MIN)
|
2018-01-17 15:31:11 -04:00
|
|
|
|
2020-04-30 16:34:51 -03:00
|
|
|
// this is 875
|
|
|
|
#define SBUS_SCALE_OFFSET (SBUS_TARGET_MIN - ((SBUS_TARGET_RANGE * SBUS_RANGE_MIN / SBUS_RANGE_RANGE)))
|
2018-01-17 15:31:11 -04:00
|
|
|
|
2021-08-07 04:33:00 -03:00
|
|
|
#ifndef HAL_SBUS_FRAME_GAP
|
2022-02-10 01:47:02 -04:00
|
|
|
#define HAL_SBUS_FRAME_GAP 2000U
|
2021-08-07 04:33:00 -03:00
|
|
|
#endif
|
|
|
|
|
2018-11-04 22:01:17 -04:00
|
|
|
// constructor
|
2021-11-05 02:39:56 -03:00
|
|
|
AP_RCProtocol_SBUS::AP_RCProtocol_SBUS(AP_RCProtocol &_frontend, bool _inverted, uint32_t configured_baud) :
|
2018-11-04 22:01:17 -04:00
|
|
|
AP_RCProtocol_Backend(_frontend),
|
2021-11-05 02:39:56 -03:00
|
|
|
inverted(_inverted),
|
|
|
|
ss{configured_baud, SoftSerial::SERIAL_CONFIG_8E2I}
|
2018-11-04 22:01:17 -04:00
|
|
|
{}
|
|
|
|
|
|
|
|
// decode a full SBUS frame
|
2018-01-17 15:31:11 -04:00
|
|
|
bool AP_RCProtocol_SBUS::sbus_decode(const uint8_t frame[25], uint16_t *values, uint16_t *num_values,
|
2018-07-20 01:25:40 -03:00
|
|
|
bool *sbus_failsafe, bool *sbus_frame_drop, uint16_t max_values)
|
2018-01-17 15:31:11 -04:00
|
|
|
{
|
2018-07-20 01:25:40 -03:00
|
|
|
/* check frame boundary markers to avoid out-of-sync cases */
|
|
|
|
if ((frame[0] != 0x0f)) {
|
|
|
|
return false;
|
|
|
|
}
|
|
|
|
|
2020-04-30 16:34:51 -03:00
|
|
|
uint16_t chancount = SBUS_INPUT_CHANNELS;
|
2018-07-20 01:25:40 -03:00
|
|
|
|
2020-04-30 16:34:51 -03:00
|
|
|
decode_11bit_channels((const uint8_t*)(&frame[1]), SBUS_INPUT_CHANNELS, values,
|
|
|
|
SBUS_TARGET_RANGE, SBUS_RANGE_RANGE, SBUS_SCALE_OFFSET);
|
2018-07-20 01:25:40 -03:00
|
|
|
|
|
|
|
/* decode switch channels if data fields are wide enough */
|
2020-04-30 16:34:51 -03:00
|
|
|
if (max_values > 17 && SBUS_INPUT_CHANNELS > 15) {
|
2018-07-20 01:25:40 -03:00
|
|
|
chancount = 18;
|
|
|
|
|
|
|
|
/* channel 17 (index 16) */
|
2018-11-27 17:11:21 -04:00
|
|
|
values[16] = (frame[SBUS_FLAGS_BYTE] & (1 << 0))?1998:998;
|
2018-07-20 01:25:40 -03:00
|
|
|
/* channel 18 (index 17) */
|
2018-11-27 17:11:21 -04:00
|
|
|
values[17] = (frame[SBUS_FLAGS_BYTE] & (1 << 1))?1998:998;
|
2018-07-20 01:25:40 -03:00
|
|
|
}
|
|
|
|
|
|
|
|
/* note the number of channels decoded */
|
|
|
|
*num_values = chancount;
|
|
|
|
|
|
|
|
/* decode and handle failsafe and frame-lost flags */
|
|
|
|
if (frame[SBUS_FLAGS_BYTE] & (1 << SBUS_FAILSAFE_BIT)) { /* failsafe */
|
|
|
|
/* report that we failed to read anything valid off the receiver */
|
|
|
|
*sbus_failsafe = true;
|
|
|
|
*sbus_frame_drop = true;
|
|
|
|
} else if (frame[SBUS_FLAGS_BYTE] & (1 << SBUS_FRAMELOST_BIT)) { /* a frame was lost */
|
|
|
|
/* set a special warning flag
|
|
|
|
*
|
|
|
|
* Attention! This flag indicates a skipped frame only, not a total link loss! Handling this
|
|
|
|
* condition as fail-safe greatly reduces the reliability and range of the radio link,
|
|
|
|
* e.g. by prematurely issuing return-to-launch!!! */
|
|
|
|
|
|
|
|
*sbus_failsafe = false;
|
|
|
|
*sbus_frame_drop = true;
|
|
|
|
} else {
|
|
|
|
*sbus_failsafe = false;
|
|
|
|
*sbus_frame_drop = false;
|
|
|
|
}
|
|
|
|
|
|
|
|
return true;
|
2018-01-17 15:31:11 -04:00
|
|
|
}
|
|
|
|
|
|
|
|
|
|
|
|
/*
|
|
|
|
process a SBUS input pulse of the given width
|
|
|
|
*/
|
|
|
|
void AP_RCProtocol_SBUS::process_pulse(uint32_t width_s0, uint32_t width_s1)
|
|
|
|
{
|
2018-11-04 22:01:17 -04:00
|
|
|
uint32_t w0 = width_s0;
|
|
|
|
uint32_t w1 = width_s1;
|
|
|
|
if (inverted) {
|
|
|
|
w0 = saved_width;
|
|
|
|
w1 = width_s0;
|
|
|
|
saved_width = width_s1;
|
2018-07-20 01:25:40 -03:00
|
|
|
}
|
2018-11-04 22:01:17 -04:00
|
|
|
uint8_t b;
|
|
|
|
if (ss.process_pulse(w0, w1, b)) {
|
|
|
|
_process_byte(ss.get_byte_timestamp_us(), b);
|
2018-01-17 15:31:11 -04:00
|
|
|
}
|
|
|
|
}
|
2018-11-02 06:42:29 -03:00
|
|
|
|
|
|
|
// support byte input
|
2018-11-04 22:01:17 -04:00
|
|
|
void AP_RCProtocol_SBUS::_process_byte(uint32_t timestamp_us, uint8_t b)
|
2018-11-02 06:42:29 -03:00
|
|
|
{
|
2021-08-07 04:33:00 -03:00
|
|
|
const bool have_frame_gap = (timestamp_us - byte_input.last_byte_us >= HAL_SBUS_FRAME_GAP);
|
2018-11-04 22:01:17 -04:00
|
|
|
byte_input.last_byte_us = timestamp_us;
|
2018-11-26 07:18:46 -04:00
|
|
|
|
2018-11-27 17:55:27 -04:00
|
|
|
if (have_frame_gap) {
|
|
|
|
// if we have a frame gap then this must be the start of a new
|
|
|
|
// frame
|
|
|
|
byte_input.ofs = 0;
|
|
|
|
}
|
2018-11-26 07:18:46 -04:00
|
|
|
if (b != 0x0F && byte_input.ofs == 0) {
|
|
|
|
// definately not SBUS, missing header byte
|
|
|
|
return;
|
|
|
|
}
|
|
|
|
if (byte_input.ofs == 0 && !have_frame_gap) {
|
|
|
|
// must have a frame gap before the start of a new SBUS frame
|
|
|
|
return;
|
|
|
|
}
|
|
|
|
|
2018-11-02 06:42:29 -03:00
|
|
|
byte_input.buf[byte_input.ofs++] = b;
|
2018-11-04 22:01:17 -04:00
|
|
|
|
2018-11-02 06:42:29 -03:00
|
|
|
if (byte_input.ofs == sizeof(byte_input.buf)) {
|
2020-03-18 21:08:17 -03:00
|
|
|
log_data(AP_RCProtocol::SBUS, timestamp_us, byte_input.buf, byte_input.ofs);
|
2018-11-02 06:42:29 -03:00
|
|
|
uint16_t values[SBUS_INPUT_CHANNELS];
|
|
|
|
uint16_t num_values=0;
|
|
|
|
bool sbus_failsafe = false;
|
|
|
|
bool sbus_frame_drop = false;
|
|
|
|
if (sbus_decode(byte_input.buf, values, &num_values,
|
|
|
|
&sbus_failsafe, &sbus_frame_drop, SBUS_INPUT_CHANNELS) &&
|
|
|
|
num_values >= MIN_RCIN_CHANNELS) {
|
2018-11-08 04:07:42 -04:00
|
|
|
add_input(num_values, values, sbus_failsafe);
|
2018-11-02 06:42:29 -03:00
|
|
|
}
|
|
|
|
byte_input.ofs = 0;
|
|
|
|
}
|
|
|
|
}
|
2018-11-04 22:01:17 -04:00
|
|
|
|
|
|
|
// support byte input
|
|
|
|
void AP_RCProtocol_SBUS::process_byte(uint8_t b, uint32_t baudrate)
|
|
|
|
{
|
2021-11-05 02:39:56 -03:00
|
|
|
// note that if we're here we're not actually using SoftSerial,
|
|
|
|
// but it does record our configured baud rate:
|
|
|
|
if (baudrate != ss.baud()) {
|
2018-11-04 22:01:17 -04:00
|
|
|
return;
|
|
|
|
}
|
|
|
|
_process_byte(AP_HAL::micros(), b);
|
|
|
|
}
|
2023-04-27 21:38:54 -03:00
|
|
|
|
|
|
|
#endif // AP_RCPROTOCOL_SBUS_ENABLED
|