2018-01-17 15:31:11 -04:00
|
|
|
/*
|
|
|
|
* 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
|
|
|
|
*/
|
|
|
|
#pragma once
|
2022-04-16 23:54:08 -03:00
|
|
|
|
|
|
|
#include "AP_RCProtocol_config.h"
|
|
|
|
|
2018-01-17 15:31:11 -04:00
|
|
|
#include <AP_HAL/AP_HAL.h>
|
|
|
|
#include <AP_Common/AP_Common.h>
|
2024-03-06 06:32:50 -04:00
|
|
|
#if AP_RCPROTOCOL_MAVLINK_RADIO_ENABLED
|
|
|
|
#include <GCS_MAVLink/GCS_MAVLink.h>
|
|
|
|
#endif
|
2018-01-17 15:31:11 -04:00
|
|
|
|
2019-07-05 02:12:15 -03:00
|
|
|
#define MAX_RCIN_CHANNELS 18
|
2018-01-17 15:31:11 -04:00
|
|
|
#define MIN_RCIN_CHANNELS 5
|
|
|
|
|
|
|
|
class AP_RCProtocol_Backend;
|
2018-10-31 21:21:03 -03:00
|
|
|
|
2018-01-17 15:31:11 -04:00
|
|
|
class AP_RCProtocol {
|
|
|
|
public:
|
2018-11-05 01:44:00 -04:00
|
|
|
|
2018-07-20 01:25:40 -03:00
|
|
|
enum rcprotocol_t {
|
2023-05-15 22:55:57 -03:00
|
|
|
#if AP_RCPROTOCOL_PPMSUM_ENABLED
|
|
|
|
PPMSUM = 0,
|
|
|
|
#endif
|
2023-05-15 23:03:39 -03:00
|
|
|
#if AP_RCPROTOCOL_IBUS_ENABLED
|
2021-11-09 03:33:48 -04:00
|
|
|
IBUS = 1,
|
2023-05-15 23:03:39 -03:00
|
|
|
#endif
|
2023-04-27 21:38:54 -03:00
|
|
|
#if AP_RCPROTOCOL_SBUS_ENABLED
|
2021-11-09 03:33:48 -04:00
|
|
|
SBUS = 2,
|
2023-04-27 21:38:54 -03:00
|
|
|
#endif
|
|
|
|
#if AP_RCPROTOCOL_SBUS_NI_ENABLED
|
2021-11-09 03:33:48 -04:00
|
|
|
SBUS_NI = 3,
|
2023-04-27 21:38:54 -03:00
|
|
|
#endif
|
2023-05-15 23:21:28 -03:00
|
|
|
#if AP_RCPROTOCOL_DSM_ENABLED
|
2021-11-09 03:33:48 -04:00
|
|
|
DSM = 4,
|
2023-05-15 23:21:28 -03:00
|
|
|
#endif
|
2023-05-15 23:08:53 -03:00
|
|
|
#if AP_RCPROTOCOL_SUMD_ENABLED
|
2021-11-09 03:33:48 -04:00
|
|
|
SUMD = 5,
|
2023-05-15 23:08:53 -03:00
|
|
|
#endif
|
2023-03-14 08:18:29 -03:00
|
|
|
#if AP_RCPROTOCOL_SRXL_ENABLED
|
2021-11-09 03:33:48 -04:00
|
|
|
SRXL = 6,
|
2023-03-14 08:18:29 -03:00
|
|
|
#endif
|
2023-04-26 04:19:07 -03:00
|
|
|
#if AP_RCPROTOCOL_SRXL2_ENABLED
|
2021-11-09 03:33:48 -04:00
|
|
|
SRXL2 = 7,
|
2023-04-26 04:19:07 -03:00
|
|
|
#endif
|
2023-04-26 10:46:08 -03:00
|
|
|
#if AP_RCPROTOCOL_CRSF_ENABLED
|
2021-11-09 03:33:48 -04:00
|
|
|
CRSF = 8,
|
2023-04-26 10:46:08 -03:00
|
|
|
#endif
|
2023-05-15 22:35:46 -03:00
|
|
|
#if AP_RCPROTOCOL_ST24_ENABLED
|
2021-11-09 03:33:48 -04:00
|
|
|
ST24 = 9,
|
2023-05-15 22:35:46 -03:00
|
|
|
#endif
|
2022-04-16 23:54:08 -03:00
|
|
|
#if AP_RCPROTOCOL_FPORT_ENABLED
|
2021-11-09 03:33:48 -04:00
|
|
|
FPORT = 10,
|
2022-04-16 23:54:08 -03:00
|
|
|
#endif
|
|
|
|
#if AP_RCPROTOCOL_FPORT2_ENABLED
|
2021-11-09 03:33:48 -04:00
|
|
|
FPORT2 = 11,
|
2022-04-16 23:54:08 -03:00
|
|
|
#endif
|
2021-11-05 02:39:56 -03:00
|
|
|
#if AP_RCPROTOCOL_FASTSBUS_ENABLED
|
|
|
|
FASTSBUS = 12,
|
2023-05-18 05:20:22 -03:00
|
|
|
#endif
|
|
|
|
#if AP_RCPROTOCOL_DRONECAN_ENABLED
|
|
|
|
DRONECAN = 13,
|
2023-12-13 04:47:51 -04:00
|
|
|
#endif
|
|
|
|
#if AP_RCPROTOCOL_GHST_ENABLED
|
|
|
|
GHST = 14,
|
2024-03-06 06:32:50 -04:00
|
|
|
#endif
|
|
|
|
#if AP_RCPROTOCOL_MAVLINK_RADIO_ENABLED
|
|
|
|
MAVLINK_RADIO = 15,
|
2024-03-05 01:50:57 -04:00
|
|
|
#endif
|
|
|
|
#if AP_RCPROTOCOL_JOYSTICK_SFML_ENABLED
|
|
|
|
JOYSTICK_SFML = 16,
|
2024-03-14 02:47:23 -03:00
|
|
|
#endif
|
|
|
|
#if AP_RCPROTOCOL_UDP_ENABLED
|
|
|
|
UDP = 17,
|
2024-03-14 02:47:43 -03:00
|
|
|
#endif
|
|
|
|
#if AP_RCPROTOCOL_FDM_ENABLED
|
|
|
|
FDM = 18,
|
2024-05-01 00:23:46 -03:00
|
|
|
#endif
|
|
|
|
#if AP_RCPROTOCOL_RADIO_ENABLED
|
|
|
|
RADIO = 19,
|
2021-11-05 02:39:56 -03:00
|
|
|
#endif
|
2018-01-17 15:31:11 -04:00
|
|
|
NONE //last enum always is None
|
|
|
|
};
|
2023-05-03 10:08:00 -03:00
|
|
|
|
|
|
|
// return protocol name as a string
|
|
|
|
static const char *protocol_name_from_protocol(rcprotocol_t protocol);
|
|
|
|
|
|
|
|
#if AP_RCPROTOCOL_ENABLED
|
|
|
|
|
|
|
|
AP_RCProtocol() {}
|
|
|
|
~AP_RCProtocol();
|
|
|
|
friend class AP_RCProtocol_Backend;
|
|
|
|
|
2018-01-17 15:31:11 -04:00
|
|
|
void init();
|
2021-02-01 12:26:33 -04:00
|
|
|
bool valid_serial_prot() const
|
2018-07-20 01:25:40 -03:00
|
|
|
{
|
|
|
|
return _valid_serial_prot;
|
|
|
|
}
|
2021-10-10 19:33:18 -03:00
|
|
|
bool should_search(uint32_t now_ms) const;
|
2018-01-17 15:31:11 -04:00
|
|
|
void process_pulse(uint32_t width_s0, uint32_t width_s1);
|
2018-11-03 02:52:57 -03:00
|
|
|
void process_pulse_list(const uint32_t *widths, uint16_t n, bool need_swap);
|
2019-12-02 01:13:14 -04:00
|
|
|
bool process_byte(uint8_t byte, uint32_t baudrate);
|
2020-05-09 05:20:33 -03:00
|
|
|
void process_handshake(uint32_t baudrate);
|
2019-08-28 19:38:58 -03:00
|
|
|
void update(void);
|
2018-11-02 08:25:05 -03:00
|
|
|
|
2022-03-16 07:02:19 -03:00
|
|
|
bool failsafe_active() const {
|
|
|
|
return _failsafe_active;
|
|
|
|
}
|
|
|
|
void set_failsafe_active(bool active) {
|
|
|
|
_failsafe_active = active;
|
|
|
|
}
|
|
|
|
|
2018-11-02 08:25:05 -03:00
|
|
|
void disable_for_pulses(enum rcprotocol_t protocol) {
|
|
|
|
_disabled_for_pulses |= (1U<<(uint8_t)protocol);
|
|
|
|
}
|
|
|
|
|
2024-05-01 00:23:46 -03:00
|
|
|
// in the case we've disabled most backends then the "return true" in
|
|
|
|
// the following method can never be reached, and the compiler gets
|
|
|
|
// annoyed at that.
|
|
|
|
#pragma GCC diagnostic push
|
|
|
|
#pragma GCC diagnostic ignored "-Wswitch-unreachable"
|
|
|
|
|
2018-11-02 19:49:17 -03:00
|
|
|
// for protocols without strong CRCs we require 3 good frames to lock on
|
|
|
|
bool requires_3_frames(enum rcprotocol_t p) {
|
2021-11-07 20:27:39 -04:00
|
|
|
switch (p) {
|
2023-05-15 23:21:28 -03:00
|
|
|
#if AP_RCPROTOCOL_DSM_ENABLED
|
2021-11-07 20:27:39 -04:00
|
|
|
case DSM:
|
2023-05-15 23:21:28 -03:00
|
|
|
#endif
|
2021-11-05 02:39:56 -03:00
|
|
|
#if AP_RCPROTOCOL_FASTSBUS_ENABLED
|
|
|
|
case FASTSBUS:
|
|
|
|
#endif
|
2023-04-27 21:38:54 -03:00
|
|
|
#if AP_RCPROTOCOL_SBUS_ENABLED
|
2021-11-07 20:27:39 -04:00
|
|
|
case SBUS:
|
2023-04-27 21:38:54 -03:00
|
|
|
#endif
|
|
|
|
#if AP_RCPROTOCOL_SBUS_NI_ENABLED
|
2021-11-07 20:27:39 -04:00
|
|
|
case SBUS_NI:
|
2023-04-27 21:38:54 -03:00
|
|
|
#endif
|
2023-05-15 22:55:57 -03:00
|
|
|
#if AP_RCPROTOCOL_PPMSUM_ENABLED
|
|
|
|
case PPMSUM:
|
|
|
|
#endif
|
2022-04-16 23:54:08 -03:00
|
|
|
#if AP_RCPROTOCOL_FPORT_ENABLED
|
2021-11-07 20:27:39 -04:00
|
|
|
case FPORT:
|
2022-04-16 23:54:08 -03:00
|
|
|
#endif
|
|
|
|
#if AP_RCPROTOCOL_FPORT2_ENABLED
|
2021-11-07 20:27:39 -04:00
|
|
|
case FPORT2:
|
2022-04-16 23:54:08 -03:00
|
|
|
#endif
|
2023-04-26 10:46:08 -03:00
|
|
|
#if AP_RCPROTOCOL_CRSF_ENABLED
|
2022-11-22 16:22:38 -04:00
|
|
|
case CRSF:
|
2023-12-13 04:47:51 -04:00
|
|
|
#endif
|
|
|
|
#if AP_RCPROTOCOL_GHST_ENABLED
|
|
|
|
case GHST:
|
2023-04-26 10:46:08 -03:00
|
|
|
#endif
|
2021-11-07 20:27:39 -04:00
|
|
|
return true;
|
2023-05-15 23:03:39 -03:00
|
|
|
#if AP_RCPROTOCOL_IBUS_ENABLED
|
2021-11-07 20:27:39 -04:00
|
|
|
case IBUS:
|
2023-05-15 23:03:39 -03:00
|
|
|
#endif
|
2023-05-15 23:08:53 -03:00
|
|
|
#if AP_RCPROTOCOL_SUMD_ENABLED
|
2021-11-07 20:27:39 -04:00
|
|
|
case SUMD:
|
2023-05-15 23:08:53 -03:00
|
|
|
#endif
|
2023-03-14 08:18:29 -03:00
|
|
|
#if AP_RCPROTOCOL_SRXL_ENABLED
|
2021-11-07 20:27:39 -04:00
|
|
|
case SRXL:
|
2023-03-14 08:18:29 -03:00
|
|
|
#endif
|
2023-04-26 04:19:07 -03:00
|
|
|
#if AP_RCPROTOCOL_SRXL2_ENABLED
|
2021-11-07 20:27:39 -04:00
|
|
|
case SRXL2:
|
2023-04-26 04:19:07 -03:00
|
|
|
#endif
|
2023-05-15 22:35:46 -03:00
|
|
|
#if AP_RCPROTOCOL_ST24_ENABLED
|
2021-11-07 20:27:39 -04:00
|
|
|
case ST24:
|
2023-05-18 05:20:22 -03:00
|
|
|
#endif
|
|
|
|
#if AP_RCPROTOCOL_DRONECAN_ENABLED
|
|
|
|
case DRONECAN:
|
2024-03-06 06:32:50 -04:00
|
|
|
#endif
|
|
|
|
#if AP_RCPROTOCOL_MAVLINK_RADIO_ENABLED
|
|
|
|
case MAVLINK_RADIO:
|
2024-03-05 01:50:57 -04:00
|
|
|
#endif
|
|
|
|
#if AP_RCPROTOCOL_JOYSTICK_SFML_ENABLED
|
|
|
|
case JOYSTICK_SFML:
|
2024-03-14 02:47:23 -03:00
|
|
|
#endif
|
|
|
|
#if AP_RCPROTOCOL_UDP_ENABLED
|
|
|
|
case UDP:
|
2024-03-14 02:47:43 -03:00
|
|
|
#endif
|
|
|
|
#if AP_RCPROTOCOL_FDM_ENABLED
|
|
|
|
case FDM:
|
2024-05-01 00:23:46 -03:00
|
|
|
#endif
|
|
|
|
#if AP_RCPROTOCOL_RADIO_ENABLED
|
|
|
|
case RADIO:
|
2023-05-15 22:35:46 -03:00
|
|
|
#endif
|
2021-11-07 20:27:39 -04:00
|
|
|
case NONE:
|
|
|
|
return false;
|
|
|
|
}
|
|
|
|
return false;
|
2018-11-02 19:49:17 -03:00
|
|
|
}
|
2024-05-01 00:23:46 -03:00
|
|
|
#pragma GCC diagnostic pop
|
2019-10-26 17:46:21 -03:00
|
|
|
|
2018-01-17 15:31:11 -04:00
|
|
|
uint8_t num_channels();
|
|
|
|
uint16_t read(uint8_t chan);
|
2020-01-28 22:16:54 -04:00
|
|
|
void read(uint16_t *pwm, uint8_t n);
|
2018-01-17 15:31:11 -04:00
|
|
|
bool new_input();
|
2018-04-10 03:14:54 -03:00
|
|
|
void start_bind(void);
|
2019-12-02 03:47:12 -04:00
|
|
|
int16_t get_RSSI(void) const;
|
2021-07-13 13:45:08 -03:00
|
|
|
int16_t get_rx_link_quality(void) const;
|
2018-07-20 01:25:40 -03:00
|
|
|
|
2018-11-02 19:49:56 -03:00
|
|
|
// return protocol name as a string
|
|
|
|
const char *protocol_name(void) const;
|
|
|
|
|
2019-10-26 17:46:21 -03:00
|
|
|
// return detected protocol
|
2018-11-05 01:44:00 -04:00
|
|
|
enum rcprotocol_t protocol_detected(void) const {
|
|
|
|
return _detected_protocol;
|
|
|
|
}
|
2019-08-27 04:40:22 -03:00
|
|
|
|
|
|
|
// add a UART for RCIN
|
|
|
|
void add_uart(AP_HAL::UARTDriver* uart);
|
2022-10-15 10:16:17 -03:00
|
|
|
bool has_uart() const { return added.uart != nullptr; }
|
2018-10-31 21:21:03 -03:00
|
|
|
|
2020-08-12 23:27:43 -03:00
|
|
|
// set allowed RC protocols
|
|
|
|
void set_rc_protocols(uint32_t mask) {
|
|
|
|
rc_protocols_mask = mask;
|
|
|
|
}
|
|
|
|
|
2021-11-10 20:34:49 -04:00
|
|
|
class SerialConfig {
|
|
|
|
public:
|
|
|
|
void apply_to_uart(AP_HAL::UARTDriver *uart) const;
|
|
|
|
|
|
|
|
uint32_t baud;
|
|
|
|
uint8_t parity;
|
|
|
|
uint8_t stop_bits;
|
|
|
|
bool invert_rx;
|
|
|
|
};
|
|
|
|
|
2022-03-27 03:29:36 -03:00
|
|
|
// return true if we are decoding a byte stream, instead of pulses
|
|
|
|
bool using_uart(void) const {
|
|
|
|
return _detected_with_bytes;
|
|
|
|
}
|
|
|
|
|
2024-03-06 06:32:50 -04:00
|
|
|
// handle mavlink radio
|
|
|
|
#if AP_RCPROTOCOL_MAVLINK_RADIO_ENABLED
|
|
|
|
void handle_radio_rc_channels(const mavlink_radio_rc_channels_t* packet);
|
|
|
|
#endif
|
|
|
|
|
2018-01-17 15:31:11 -04:00
|
|
|
private:
|
2019-08-27 04:40:22 -03:00
|
|
|
void check_added_uart(void);
|
|
|
|
|
2020-08-12 23:27:43 -03:00
|
|
|
// return true if a specific protocol is enabled
|
|
|
|
bool protocol_enabled(enum rcprotocol_t protocol) const;
|
|
|
|
|
2024-02-05 01:02:44 -04:00
|
|
|
// explicitly investigate a backend for data, as opposed to
|
|
|
|
// feeding the backend a byte (or pulse-train) at a time and
|
|
|
|
// having them make an "add_input" callback):
|
|
|
|
bool detect_async_protocol(rcprotocol_t protocol);
|
|
|
|
|
2018-01-17 15:31:11 -04:00
|
|
|
enum rcprotocol_t _detected_protocol = NONE;
|
2018-11-02 08:25:05 -03:00
|
|
|
uint16_t _disabled_for_pulses;
|
2018-11-01 00:44:55 -03:00
|
|
|
bool _detected_with_bytes;
|
2018-01-17 15:31:11 -04:00
|
|
|
AP_RCProtocol_Backend *backend[NONE];
|
2020-04-30 16:34:51 -03:00
|
|
|
bool _new_input;
|
2018-01-17 19:12:16 -04:00
|
|
|
uint32_t _last_input_ms;
|
2022-03-16 07:02:19 -03:00
|
|
|
bool _failsafe_active;
|
2020-04-30 16:34:51 -03:00
|
|
|
bool _valid_serial_prot;
|
2018-10-31 21:21:03 -03:00
|
|
|
|
2019-08-27 04:40:22 -03:00
|
|
|
// optional additional uart
|
|
|
|
struct {
|
|
|
|
AP_HAL::UARTDriver *uart;
|
|
|
|
bool opened;
|
2021-11-10 20:34:49 -04:00
|
|
|
uint32_t last_config_change_ms;
|
|
|
|
uint8_t config_num;
|
2019-08-27 04:40:22 -03:00
|
|
|
} added;
|
2020-08-12 23:27:43 -03:00
|
|
|
|
|
|
|
// allowed RC protocols mask (first bit means "all")
|
|
|
|
uint32_t rc_protocols_mask;
|
2023-05-03 10:08:00 -03:00
|
|
|
|
|
|
|
#endif // AP_RCPROTCOL_ENABLED
|
|
|
|
|
2019-08-27 04:40:22 -03:00
|
|
|
};
|
|
|
|
|
2023-05-03 10:08:00 -03:00
|
|
|
#if AP_RCPROTOCOL_ENABLED
|
2019-08-27 04:40:22 -03:00
|
|
|
namespace AP {
|
|
|
|
AP_RCProtocol &RC();
|
2018-01-17 15:31:11 -04:00
|
|
|
};
|
|
|
|
|
2018-01-17 19:12:16 -04:00
|
|
|
#include "AP_RCProtocol_Backend.h"
|
2023-05-03 10:08:00 -03:00
|
|
|
#endif // AP_RCProtocol_enabled
|