mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-18 06:38:29 -04:00
AP_RCProtocol: cleanup code style
using Tools/CodeStyle/ardupilot-astyle.sh
This commit is contained in:
parent
f9ab7e54d4
commit
1dcac14b1e
@ -24,7 +24,7 @@
|
|||||||
class AP_RCProtocol_Backend;
|
class AP_RCProtocol_Backend;
|
||||||
class AP_RCProtocol {
|
class AP_RCProtocol {
|
||||||
public:
|
public:
|
||||||
enum rcprotocol_t{
|
enum rcprotocol_t {
|
||||||
PPM = 0,
|
PPM = 0,
|
||||||
SBUS,
|
SBUS,
|
||||||
SBUS_NI,
|
SBUS_NI,
|
||||||
@ -35,10 +35,16 @@ public:
|
|||||||
NONE //last enum always is None
|
NONE //last enum always is None
|
||||||
};
|
};
|
||||||
void init();
|
void init();
|
||||||
bool valid_serial_prot() { return _valid_serial_prot; }
|
bool valid_serial_prot()
|
||||||
|
{
|
||||||
|
return _valid_serial_prot;
|
||||||
|
}
|
||||||
void process_pulse(uint32_t width_s0, uint32_t width_s1);
|
void process_pulse(uint32_t width_s0, uint32_t width_s1);
|
||||||
void process_byte(uint8_t byte);
|
void process_byte(uint8_t byte);
|
||||||
enum rcprotocol_t protocol_detected() { return _detected_protocol; }
|
enum rcprotocol_t protocol_detected()
|
||||||
|
{
|
||||||
|
return _detected_protocol;
|
||||||
|
}
|
||||||
uint8_t num_channels();
|
uint8_t num_channels();
|
||||||
uint16_t read(uint8_t chan);
|
uint16_t read(uint8_t chan);
|
||||||
bool new_input();
|
bool new_input();
|
||||||
|
@ -19,8 +19,7 @@
|
|||||||
|
|
||||||
#include "AP_RCProtocol.h"
|
#include "AP_RCProtocol.h"
|
||||||
|
|
||||||
class AP_RCProtocol_Backend
|
class AP_RCProtocol_Backend {
|
||||||
{
|
|
||||||
friend class AP_RCProtcol;
|
friend class AP_RCProtcol;
|
||||||
|
|
||||||
public:
|
public:
|
||||||
|
@ -48,7 +48,7 @@ void AP_RCProtocol_DSM::process_pulse(uint32_t width_s0, uint32_t width_s1)
|
|||||||
byte_ofs = dsm_state.bit_ofs/10;
|
byte_ofs = dsm_state.bit_ofs/10;
|
||||||
bit_ofs = dsm_state.bit_ofs%10;
|
bit_ofs = dsm_state.bit_ofs%10;
|
||||||
|
|
||||||
if(byte_ofs > 15) {
|
if (byte_ofs > 15) {
|
||||||
// invalid data
|
// invalid data
|
||||||
goto reset;
|
goto reset;
|
||||||
}
|
}
|
||||||
@ -134,8 +134,9 @@ reset:
|
|||||||
bool AP_RCProtocol_DSM::dsm_decode_channel(uint16_t raw, unsigned shift, unsigned *channel, unsigned *value)
|
bool AP_RCProtocol_DSM::dsm_decode_channel(uint16_t raw, unsigned shift, unsigned *channel, unsigned *value)
|
||||||
{
|
{
|
||||||
|
|
||||||
if (raw == 0xffff)
|
if (raw == 0xffff) {
|
||||||
return false;
|
return false;
|
||||||
|
}
|
||||||
|
|
||||||
*channel = (raw >> shift) & 0xf;
|
*channel = (raw >> shift) & 0xf;
|
||||||
|
|
||||||
@ -175,18 +176,21 @@ void AP_RCProtocol_DSM::dsm_guess_format(bool reset, const uint8_t dsm_frame[16]
|
|||||||
unsigned channel, value;
|
unsigned channel, value;
|
||||||
|
|
||||||
/* if the channel decodes, remember the assigned number */
|
/* if the channel decodes, remember the assigned number */
|
||||||
if (dsm_decode_channel(raw, 10, &channel, &value) && (channel < 31))
|
if (dsm_decode_channel(raw, 10, &channel, &value) && (channel < 31)) {
|
||||||
cs10 |= (1 << channel);
|
cs10 |= (1 << channel);
|
||||||
|
}
|
||||||
|
|
||||||
if (dsm_decode_channel(raw, 11, &channel, &value) && (channel < 31))
|
if (dsm_decode_channel(raw, 11, &channel, &value) && (channel < 31)) {
|
||||||
cs11 |= (1 << channel);
|
cs11 |= (1 << channel);
|
||||||
|
}
|
||||||
|
|
||||||
/* XXX if we cared, we could look for the phase bit here to decide 1 vs. 2-dsm_frame format */
|
/* XXX if we cared, we could look for the phase bit here to decide 1 vs. 2-dsm_frame format */
|
||||||
}
|
}
|
||||||
|
|
||||||
/* wait until we have seen plenty of frames - 5 should normally be enough */
|
/* wait until we have seen plenty of frames - 5 should normally be enough */
|
||||||
if (samples++ < 5)
|
if (samples++ < 5) {
|
||||||
return;
|
return;
|
||||||
|
}
|
||||||
|
|
||||||
/*
|
/*
|
||||||
* Iterate the set of sensible sniffed channel sets and see whether
|
* Iterate the set of sensible sniffed channel sets and see whether
|
||||||
@ -213,12 +217,14 @@ void AP_RCProtocol_DSM::dsm_guess_format(bool reset, const uint8_t dsm_frame[16]
|
|||||||
|
|
||||||
for (unsigned i = 0; i < sizeof(masks)/sizeof(masks[0]); i++) {
|
for (unsigned i = 0; i < sizeof(masks)/sizeof(masks[0]); i++) {
|
||||||
|
|
||||||
if (cs10 == masks[i])
|
if (cs10 == masks[i]) {
|
||||||
votes10++;
|
votes10++;
|
||||||
|
}
|
||||||
|
|
||||||
if (cs11 == masks[i])
|
if (cs11 == masks[i]) {
|
||||||
votes11++;
|
votes11++;
|
||||||
}
|
}
|
||||||
|
}
|
||||||
|
|
||||||
if ((votes11 == 1) && (votes10 == 0)) {
|
if ((votes11 == 1) && (votes10 == 0)) {
|
||||||
dsm_channel_shift = 11;
|
dsm_channel_shift = 11;
|
||||||
@ -283,20 +289,24 @@ bool AP_RCProtocol_DSM::dsm_decode(uint64_t frame_time, const uint8_t dsm_frame[
|
|||||||
uint16_t raw = (dp[0] << 8) | dp[1];
|
uint16_t raw = (dp[0] << 8) | dp[1];
|
||||||
unsigned channel, value;
|
unsigned channel, value;
|
||||||
|
|
||||||
if (!dsm_decode_channel(raw, dsm_channel_shift, &channel, &value))
|
if (!dsm_decode_channel(raw, dsm_channel_shift, &channel, &value)) {
|
||||||
continue;
|
continue;
|
||||||
|
}
|
||||||
|
|
||||||
/* ignore channels out of range */
|
/* ignore channels out of range */
|
||||||
if (channel >= max_values)
|
if (channel >= max_values) {
|
||||||
continue;
|
continue;
|
||||||
|
}
|
||||||
|
|
||||||
/* update the decoded channel count */
|
/* update the decoded channel count */
|
||||||
if (channel >= *num_values)
|
if (channel >= *num_values) {
|
||||||
*num_values = channel + 1;
|
*num_values = channel + 1;
|
||||||
|
}
|
||||||
|
|
||||||
/* convert 0-1024 / 0-2048 values to 1000-2000 ppm encoding. */
|
/* convert 0-1024 / 0-2048 values to 1000-2000 ppm encoding. */
|
||||||
if (dsm_channel_shift == 10)
|
if (dsm_channel_shift == 10) {
|
||||||
value *= 2;
|
value *= 2;
|
||||||
|
}
|
||||||
|
|
||||||
/*
|
/*
|
||||||
* Spektrum scaling is special. There are these basic considerations
|
* Spektrum scaling is special. There are these basic considerations
|
||||||
@ -346,8 +356,9 @@ bool AP_RCProtocol_DSM::dsm_decode(uint64_t frame_time, const uint8_t dsm_frame[
|
|||||||
* lines, so if we get a channel count of 13, we'll return 12 (the last
|
* lines, so if we get a channel count of 13, we'll return 12 (the last
|
||||||
* data index that is stable).
|
* data index that is stable).
|
||||||
*/
|
*/
|
||||||
if (*num_values == 13)
|
if (*num_values == 13) {
|
||||||
*num_values = 12;
|
*num_values = 12;
|
||||||
|
}
|
||||||
|
|
||||||
#if 0
|
#if 0
|
||||||
if (dsm_channel_shift == 11) {
|
if (dsm_channel_shift == 11) {
|
||||||
|
@ -180,8 +180,7 @@ bool AP_RCProtocol_SBUS::sbus_decode(const uint8_t frame[25], uint16_t *values,
|
|||||||
/* report that we failed to read anything valid off the receiver */
|
/* report that we failed to read anything valid off the receiver */
|
||||||
*sbus_failsafe = true;
|
*sbus_failsafe = true;
|
||||||
*sbus_frame_drop = true;
|
*sbus_frame_drop = true;
|
||||||
}
|
} else if (frame[SBUS_FLAGS_BYTE] & (1 << SBUS_FRAMELOST_BIT)) { /* a frame was lost */
|
||||||
else if (frame[SBUS_FLAGS_BYTE] & (1 << SBUS_FRAMELOST_BIT)) { /* a frame was lost */
|
|
||||||
/* set a special warning flag
|
/* set a special warning flag
|
||||||
*
|
*
|
||||||
* Attention! This flag indicates a skipped frame only, not a total link loss! Handling this
|
* Attention! This flag indicates a skipped frame only, not a total link loss! Handling this
|
||||||
|
@ -22,7 +22,8 @@
|
|||||||
class AP_RCProtocol_SBUS_NI : public AP_RCProtocol_SBUS {
|
class AP_RCProtocol_SBUS_NI : public AP_RCProtocol_SBUS {
|
||||||
public:
|
public:
|
||||||
AP_RCProtocol_SBUS_NI(AP_RCProtocol &_frontend) : AP_RCProtocol_SBUS(_frontend), saved_width(0) {}
|
AP_RCProtocol_SBUS_NI(AP_RCProtocol &_frontend) : AP_RCProtocol_SBUS(_frontend), saved_width(0) {}
|
||||||
void process_pulse(uint32_t width_s0, uint32_t width_s1) override {
|
void process_pulse(uint32_t width_s0, uint32_t width_s1) override
|
||||||
|
{
|
||||||
AP_RCProtocol_SBUS::process_pulse(saved_width, width_s0);
|
AP_RCProtocol_SBUS::process_pulse(saved_width, width_s0);
|
||||||
saved_width = width_s1;
|
saved_width = width_s1;
|
||||||
}
|
}
|
||||||
|
@ -41,7 +41,7 @@ uint16_t AP_RCProtocol_SRXL::srxl_crc16(uint16_t crc, uint8_t new_byte)
|
|||||||
{
|
{
|
||||||
uint8_t loop;
|
uint8_t loop;
|
||||||
crc = crc ^ (uint16_t)new_byte << 8;
|
crc = crc ^ (uint16_t)new_byte << 8;
|
||||||
for(loop = 0; loop < 8; loop++) {
|
for (loop = 0; loop < 8; loop++) {
|
||||||
crc = (crc & 0x8000) ? (crc << 1) ^ 0x1021 : (crc << 1);
|
crc = (crc & 0x8000) ? (crc << 1) ^ 0x1021 : (crc << 1);
|
||||||
}
|
}
|
||||||
return crc;
|
return crc;
|
||||||
@ -163,7 +163,7 @@ int AP_RCProtocol_SRXL::srxl_channels_get_v1v2(uint16_t max_values, uint8_t *num
|
|||||||
}
|
}
|
||||||
|
|
||||||
/* provide channel data to FMU */
|
/* provide channel data to FMU */
|
||||||
if ( (uint16_t)*num_values > max_values) {
|
if ((uint16_t)*num_values > max_values) {
|
||||||
*num_values = (uint8_t)max_values;
|
*num_values = (uint8_t)max_values;
|
||||||
}
|
}
|
||||||
memcpy(values, channels, (*num_values)*2);
|
memcpy(values, channels, (*num_values)*2);
|
||||||
@ -254,9 +254,9 @@ void AP_RCProtocol_SRXL::process_byte(uint8_t byte)
|
|||||||
uint64_t timestamp_us = AP_HAL::micros64();
|
uint64_t timestamp_us = AP_HAL::micros64();
|
||||||
/*----------------------------------------distinguish different srxl variants at the beginning of each frame---------------------------------------------- */
|
/*----------------------------------------distinguish different srxl variants at the beginning of each frame---------------------------------------------- */
|
||||||
/* Check if we have a new begin of a frame --> indicators: Time gap in datastream + SRXL header 0xA<VARIANT>*/
|
/* Check if we have a new begin of a frame --> indicators: Time gap in datastream + SRXL header 0xA<VARIANT>*/
|
||||||
if ( (timestamp_us - last_data_us) >= SRXL_MIN_FRAMESPACE_US) {
|
if ((timestamp_us - last_data_us) >= SRXL_MIN_FRAMESPACE_US) {
|
||||||
/* Now detect SRXL variant based on header */
|
/* Now detect SRXL variant based on header */
|
||||||
switch(byte) {
|
switch (byte) {
|
||||||
case SRXL_HEADER_V1:
|
case SRXL_HEADER_V1:
|
||||||
frame_len_full = SRXL_FRAMELEN_V1;
|
frame_len_full = SRXL_FRAMELEN_V1;
|
||||||
frame_header = SRXL_HEADER_V1;
|
frame_header = SRXL_HEADER_V1;
|
||||||
@ -306,7 +306,7 @@ void AP_RCProtocol_SRXL::process_byte(uint8_t byte)
|
|||||||
if (buflen <= (frame_len_full-2)) {
|
if (buflen <= (frame_len_full-2)) {
|
||||||
crc_fmu = srxl_crc16(crc_fmu,byte);
|
crc_fmu = srxl_crc16(crc_fmu,byte);
|
||||||
}
|
}
|
||||||
if( buflen == frame_len_full ) {
|
if (buflen == frame_len_full) {
|
||||||
/* CRC check here */
|
/* CRC check here */
|
||||||
crc_receiver = ((uint16_t)buffer[buflen-2] << 8U) | ((uint16_t)buffer[buflen-1]);
|
crc_receiver = ((uint16_t)buffer[buflen-2] << 8U) | ((uint16_t)buffer[buflen-1]);
|
||||||
if (crc_receiver == crc_fmu) {
|
if (crc_receiver == crc_fmu) {
|
||||||
@ -332,8 +332,7 @@ void AP_RCProtocol_SRXL::process_byte(uint8_t byte)
|
|||||||
}
|
}
|
||||||
}
|
}
|
||||||
decode_state_next = STATE_IDLE; /* frame data buffering and decoding finished --> statemachine not in use until new header drops is */
|
decode_state_next = STATE_IDLE; /* frame data buffering and decoding finished --> statemachine not in use until new header drops is */
|
||||||
}
|
} else {
|
||||||
else {
|
|
||||||
/* frame not completely received --> frame data buffering still ongoing */
|
/* frame not completely received --> frame data buffering still ongoing */
|
||||||
decode_state_next = STATE_COLLECT;
|
decode_state_next = STATE_COLLECT;
|
||||||
}
|
}
|
||||||
|
@ -48,7 +48,7 @@ private:
|
|||||||
ST24_PACKET_TYPE_TRANSMITTERGPSDATA
|
ST24_PACKET_TYPE_TRANSMITTERGPSDATA
|
||||||
};
|
};
|
||||||
|
|
||||||
#pragma pack(push, 1)
|
#pragma pack(push, 1)
|
||||||
typedef struct {
|
typedef struct {
|
||||||
uint8_t header1; ///< 0x55 for a valid packet
|
uint8_t header1; ///< 0x55 for a valid packet
|
||||||
uint8_t header2; ///< 0x55 for a valid packet
|
uint8_t header2; ///< 0x55 for a valid packet
|
||||||
@ -129,7 +129,7 @@ private:
|
|||||||
uint8_t pressCompassStatus; ///< baro / compass status
|
uint8_t pressCompassStatus; ///< baro / compass status
|
||||||
} TelemetryData;
|
} TelemetryData;
|
||||||
|
|
||||||
#pragma pack(pop)
|
#pragma pack(pop)
|
||||||
|
|
||||||
enum ST24_DECODE_STATE {
|
enum ST24_DECODE_STATE {
|
||||||
ST24_DECODE_STATE_UNSYNCED = 0,
|
ST24_DECODE_STATE_UNSYNCED = 0,
|
||||||
|
@ -29,7 +29,7 @@ private:
|
|||||||
static uint16_t sumd_crc16(uint16_t crc, uint8_t value);
|
static uint16_t sumd_crc16(uint16_t crc, uint8_t value);
|
||||||
static uint8_t sumd_crc8(uint8_t crc, uint8_t value);
|
static uint8_t sumd_crc8(uint8_t crc, uint8_t value);
|
||||||
|
|
||||||
#pragma pack(push, 1)
|
#pragma pack(push, 1)
|
||||||
typedef struct {
|
typedef struct {
|
||||||
uint8_t header; ///< 0xA8 for a valid packet
|
uint8_t header; ///< 0xA8 for a valid packet
|
||||||
uint8_t status; ///< 0x01 valid and live SUMD data frame / 0x00 = SUMH / 0x81 = Failsafe
|
uint8_t status; ///< 0x01 valid and live SUMD data frame / 0x00 = SUMH / 0x81 = Failsafe
|
||||||
@ -40,7 +40,7 @@ private:
|
|||||||
uint8_t telemetry; ///< Telemetry request
|
uint8_t telemetry; ///< Telemetry request
|
||||||
uint8_t crc8; ///< SUMH CRC8
|
uint8_t crc8; ///< SUMH CRC8
|
||||||
} ReceiverFcPacketHoTT;
|
} ReceiverFcPacketHoTT;
|
||||||
#pragma pack(pop)
|
#pragma pack(pop)
|
||||||
|
|
||||||
|
|
||||||
enum SUMD_DECODE_STATE {
|
enum SUMD_DECODE_STATE {
|
||||||
|
Loading…
Reference in New Issue
Block a user