Path: blob/master/libraries/AP_Frsky_Telem/AP_Frsky_MAVlite_MAVliteToSPort.h
10012 views
#pragma once12#include "AP_Frsky_config.h"34#if HAL_WITH_FRSKY_TELEM_BIDIRECTIONAL56#include "AP_Frsky_MAVlite_Message.h"7#include "AP_Frsky_SPort.h"89#include <AP_HAL/utility/RingBuffer.h>1011#include <stdint.h>1213/*14* An instance of this class encodes a MAVlite message into several15* SPort packets, and pushes them onto the supplied queue.16*17* process() will return false if there is insufficient room in the18* queue for all SPort packets.19*20* See AP_Frsky_MAVlite.h for a description of the encoding of a21* MAVlite message in SPort packets.22*/2324class AP_Frsky_MAVlite_MAVliteToSPort {25public:2627// insert sport packets calculated from mavlite msg into queue28bool process(ObjectBuffer_TS<AP_Frsky_SPort::sport_packet_t> &queue,29const AP_Frsky_MAVlite_Message &msg) WARN_IF_UNUSED;3031private:3233enum class State : uint8_t {34WANT_LEN,35WANT_MSGID,36WANT_PAYLOAD,37WANT_CHECKSUM,38DONE,39};40State state = State::WANT_LEN;4142void reset();4344void process_byte(uint8_t byte, ObjectBuffer_TS<AP_Frsky_SPort::sport_packet_t> &queue);4546AP_Frsky_SPort::sport_packet_t packet {};47uint8_t packet_offs = 0;4849uint8_t next_seq = 0;50uint8_t payload_count = 0;51uint8_t payload_len;5253int16_t checksum; // sent at end of packet54void update_checksum(const uint8_t c);55};5657#endif // HAL_WITH_FRSKY_TELEM_BIDIRECTIONAL585960