123456789101112131415161718192021222324252627282930313233343536373839404142434445464748495051525354555657585960616263646566676869707172737475767778798081828384858687888990919293949596979899100101102103104105106107108109 |
- #pragma once
- #include <AP_HAL/AP_HAL.h>
- #include <AP_Common/AP_Common.h>
- #define MAX_RCIN_CHANNELS 18
- #define MIN_RCIN_CHANNELS 5
- class AP_RCProtocol_Backend;
- class AP_RCProtocol {
- public:
- AP_RCProtocol() {}
- ~AP_RCProtocol();
- enum rcprotocol_t {
- PPM = 0,
- IBUS,
- SBUS,
- SBUS_NI,
- DSM,
- SUMD,
- SRXL,
- ST24,
- NONE
- };
- void init();
- bool valid_serial_prot()
- {
- return _valid_serial_prot;
- }
- void process_pulse(uint32_t width_s0, uint32_t width_s1);
- void process_pulse_list(const uint32_t *widths, uint16_t n, bool need_swap);
- void process_byte(uint8_t byte, uint32_t baudrate);
- void update(void);
- void disable_for_pulses(enum rcprotocol_t protocol) {
- _disabled_for_pulses |= (1U<<(uint8_t)protocol);
- }
-
- bool requires_3_frames(enum rcprotocol_t p) {
- return (p == DSM || p == SBUS || p == SBUS_NI || p == PPM);
- }
-
- enum rcprotocol_t protocol_detected()
- {
- return _detected_protocol;
- }
- uint8_t num_channels();
- uint16_t read(uint8_t chan);
- bool new_input();
- void start_bind(void);
-
- static const char *protocol_name_from_protocol(rcprotocol_t protocol);
-
- const char *protocol_name(void) const;
-
- enum rcprotocol_t protocol_detected(void) const {
- return _detected_protocol;
- }
-
- void add_uart(AP_HAL::UARTDriver* uart);
- private:
- void check_added_uart(void);
- enum rcprotocol_t _detected_protocol = NONE;
- uint16_t _disabled_for_pulses;
- bool _detected_with_bytes;
- AP_RCProtocol_Backend *backend[NONE];
- bool _new_input = false;
- uint32_t _last_input_ms;
- bool _valid_serial_prot = false;
- uint8_t _good_frames[NONE];
-
- struct {
- AP_HAL::UARTDriver *uart;
- uint32_t baudrate;
- bool opened;
- uint32_t last_baud_change_ms;
- } added;
- };
- namespace AP {
- AP_RCProtocol &RC();
- };
- #include "AP_RCProtocol_Backend.h"
|