2019-12-02 01:13:14 -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/>.
|
|
|
|
*
|
|
|
|
* Code by Andrew Tridgell and Siddharth Bharat Purohit
|
|
|
|
*/
|
|
|
|
|
|
|
|
#pragma once
|
|
|
|
|
2022-04-16 23:54:08 -03:00
|
|
|
#include "AP_RCProtocol_config.h"
|
|
|
|
|
|
|
|
#if AP_RCPROTOCOL_FPORT_ENABLED
|
2020-12-10 05:28:41 -04:00
|
|
|
|
2019-12-02 01:13:14 -04:00
|
|
|
#include "AP_RCProtocol.h"
|
|
|
|
#include "SoftSerial.h"
|
2022-04-16 23:54:08 -03:00
|
|
|
#include <AP_Frsky_Telem/AP_Frsky_SPort.h>
|
2019-12-02 01:13:14 -04:00
|
|
|
|
|
|
|
#define FPORT_CONTROL_FRAME_SIZE 29
|
|
|
|
|
|
|
|
struct FPort_Frame;
|
|
|
|
|
|
|
|
class AP_RCProtocol_FPort : public AP_RCProtocol_Backend {
|
|
|
|
public:
|
|
|
|
AP_RCProtocol_FPort(AP_RCProtocol &_frontend, bool inverted);
|
|
|
|
void process_pulse(uint32_t width_s0, uint32_t width_s1) override;
|
|
|
|
void process_byte(uint8_t byte, uint32_t baudrate) override;
|
|
|
|
|
|
|
|
private:
|
|
|
|
void decode_control(const FPort_Frame &frame);
|
|
|
|
void decode_downlink(const FPort_Frame &frame);
|
|
|
|
bool check_checksum(void);
|
|
|
|
|
|
|
|
void _process_byte(uint32_t timestamp_us, uint8_t byte);
|
|
|
|
SoftSerial ss{115200, SoftSerial::SERIAL_CONFIG_8N1};
|
|
|
|
uint32_t saved_width;
|
|
|
|
|
|
|
|
struct {
|
|
|
|
uint8_t buf[FPORT_CONTROL_FRAME_SIZE];
|
|
|
|
uint8_t ofs;
|
|
|
|
uint32_t last_byte_us;
|
2019-12-02 23:22:44 -04:00
|
|
|
bool got_DLE;
|
2019-12-02 01:13:14 -04:00
|
|
|
} byte_input;
|
|
|
|
|
|
|
|
const bool inverted;
|
2020-03-19 19:48:40 -03:00
|
|
|
|
2023-08-06 01:15:48 -03:00
|
|
|
#if AP_FRSKY_SPORT_TELEM_ENABLED
|
2020-03-19 19:48:40 -03:00
|
|
|
struct {
|
|
|
|
bool available = false;
|
2020-12-10 05:28:41 -04:00
|
|
|
AP_Frsky_SPort::sport_packet_t packet;
|
2020-03-19 19:48:40 -03:00
|
|
|
} telem_data;
|
2023-08-06 01:15:48 -03:00
|
|
|
#endif // AP_FRSKY_SPORT_TELEM_ENABLED
|
2020-03-19 19:48:40 -03:00
|
|
|
|
|
|
|
// receiver sends 0x10 when ready to receive telemetry frames (R-XSR)
|
|
|
|
bool rx_driven_frame_rate = false;
|
|
|
|
|
|
|
|
// if the receiver is not controlling frame rate apply a constraint on consecutive frames
|
|
|
|
uint8_t consecutive_telemetry_frame_count;
|
2019-12-02 01:13:14 -04:00
|
|
|
};
|
2022-04-16 23:54:08 -03:00
|
|
|
|
|
|
|
#endif // AP_RCPROTOCOL_FPORT_ENABLED
|