AP_RCProtocol: cleanup code style

using Tools/CodeStyle/ardupilot-astyle.sh
This commit is contained in:
Andrew Tridgell 2018-07-20 14:25:40 +10:00
parent f9ab7e54d4
commit 1dcac14b1e
17 changed files with 581 additions and 566 deletions

View File

@ -35,10 +35,16 @@ public:
NONE //last enum always is None
};
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_byte(uint8_t byte);
enum rcprotocol_t protocol_detected() { return _detected_protocol; }
enum rcprotocol_t protocol_detected()
{
return _detected_protocol;
}
uint8_t num_channels();
uint16_t read(uint8_t chan);
bool new_input();

View File

@ -19,8 +19,7 @@
#include "AP_RCProtocol.h"
class AP_RCProtocol_Backend
{
class AP_RCProtocol_Backend {
friend class AP_RCProtcol;
public:

View File

@ -134,8 +134,9 @@ reset:
bool AP_RCProtocol_DSM::dsm_decode_channel(uint16_t raw, unsigned shift, unsigned *channel, unsigned *value)
{
if (raw == 0xffff)
if (raw == 0xffff) {
return false;
}
*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;
/* 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);
}
if (dsm_decode_channel(raw, 11, &channel, &value) && (channel < 31))
if (dsm_decode_channel(raw, 11, &channel, &value) && (channel < 31)) {
cs11 |= (1 << channel);
}
/* 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 */
if (samples++ < 5)
if (samples++ < 5) {
return;
}
/*
* 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++) {
if (cs10 == masks[i])
if (cs10 == masks[i]) {
votes10++;
}
if (cs11 == masks[i])
if (cs11 == masks[i]) {
votes11++;
}
}
if ((votes11 == 1) && (votes10 == 0)) {
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];
unsigned channel, value;
if (!dsm_decode_channel(raw, dsm_channel_shift, &channel, &value))
if (!dsm_decode_channel(raw, dsm_channel_shift, &channel, &value)) {
continue;
}
/* ignore channels out of range */
if (channel >= max_values)
if (channel >= max_values) {
continue;
}
/* update the decoded channel count */
if (channel >= *num_values)
if (channel >= *num_values) {
*num_values = channel + 1;
}
/* convert 0-1024 / 0-2048 values to 1000-2000 ppm encoding. */
if (dsm_channel_shift == 10)
if (dsm_channel_shift == 10) {
value *= 2;
}
/*
* 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
* data index that is stable).
*/
if (*num_values == 13)
if (*num_values == 13) {
*num_values = 12;
}
#if 0
if (dsm_channel_shift == 11) {

View File

@ -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 */
*sbus_failsafe = 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
*
* Attention! This flag indicates a skipped frame only, not a total link loss! Handling this

View File

@ -22,7 +22,8 @@
class AP_RCProtocol_SBUS_NI : public AP_RCProtocol_SBUS {
public:
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);
saved_width = width_s1;
}

View File

@ -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 */
}
else {
} else {
/* frame not completely received --> frame data buffering still ongoing */
decode_state_next = STATE_COLLECT;
}