ardupilot/libraries/AP_RCProtocol/AP_RCProtocol_Backend.h

114 lines
3.5 KiB
C
Raw Normal View History

/*
* 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/>.
*
* Code by Andrew Tridgell and Siddharth Bharat Purohit
*/
#pragma once
#include "AP_RCProtocol.h"
#include <AP_HAL/utility/sparse-endian.h>
class AP_RCProtocol_Backend {
friend class AP_RCProtcol;
public:
AP_RCProtocol_Backend(AP_RCProtocol &_frontend);
virtual ~AP_RCProtocol_Backend() {}
virtual void process_pulse(uint32_t width_s0, uint32_t width_s1) {}
virtual void process_byte(uint8_t byte, uint32_t baudrate) {}
uint16_t read(uint8_t chan);
void read(uint16_t *pwm, uint8_t n);
bool new_input();
uint8_t num_channels();
2018-04-10 03:14:54 -03:00
// support for receivers that have FC initiated bind support
virtual void start_bind(void) {}
// allow for backends that need regular polling
virtual void update(void) {}
enum {
PARSE_TYPE_SIGREAD,
PARSE_TYPE_SERIAL
};
// get number of frames, ignoring failsafe
uint32_t get_rc_frame_count(void) const {
return rc_frame_count;
}
// reset valid rc frame count
void reset_rc_frame_count(void) {
rc_frame_count = 0;
}
// get number of frames, honoring failsafe
uint32_t get_rc_input_count(void) const {
return rc_input_count;
}
2019-12-02 03:47:12 -04:00
// get RSSI
int16_t get_RSSI(void) const {
return rssi;
}
// get UART for RCIN, if available. This will return false if we
// aren't getting the active RC input protocol via the uart
AP_HAL::UARTDriver *get_UART(void) const {
return frontend._detected_with_bytes?frontend.added.uart:nullptr;
}
// get an available uart regardless of whether we have detected a protocol via it
AP_HAL::UARTDriver *get_available_UART(void) const {
return frontend.added.uart;
}
// return true if we have a uart available for protocol handling.
bool have_UART(void) const {
return frontend.added.uart != nullptr;
}
protected:
struct Channels11Bit_8Chan {
#if __BYTE_ORDER != __LITTLE_ENDIAN
#error "Only supported on little-endian architectures"
#endif
uint32_t ch0 : 11;
uint32_t ch1 : 11;
uint32_t ch2 : 11;
uint32_t ch3 : 11;
uint32_t ch4 : 11;
uint32_t ch5 : 11;
uint32_t ch6 : 11;
uint32_t ch7 : 11;
} PACKED;
2019-12-02 03:47:12 -04:00
void add_input(uint8_t num_channels, uint16_t *values, bool in_failsafe, int16_t rssi=-1);
2020-03-23 16:20:00 -03:00
AP_RCProtocol &frontend;
void log_data(AP_RCProtocol::rcprotocol_t prot, uint32_t timestamp, const uint8_t *data, uint8_t len) const;
// decode channels from the standard 11bit format (used by CRSF and SBUS)
void decode_11bit_channels(const uint8_t* data, uint8_t nchannels, uint16_t *values, uint16_t mult, uint16_t div, uint16_t offset);
private:
uint32_t rc_input_count;
uint32_t last_rc_input_count;
uint32_t rc_frame_count;
uint16_t _pwm_values[MAX_RCIN_CHANNELS];
uint8_t _num_channels;
2019-12-02 03:47:12 -04:00
int16_t rssi = -1;
};