1
0
Fork 0
mirror of https://github.com/betaflight/betaflight.git synced 2025-07-26 01:35:41 +03:00

Removed trailing whitespace.

This commit is contained in:
mikeller 2020-10-14 22:00:05 +13:00
parent 5bf4f71a6d
commit ab5c7a75be
5 changed files with 26 additions and 26 deletions

View file

@ -322,7 +322,7 @@ void tasksInit(void)
} else if (rxRuntimeState.serialrxProvider == SERIALRX_CRSF) { } else if (rxRuntimeState.serialrxProvider == SERIALRX_CRSF) {
// Reschedule telemetry to 500hz, 2ms for CRSF // Reschedule telemetry to 500hz, 2ms for CRSF
rescheduleTask(TASK_TELEMETRY, TASK_PERIOD_HZ(500)); rescheduleTask(TASK_TELEMETRY, TASK_PERIOD_HZ(500));
} }
} }
#endif #endif

View file

@ -56,8 +56,8 @@
// define the time window after the end of the last received packet where telemetry packets may be sent // define the time window after the end of the last received packet where telemetry packets may be sent
// NOTE: This allows the Rx to double-up on Rx packets to transmit data other than servo data, but // NOTE: This allows the Rx to double-up on Rx packets to transmit data other than servo data, but
// only if sent < 1ms after the servo data packet. // only if sent < 1ms after the servo data packet.
#define GHST_RX_TO_TELEMETRY_MIN_US 1000 #define GHST_RX_TO_TELEMETRY_MIN_US 1000
#define GHST_RX_TO_TELEMETRY_MAX_US 2000 #define GHST_RX_TO_TELEMETRY_MAX_US 2000
#define GHST_PAYLOAD_OFFSET offsetof(ghstFrameDef_t, type) #define GHST_PAYLOAD_OFFSET offsetof(ghstFrameDef_t, type)
@ -82,20 +82,20 @@ static timeUs_t lastRcFrameTimeUs = 0;
/* GHST Protocol /* GHST Protocol
* Ghost uses 420k baud single-wire, half duplex connection, connected to a FC UART 'Tx' pin * Ghost uses 420k baud single-wire, half duplex connection, connected to a FC UART 'Tx' pin
* Each control packet is interleaved with one or more corresponding downlink packets * Each control packet is interleaved with one or more corresponding downlink packets
* *
* Uplink packet format (Control packets) * Uplink packet format (Control packets)
* <Addr><Len><Type><Payload><CRC> * <Addr><Len><Type><Payload><CRC>
* *
* Addr: u8 Destination address * Addr: u8 Destination address
* Len u8 Length includes the packet ID, but not the CRC * Len u8 Length includes the packet ID, but not the CRC
* CRC u8 * CRC u8
* *
* Ghost packets are designed to be as short as possible, for minimum latency. * Ghost packets are designed to be as short as possible, for minimum latency.
* *
* Note that the GHST protocol does not handle, itself, failsafe conditions. Packets are passed from * Note that the GHST protocol does not handle, itself, failsafe conditions. Packets are passed from
* the Ghost receiver to Betaflight as and when they arrive. Betaflight itself is responsible for * the Ghost receiver to Betaflight as and when they arrive. Betaflight itself is responsible for
* determining when a failsafe is necessary based on dropped packets. * determining when a failsafe is necessary based on dropped packets.
* *
*/ */
#define GHST_FRAME_LENGTH_ADDRESS 1 #define GHST_FRAME_LENGTH_ADDRESS 1
@ -162,7 +162,7 @@ STATIC_UNIT_TESTED void ghstDataReceive(uint16_t c, void *data)
ghstFrameAvailable = true; ghstFrameAvailable = true;
// remember what time the incoming (Rx) packet ended, so that we can ensure a quite bus before sending telemetry // remember what time the incoming (Rx) packet ended, so that we can ensure a quite bus before sending telemetry
ghstRxFrameEndAtUs = microsISR(); ghstRxFrameEndAtUs = microsISR();
} }
} }
} }
@ -179,7 +179,7 @@ STATIC_UNIT_TESTED uint8_t ghstFrameStatus(rxRuntimeState_t *rxRuntimeState)
ghstValidatedFrameAvailable = true; ghstValidatedFrameAvailable = true;
return RX_FRAME_COMPLETE | RX_FRAME_PROCESSING_REQUIRED; // request callback through ghstProcessFrame to do the decoding work return RX_FRAME_COMPLETE | RX_FRAME_PROCESSING_REQUIRED; // request callback through ghstProcessFrame to do the decoding work
} }
return RX_FRAME_DROPPED; // frame was invalid return RX_FRAME_DROPPED; // frame was invalid
} }
@ -194,7 +194,7 @@ STATIC_UNIT_TESTED uint8_t ghstFrameStatus(rxRuntimeState_t *rxRuntimeState)
static bool ghstProcessFrame(const rxRuntimeState_t *rxRuntimeState) static bool ghstProcessFrame(const rxRuntimeState_t *rxRuntimeState)
{ {
// Assume that the only way we get here is if ghstFrameStatus returned RX_FRAME_PROCESSING_REQUIRED, which indicates that the CRC // Assume that the only way we get here is if ghstFrameStatus returned RX_FRAME_PROCESSING_REQUIRED, which indicates that the CRC
// is correct, and the message was actually for us. // is correct, and the message was actually for us.
UNUSED(rxRuntimeState); UNUSED(rxRuntimeState);
@ -225,7 +225,7 @@ static bool ghstProcessFrame(const rxRuntimeState_t *rxRuntimeState)
case GHST_UL_RC_CHANS_HS4_5TO8: startIdx = 4; break; case GHST_UL_RC_CHANS_HS4_5TO8: startIdx = 4; break;
case GHST_UL_RC_CHANS_HS4_9TO12: startIdx = 8; break; case GHST_UL_RC_CHANS_HS4_9TO12: startIdx = 8; break;
case GHST_UL_RC_CHANS_HS4_13TO16: startIdx = 12; break; case GHST_UL_RC_CHANS_HS4_13TO16: startIdx = 12; break;
} }
ghstChannelData[startIdx++] = rcChannels->cha << 3; ghstChannelData[startIdx++] = rcChannels->cha << 3;
ghstChannelData[startIdx++] = rcChannels->chb << 3; ghstChannelData[startIdx++] = rcChannels->chb << 3;
@ -245,15 +245,15 @@ static bool ghstProcessFrame(const rxRuntimeState_t *rxRuntimeState)
STATIC_UNIT_TESTED uint16_t ghstReadRawRC(const rxRuntimeState_t *rxRuntimeState, uint8_t chan) STATIC_UNIT_TESTED uint16_t ghstReadRawRC(const rxRuntimeState_t *rxRuntimeState, uint8_t chan)
{ {
UNUSED(rxRuntimeState); UNUSED(rxRuntimeState);
// derived from original SBus scaling, with slight correction for offset (now symmetrical // derived from original SBus scaling, with slight correction for offset (now symmetrical
// around OpenTx 0 value) // around OpenTx 0 value)
// scaling is: // scaling is:
// OpenTx RC PWM // OpenTx RC PWM
// min -1024 172 988us // min -1024 172 988us
// ctr 0 992 1500us // ctr 0 992 1500us
// max 1024 1811 2012us // max 1024 1811 2012us
// //
return (5 * (ghstChannelData[chan]+1) / 8) + 880; return (5 * (ghstChannelData[chan]+1) / 8) + 880;
@ -279,7 +279,7 @@ bool ghstRxInit(const rxConfig_t *rxConfig, rxRuntimeState_t *rxRuntimeState)
} }
rxRuntimeState->channelCount = GHST_MAX_NUM_CHANNELS; rxRuntimeState->channelCount = GHST_MAX_NUM_CHANNELS;
rxRuntimeState->rxRefreshRate = GHST_TIME_BETWEEN_FRAMES_US; rxRuntimeState->rxRefreshRate = GHST_TIME_BETWEEN_FRAMES_US;
rxRuntimeState->rcReadRawFn = ghstReadRawRC; rxRuntimeState->rcReadRawFn = ghstReadRawRC;
rxRuntimeState->rcFrameStatusFn = ghstFrameStatus; rxRuntimeState->rcFrameStatusFn = ghstFrameStatus;

View file

@ -22,7 +22,7 @@
#include "rx/ghst_protocol.h" #include "rx/ghst_protocol.h"
#define GHST_MAX_NUM_CHANNELS 16 #define GHST_MAX_NUM_CHANNELS 16
void ghstRxWriteTelemetryData(const void *data, int len); void ghstRxWriteTelemetryData(const void *data, int len);
void ghstRxSendTelemetryData(void); void ghstRxSendTelemetryData(void);

View file

@ -28,7 +28,7 @@
#define GHST_TX_BAUDRATE_FAST 400000 #define GHST_TX_BAUDRATE_FAST 400000
#define GHST_TX_BAUDRATE_SLOW 115200 #define GHST_TX_BAUDRATE_SLOW 115200
#define GHST_BYTE_TIME_FAST_US ((1000000/GHST_TX_BAUDRATE_FAST)*10) // 10 bit words (8 data, 1 start, 1 stop) #define GHST_BYTE_TIME_FAST_US ((1000000/GHST_TX_BAUDRATE_FAST)*10) // 10 bit words (8 data, 1 start, 1 stop)
#define GHST_BYTE_TIME_SLOW_US ((1000000/GHST_TX_BAUDRATE_SLOW)*10) #define GHST_BYTE_TIME_SLOW_US ((1000000/GHST_TX_BAUDRATE_SLOW)*10)
#define GHST_UART_WORDLENGTH UART_WORDLENGTH_8B #define GHST_UART_WORDLENGTH UART_WORDLENGTH_8B
typedef enum { typedef enum {
@ -41,7 +41,7 @@ typedef enum {
GHST_ADDR_QUANTUM_TEE2 = 0x85, GHST_ADDR_QUANTUM_TEE2 = 0x85,
GHST_ADDR_QUANTUM_GW1 = 0x86, GHST_ADDR_QUANTUM_GW1 = 0x86,
GHST_ADDR_5G_CLK = 0x87, // phase 3 GHST_ADDR_5G_CLK = 0x87, // phase 3
GHST_ADDR_RX = 0x89 GHST_ADDR_RX = 0x89
} ghstAddr_e; } ghstAddr_e;
typedef enum { typedef enum {
@ -54,7 +54,7 @@ typedef enum {
typedef enum { typedef enum {
GHST_DL_OPENTX_SYNC = 0x20, GHST_DL_OPENTX_SYNC = 0x20,
GHST_DL_LINK_STAT = 0x21, GHST_DL_LINK_STAT = 0x21,
GHST_DL_VTX_STAT = 0x22, GHST_DL_VTX_STAT = 0x22,
GHST_DL_PACK_STAT = 0x23, // Battery (Pack) Status GHST_DL_PACK_STAT = 0x23, // Battery (Pack) Status
} ghstDl_e; } ghstDl_e;
@ -64,9 +64,9 @@ typedef enum {
#define GHST_FRAME_SIZE 14 // including addr, type, len, crc, and payload #define GHST_FRAME_SIZE 14 // including addr, type, len, crc, and payload
#define GHST_PAYLOAD_SIZE_MAX 14 #define GHST_PAYLOAD_SIZE_MAX 14
#define GHST_FRAME_SIZE_MAX 24 #define GHST_FRAME_SIZE_MAX 24
typedef struct ghstFrameDef_s { typedef struct ghstFrameDef_s {
uint8_t addr; uint8_t addr;
@ -88,7 +88,7 @@ typedef struct ghstPayloadPulses_s {
unsigned int ch3: 12; unsigned int ch3: 12;
unsigned int ch4: 12; unsigned int ch4: 12;
unsigned int cha: 8; unsigned int cha: 8;
unsigned int chb: 8; unsigned int chb: 8;
unsigned int chc: 8; unsigned int chc: 8;
unsigned int chd: 8; unsigned int chd: 8;

View file

@ -141,7 +141,7 @@ static void processGhst(void)
void initGhstTelemetry(void) void initGhstTelemetry(void)
{ {
// If the GHST Rx driver is active, since tx and rx share the same pin, assume telemetry is enabled. // If the GHST Rx driver is active, since tx and rx share the same pin, assume telemetry is enabled.
ghstTelemetryEnabled = ghstRxIsActive(); ghstTelemetryEnabled = ghstRxIsActive();
if (!ghstTelemetryEnabled) { if (!ghstTelemetryEnabled) {