Merge pull request #9485 from jflyper/bfdev-white-space-tidy

White space tidy
This commit is contained in:
Michael Keller 2020-02-18 00:24:24 +13:00 committed by GitHub
commit 6bb7dbbba9
No known key found for this signature in database
GPG Key ID: 4AEE18F83AFDEB23
58 changed files with 310 additions and 310 deletions

View File

@ -4068,7 +4068,7 @@ static void cliDumpPidProfile(uint8_t pidProfileIndex, dumpFlags_t dumpMask)
cliPrintLinefeed();
cliProfile("");
char profileStr[10];
tfp_sprintf(profileStr, "profile %d", pidProfileIndex);
dumpAllValues(PROFILE_VALUE, dumpMask, profileStr);
@ -6391,7 +6391,7 @@ static void cliHelp(char *cmdline)
) {
printEntry = true;
}
}
}
if (printEntry) {
anyMatches = true;

View File

@ -196,7 +196,7 @@ static const char * const lookupTableGPSSBASMode[] = {
};
static const char * const lookupTableGPSUBLOXMode[] = {
"AIRBORNE", "PEDESTRIAN", "DYNAMIC"
"AIRBORNE", "PEDESTRIAN", "DYNAMIC"
};
#endif

View File

@ -254,7 +254,7 @@ static void cmsPageSelect(displayPort_t *instance, int8_t newpage)
currentCtx.page = (newpage + pageCount) % pageCount;
pageTop = &currentCtx.menu->entries[currentCtx.page * maxMenuItems];
cmsUpdateMaxRow(instance);
const OSD_Entry *p;
int i;
for (p = pageTop, i = 0; (p <= pageTop + pageMaxRow); p++, i++) {

View File

@ -183,7 +183,7 @@ const OSD_Entry cmsx_menuGpsRescueEntries[] =
{ "THROTTLE MAX", OME_UINT16, NULL, &(OSD_UINT16_t){ &gpsRescueConfig_throttleMax, 1000, 2000, 1 }, REBOOT_REQUIRED },
{ "THROTTLE HOV", OME_UINT16, NULL, &(OSD_UINT16_t){ &gpsRescueConfig_throttleHover, 1000, 2000, 1 }, REBOOT_REQUIRED },
{ "ASCEND RATE", OME_UINT16, NULL, &(OSD_UINT16_t){ &gpsRescueConfig_ascendRate, 100, 2500, 1 }, REBOOT_REQUIRED },
{ "DESCEND RATE", OME_UINT16, NULL, &(OSD_UINT16_t){ &gpsRescueConfig_descendRate, 100, 500, 1 }, REBOOT_REQUIRED },
{ "DESCEND RATE", OME_UINT16, NULL, &(OSD_UINT16_t){ &gpsRescueConfig_descendRate, 100, 500, 1 }, REBOOT_REQUIRED },
{ "ARM WITHOUT FIX", OME_Bool, NULL, &gpsRescueConfig_allowArmingWithoutFix, REBOOT_REQUIRED },
{ "MIN SATELITES", OME_UINT8, NULL, &(OSD_UINT8_t){ &gpsRescueConfig_minSats, 5, 50, 1 }, REBOOT_REQUIRED },
{ "GPS RESCUE PID", OME_Submenu, cmsMenuChange, &cms_menuGpsRescuePid, 0},

View File

@ -97,7 +97,7 @@ const void *cmsSelectVtx(displayPort_t *pDisplay, const void *ptr)
vtxDevType_e vtxType = vtxCommonGetDeviceType(device);
switch (vtxType) {
#if defined(USE_VTX_RTC6705)
case VTXDEV_RTC6705:
cmsMenuChange(pDisplay, &cmsx_menuVtxRTC6705);

View File

@ -394,7 +394,7 @@ static void validateAndFixConfig(void)
motorConfig()->dev.useDshotBitbang == DSHOT_BITBANG_ON) {
motorConfigMutable()->dev.useDshotBitbang = DSHOT_BITBANG_AUTO;
}
#endif
#endif
#ifdef USE_ADC
adcConfigMutable()->vbat.enabled = (batteryConfig()->voltageMeterSource == VOLTAGE_METER_ADC);

View File

@ -322,7 +322,7 @@ void adcInit(const adcConfig_t *config)
// Find an ADC device that can handle this input pin
for (dev = 0; dev < ADCDEV_COUNT; dev++) {
if (!adcDevice[dev].ADCx
if (!adcDevice[dev].ADCx
#ifndef USE_DMA_SPEC
|| !adcDevice[dev].dmaResource
#endif
@ -397,9 +397,9 @@ void adcInit(const adcConfig_t *config)
sConfig.Rank = adcRegularRank[rank++]; /* Rank of sampled channel number ADCx_CHANNEL */
sConfig.SamplingTime = ADC_SAMPLETIME_640CYCLES_5; /* Sampling time (number of clock cycles unit) */
sConfig.SingleDiff = ADC_SINGLE_ENDED; /* Single-ended input channel */
sConfig.OffsetNumber = ADC_OFFSET_NONE; /* No offset subtraction */
sConfig.OffsetNumber = ADC_OFFSET_NONE; /* No offset subtraction */
sConfig.Offset = 0; /* Parameter discarded because offset correction is disabled */
if (HAL_ADC_ConfigChannel(&adc->ADCHandle, &sConfig) != HAL_OK) {
handleError();
}
@ -437,7 +437,7 @@ void adcInit(const adcConfig_t *config)
HAL_DMA_Init(&adc->DmaHandle);
dmaInit(dmaIdentifier, OWNER_ADC, RESOURCE_INDEX(dev));
// Associate the DMA handle
__HAL_LINKDMA(&adc->ADCHandle, DMA_Handle, adc->DmaHandle);
@ -450,7 +450,7 @@ void adcInit(const adcConfig_t *config)
// NVIC configuration for DMA Input data interrupt
HAL_NVIC_SetPriority(DMA1_Stream1_IRQn, 1, 0);
HAL_NVIC_EnableIRQ(DMA1_Stream1_IRQn);
HAL_NVIC_EnableIRQ(DMA1_Stream1_IRQn);
#endif
}
@ -521,7 +521,7 @@ adcPrivateVref = __HAL_ADC_CALC_VREFANALOG_VOLTAGE(value, ADC_RESOLUTION_12B);
uint16_t adcInternalReadTempsensor(void)
{
uint16_t value = adcInternalRead(ADC_TEMPSENSOR);
uint16_t value = adcInternalRead(ADC_TEMPSENSOR);
adcPrivateTemp = __HAL_ADC_CALC_TEMPERATURE(adcPrivateVref, value, ADC_RESOLUTION_12B);
return value;
}

View File

@ -189,7 +189,7 @@ void adcInitDevice(adcDevice_t *adcdev, int channelCount)
hadc->Init.NbrOfConversion = channelCount;
hadc->Init.DiscontinuousConvMode = DISABLE;
hadc->Init.NbrOfDiscConversion = 1; // Don't care
hadc->Init.ExternalTrigConv = ADC_SOFTWARE_START;
hadc->Init.ExternalTrigConv = ADC_SOFTWARE_START;
hadc->Init.ExternalTrigConvEdge = ADC_EXTERNALTRIGCONVEDGE_NONE; // Don't care
hadc->Init.ConversionDataManagement = ADC_CONVERSIONDATA_DMA_CIRCULAR;
hadc->Init.Overrun = ADC_OVR_DATA_OVERWRITTEN;
@ -281,7 +281,7 @@ void adcInit(const adcConfig_t *config)
// Find an ADC device that can handle this input pin
for (dev = 0; dev < ADCDEV_COUNT; dev++) {
if (!adcDevice[dev].ADCx
if (!adcDevice[dev].ADCx
#ifndef USE_DMA_SPEC
|| !adcDevice[dev].dmaResource
#endif
@ -366,9 +366,9 @@ void adcInit(const adcConfig_t *config)
sConfig.Rank = adcRegularRankMap[rank++]; /* Rank of sampled channel number ADCx_CHANNEL */
sConfig.SamplingTime = ADC_SAMPLETIME_387CYCLES_5; /* Sampling time (number of clock cycles unit) */
sConfig.SingleDiff = ADC_SINGLE_ENDED; /* Single-ended input channel */
sConfig.OffsetNumber = ADC_OFFSET_NONE; /* No offset subtraction */
sConfig.OffsetNumber = ADC_OFFSET_NONE; /* No offset subtraction */
sConfig.Offset = 0; /* Parameter discarded because offset correction is disabled */
if (HAL_ADC_ConfigChannel(&adc->ADCHandle, &sConfig) != HAL_OK) {
Error_Handler();
}
@ -406,7 +406,7 @@ void adcInit(const adcConfig_t *config)
HAL_DMA_Init(&adc->DmaHandle);
dmaInit(dmaIdentifier, OWNER_ADC, RESOURCE_INDEX(dev));
// Associate the DMA handle
__HAL_LINKDMA(&adc->ADCHandle, DMA_Handle, adc->DmaHandle);
@ -419,7 +419,7 @@ void adcInit(const adcConfig_t *config)
// NVIC configuration for DMA Input data interrupt
HAL_NVIC_SetPriority(DMA1_Stream1_IRQn, 1, 0);
HAL_NVIC_EnableIRQ(DMA1_Stream1_IRQn);
HAL_NVIC_EnableIRQ(DMA1_Stream1_IRQn);
#endif
}
@ -486,7 +486,7 @@ uint16_t adcInternalReadVrefint(void)
uint16_t adcInternalReadTempsensor(void)
{
uint16_t value = adcInternalRead(ADC_TEMPSENSOR);
uint16_t value = adcInternalRead(ADC_TEMPSENSOR);
return value;
}
#endif // USE_ADC_INTERNAL

View File

@ -83,7 +83,7 @@ typedef enum {
// De facto standard mode
// See https://en.wikipedia.org/wiki/Serial_Peripheral_Interface
//
//
// Mode CPOL CPHA
// 0 0 0
// 1 0 1

View File

@ -104,7 +104,7 @@ typedef enum {
.userParam = 0, \
.owner.owner = 0, \
.owner.resourceIndex = 0 \
}
}
#define DEFINE_DMA_IRQ_HANDLER(d, s, i) void DMA ## d ## _Stream ## s ## _IRQHandler(void) {\
const uint8_t index = DMA_IDENTIFIER_TO_INDEX(i); \
@ -173,8 +173,8 @@ typedef enum {
DMA2_CH3_HANDLER,
DMA2_CH4_HANDLER,
DMA2_CH5_HANDLER,
DMA_LAST_HANDLER = DMA2_CH5_HANDLER
#else
DMA_LAST_HANDLER = DMA2_CH5_HANDLER
#else
DMA_LAST_HANDLER = DMA1_CH7_HANDLER
#endif
} dmaIdentifier_e;

View File

@ -106,7 +106,7 @@ uint16_t dshotConvertToExternal(float motorValue)
}
FAST_CODE uint16_t prepareDshotPacket(dshotProtocolControl_t *pcb)
{
{
uint16_t packet;
ATOMIC_BLOCK(NVIC_PRIO_DSHOT_DMA) {
@ -115,14 +115,14 @@ FAST_CODE uint16_t prepareDshotPacket(dshotProtocolControl_t *pcb)
}
// compute checksum
unsigned csum = 0;
unsigned csum = 0;
unsigned csum_data = packet;
for (int i = 0; i < 3; i++) {
csum ^= csum_data; // xor data by nibbles
csum_data >>= 4;
}
// append checksum
#ifdef USE_DSHOT_TELEMETRY
#ifdef USE_DSHOT_TELEMETRY
if (useDshotTelemetry) {
csum = ~csum;
}

View File

@ -52,16 +52,16 @@ static uint32_t decode_bb_value(uint32_t value, uint16_t buffer[], uint32_t coun
static const uint32_t decode[32] = {
iv, iv, iv, iv, iv, iv, iv, iv, iv, 9, 10, 11, iv, 13, 14, 15,
iv, iv, 2, 3, iv, 5, 6, 7, iv, 0, 8, 1, iv, 4, 12, iv };
uint32_t decodedValue = decode[value & 0x1f];
decodedValue |= decode[(value >> 5) & 0x1f] << 4;
decodedValue |= decode[(value >> 10) & 0x1f] << 8;
decodedValue |= decode[(value >> 15) & 0x1f] << 12;
uint32_t csum = decodedValue;
csum = csum ^ (csum >> 8); // xor bytes
csum = csum ^ (csum >> 4); // xor nibbles
if ((csum & 0xf) != 0xf || decodedValue > 0xffff) {
#ifdef DEBUG_BBDECODE
memcpy(dshotTelemetryState.inputBuffer, sequence, sizeof(sequence));
@ -72,7 +72,7 @@ static uint32_t decode_bb_value(uint32_t value, uint16_t buffer[], uint32_t coun
value = BB_INVALID;
} else {
value = decodedValue >> 4;
if (value == 0x0fff) {
return 0;
}
@ -189,7 +189,7 @@ uint32_t decode_bb_bitband( uint16_t buffer[], uint32_t count, uint32_t bit)
if (nlen < 0) {
value = BB_INVALID;
}
#ifdef DEBUG_BBDECODE
sequence[sequenceIndex] = sequence[sequenceIndex] + (nlen) * 3;
sequenceIndex++;

View File

@ -110,7 +110,7 @@ typedef struct bbPort_s {
uint8_t direction;
#ifdef USE_DMA_REGISTER_CACHE
#ifdef USE_DMA_REGISTER_CACHE
// DMA resource register cache
dmaRegCache_t dmaRegOutput;
dmaRegCache_t dmaRegInput;

View File

@ -186,7 +186,7 @@ void bbSwitchToOutput(bbPort_t * bbPort)
void bbSwitchToInput(bbPort_t *bbPort)
{
// Set GPIO to input
ATOMIC_BLOCK(NVIC_PRIO_TIMER) {
MODIFY_REG(bbPort->gpio->MODER, bbPort->gpioModeMask, bbPort->gpioModeInput);
}

View File

@ -182,7 +182,7 @@ void bbSwitchToInput(bbPort_t *bbPort)
dbgPinHi(1);
// Set GPIO to input
ATOMIC_BLOCK(NVIC_PRIO_TIMER) {
MODIFY_REG(bbPort->gpio->MODER, bbPort->gpioModeMask, bbPort->gpioModeInput);
}

View File

@ -77,40 +77,40 @@ void dshotSetPidLoopTime(uint32_t pidLoopTime)
}
static FAST_CODE bool dshotCommandQueueFull()
{
{
return (commandQueueHead + 1) % (DSHOT_MAX_COMMANDS + 1) == commandQueueTail;
}
}
FAST_CODE bool dshotCommandQueueEmpty(void)
{
{
return commandQueueHead == commandQueueTail;
}
}
static FAST_CODE bool isLastDshotCommand(void)
{
{
return ((commandQueueTail + 1) % (DSHOT_MAX_COMMANDS + 1) == commandQueueHead);
}
}
FAST_CODE bool dshotCommandIsProcessing(void)
{
{
if (dshotCommandQueueEmpty()) {
return false;
}
dshotCommandControl_t* command = &commandQueue[commandQueueTail];
const bool commandIsProcessing = command->state == DSHOT_COMMAND_STATE_STARTDELAY
|| command->state == DSHOT_COMMAND_STATE_ACTIVE
|| command->state == DSHOT_COMMAND_STATE_ACTIVE
|| (command->state == DSHOT_COMMAND_STATE_POSTDELAY && !isLastDshotCommand());
return commandIsProcessing;
}
static FAST_CODE bool dshotCommandQueueUpdate(void)
{
{
if (!dshotCommandQueueEmpty()) {
commandQueueTail = (commandQueueTail + 1) % (DSHOT_MAX_COMMANDS + 1);
if (!dshotCommandQueueEmpty()) {
// There is another command in the queue so update it so it's ready to output in
// sequence. It can go directly to the DSHOT_COMMAND_STATE_ACTIVE state and bypass
// the DSHOT_COMMAND_STATE_IDLEWAIT and DSHOT_COMMAND_STATE_STARTDELAY states.
// There is another command in the queue so update it so it's ready to output in
// sequence. It can go directly to the DSHOT_COMMAND_STATE_ACTIVE state and bypass
// the DSHOT_COMMAND_STATE_IDLEWAIT and DSHOT_COMMAND_STATE_STARTDELAY states.
dshotCommandControl_t* nextCommand = &commandQueue[commandQueueTail];
nextCommand->state = DSHOT_COMMAND_STATE_ACTIVE;
nextCommand->nextCommandCycleDelay = 0;

View File

@ -139,7 +139,7 @@ static bool flashSpiInit(const flashConfig_t *flashConfig)
delay(50); // short delay required after initialisation of SPI device instance.
/*
/*
* Some newer chips require one dummy byte to be read; we can read
* 4 bytes for these chips while retaining backward compatibility.
*/

View File

@ -21,7 +21,7 @@
/*
* Winbond W25M series stacked die flash driver.
* Handles homogeneous stack of identical dies by calling die drivers.
*
*
* Author: jflyper
*/

View File

@ -523,9 +523,9 @@ static uint32_t currentPage = UINT32_MAX;
void w25n01g_pageProgramFinish(flashDevice_t *fdevice)
{
if (bufferDirty && W25N01G_LINEAR_TO_COLUMN(programLoadAddress) == 0) {
currentPage = W25N01G_LINEAR_TO_PAGE(programStartAddress); // reset page to the page being written
w25n01g_programExecute(fdevice, W25N01G_LINEAR_TO_PAGE(programStartAddress));
bufferDirty = false;

View File

@ -82,17 +82,17 @@ void pwmChannelDMAStart(TIM_HandleTypeDef *htim, uint32_t Channel, uint32_t *pDa
HAL_DMA_Start_IT(htim->hdma[TIM_DMA_ID_CC1], (uint32_t)pData, (uint32_t)&htim->Instance->CCR1, Length);
__HAL_TIM_ENABLE_DMA(htim, TIM_DMA_CC1);
break;
case TIM_CHANNEL_2:
HAL_DMA_Start_IT(htim->hdma[TIM_DMA_ID_CC2], (uint32_t)pData, (uint32_t)&htim->Instance->CCR2, Length);
__HAL_TIM_ENABLE_DMA(htim, TIM_DMA_CC2);
break;
case TIM_CHANNEL_3:
HAL_DMA_Start_IT(htim->hdma[TIM_DMA_ID_CC3], (uint32_t)pData, (uint32_t)&htim->Instance->CCR3,Length);
__HAL_TIM_ENABLE_DMA(htim, TIM_DMA_CC3);
break;
case TIM_CHANNEL_4:
HAL_DMA_Start_IT(htim->hdma[TIM_DMA_ID_CC4], (uint32_t)pData, (uint32_t)&htim->Instance->CCR4, Length);
__HAL_TIM_ENABLE_DMA(htim, TIM_DMA_CC4);
@ -132,11 +132,11 @@ void pwmChannelDMAStop(TIM_HandleTypeDef *htim, uint32_t Channel)
void pwmBurstDMAStart(TIM_HandleTypeDef *htim, uint32_t BurstBaseAddress, uint32_t BurstRequestSrc, uint32_t BurstUnit, uint32_t* BurstBuffer, uint32_t BurstLength)
{
// Setup DMA stream
HAL_DMA_Start_IT(htim->hdma[TIM_DMA_ID_UPDATE], (uint32_t)BurstBuffer, (uint32_t)&htim->Instance->DMAR, BurstLength);
HAL_DMA_Start_IT(htim->hdma[TIM_DMA_ID_UPDATE], (uint32_t)BurstBuffer, (uint32_t)&htim->Instance->DMAR, BurstLength);
// Configure burst mode DMA */
htim->Instance->DCR = BurstBaseAddress | BurstUnit;
htim->Instance->DCR = BurstBaseAddress | BurstUnit;
// Enable burst mode DMA
__HAL_TIM_ENABLE_DMA(htim, BurstRequestSrc);
}
@ -200,7 +200,7 @@ void pwmCompleteDshotMotorUpdate(void)
// Transfer CCR1 through CCR4 for each burst
pwmBurstDMAStart(&burstDmaTimer->timHandle,
TIM_DMABASE_CCR1, TIM_DMA_UPDATE, TIM_DMABURSTLENGTH_4TRANSFERS,
TIM_DMABASE_CCR1, TIM_DMA_UPDATE, TIM_DMABURSTLENGTH_4TRANSFERS,
(uint32_t*)burstDmaTimer->dmaBurstBuffer, burstDmaTimer->dmaBurstLength);
}
} else

View File

@ -226,7 +226,7 @@ FAST_CODE_NOINLINE bool pwmStartDshotMotorUpdate(void)
if (edges > MIN_GCR_EDGES) {
dshotTelemetryState.readCount++;
value = decodeTelemetryPacket(dmaMotors[i].dmaBuffer, edges);
#ifdef USE_DSHOT_TELEMETRY_STATS
bool validTelemetryPacket = false;
#endif

View File

@ -947,7 +947,7 @@ bool escEnablePassthrough(serialPort_t *escPassthroughPort, const motorDevConfig
LED0_OFF;
LED1_OFF;
//StopPwmAllMotors();
// XXX Review effect of motor refactor
// XXX Review effect of motor refactor
//pwmDisableMotors();
motorDisable();
passPort = escPassthroughPort;

View File

@ -100,16 +100,16 @@ UART_BUFFERS(8);
#undef UART_BUFFERS
serialPort_t *uartOpen(UARTDevice_e device, serialReceiveCallbackPtr rxCallback, void *rxCallbackData, uint32_t baudRate, portMode_e mode, portOptions_e options)
{
{
uartPort_t *s = serialUART(device, baudRate, mode, options);
if (!s)
return (serialPort_t *)s;
#ifdef USE_DMA
s->txDMAEmpty = true;
#endif
// common serial initialisation code should move to serialPort::init()
s->port.rxBufferHead = s->port.rxBufferTail = 0;
s->port.txBufferHead = s->port.txBufferTail = 0;
@ -119,9 +119,9 @@ serialPort_t *uartOpen(UARTDevice_e device, serialReceiveCallbackPtr rxCallback,
s->port.mode = mode;
s->port.baudRate = baudRate;
s->port.options = options;
uartReconfigure(s);
return (serialPort_t *)s;
}

View File

@ -115,7 +115,7 @@ void uartReconfigure(uartPort_t *uartPort)
uartPort->rxDMAHandle.Instance = (DMA_ARCH_TYPE *)uartPort->rxDMAResource;
#if !(defined(STM32H7) || defined(STM32G4))
uartPort->rxDMAHandle.Init.Channel = uartPort->rxDMAChannel;
#else
#else
uartPort->txDMAHandle.Init.Request = uartPort->rxDMAChannel;
#endif
uartPort->rxDMAHandle.Init.Direction = DMA_PERIPH_TO_MEMORY;
@ -165,7 +165,7 @@ void uartReconfigure(uartPort_t *uartPort)
uartPort->txDMAHandle.Instance = (DMA_ARCH_TYPE *)uartPort->txDMAResource;
#if !(defined(STM32H7) || defined(STM32G4))
uartPort->txDMAHandle.Init.Channel = uartPort->txDMAChannel;
#else
#else
uartPort->txDMAHandle.Init.Request = uartPort->txDMAChannel;
#endif
uartPort->txDMAHandle.Init.Direction = DMA_MEMORY_TO_PERIPH;

View File

@ -52,7 +52,7 @@ const uartHardware_t uartHardware[UARTDEV_COUNT] = {
#ifdef USE_UART1_TX_DMA
.txDMAResource = (dmaResource_t *)DMA2_Stream7,
#endif
.rxPins = { { DEFIO_TAG_E(PA10) }, { DEFIO_TAG_E(PB7) },
.rxPins = { { DEFIO_TAG_E(PA10) }, { DEFIO_TAG_E(PB7) },
#if defined (STM32F411xE)
{ DEFIO_TAG_E(PB3) },
#endif

View File

@ -179,10 +179,10 @@ const uartHardware_t uartHardware[UARTDEV_COUNT] = {
.txDMAResource = (dmaResource_t *)UART4_TX_DMA_CHANNEL,
#endif
.rxPins = {
{ DEFIO_TAG_E(PC11), GPIO_AF5_UART4 },
{ DEFIO_TAG_E(PC11), GPIO_AF5_UART4 },
},
.txPins = {
{ DEFIO_TAG_E(PC10), GPIO_AF5_UART4 },
{ DEFIO_TAG_E(PC10), GPIO_AF5_UART4 },
},
.rcc_apb1 = RCC_APB11(UART4),
.rxIrq = UART4_IRQn,

View File

@ -194,14 +194,14 @@ const uartHardware_t uartHardware[UARTDEV_COUNT] = {
{ DEFIO_TAG_E(PA1), GPIO_AF8_UART4 },
{ DEFIO_TAG_E(PA11), GPIO_AF6_UART4 },
{ DEFIO_TAG_E(PB8), GPIO_AF8_UART4 },
{ DEFIO_TAG_E(PC11), GPIO_AF8_UART4 },
{ DEFIO_TAG_E(PC11), GPIO_AF8_UART4 },
{ DEFIO_TAG_E(PD0), GPIO_AF8_UART4 }
},
.txPins = {
{ DEFIO_TAG_E(PA0), GPIO_AF8_UART4 },
{ DEFIO_TAG_E(PA12), GPIO_AF6_UART4 },
{ DEFIO_TAG_E(PB9), GPIO_AF8_UART4 },
{ DEFIO_TAG_E(PC10), GPIO_AF8_UART4 },
{ DEFIO_TAG_E(PC10), GPIO_AF8_UART4 },
{ DEFIO_TAG_E(PD1), GPIO_AF8_UART4 }
},
.rcc_apb1 = RCC_APB1L(UART4),

View File

@ -700,7 +700,7 @@ int8_t calculateThrottlePercent(void)
if (featureIsEnabled(FEATURE_3D)
&& !IS_RC_MODE_ACTIVE(BOX3D)
&& !flight3DConfig()->switched_mode3d) {
if (channelData > (rxConfig()->midrc + flight3DConfig()->deadband3d_throttle)) {
ret = ((channelData - rxConfig()->midrc - flight3DConfig()->deadband3d_throttle) * 100) / (PWM_RANGE_MAX - rxConfig()->midrc - flight3DConfig()->deadband3d_throttle);
} else if (channelData < (rxConfig()->midrc - flight3DConfig()->deadband3d_throttle)) {
@ -761,7 +761,7 @@ bool processRx(timeUs_t currentTimeUs)
const throttleStatus_e throttleStatus = calculateThrottleStatus();
const uint8_t throttlePercent = calculateThrottlePercentAbs();
const bool launchControlActive = isLaunchControlActive();
if (airmodeIsEnabled() && ARMING_FLAG(ARMED) && !launchControlActive) {

View File

@ -98,7 +98,7 @@ enum {
static FAST_RAM_ZERO_INIT rcSmoothingFilter_t rcSmoothingData;
#endif // USE_RC_SMOOTHING_FILTER
uint32_t getRcFrameNumber()
uint32_t getRcFrameNumber()
{
return rcFrameNumber;
}
@ -206,7 +206,7 @@ float getRcCurveSlope(int axis, float deflection)
static void calculateSetpointRate(int axis)
{
float angleRate;
#ifdef USE_GPS_RESCUE
if ((axis == FD_YAW) && FLIGHT_MODE(GPS_RESCUE_MODE)) {
// If GPS Rescue is active then override the setpointRate used in the
@ -370,7 +370,7 @@ FAST_CODE_NOINLINE void rcSmoothingSetFilterCutoffs(rcSmoothingFilter_t *smoothi
{
const float dT = targetPidLooptime * 1e-6f;
uint16_t oldCutoff = smoothingData->inputCutoffFrequency;
if (smoothingData->inputCutoffSetting == 0) {
smoothingData->inputCutoffFrequency = calcRcSmoothingCutoff(smoothingData->averageFrameTimeUs, (smoothingData->inputFilterType == RC_SMOOTHING_INPUT_PT1), smoothingData->autoSmoothnessFactor);
}
@ -380,7 +380,7 @@ FAST_CODE_NOINLINE void rcSmoothingSetFilterCutoffs(rcSmoothingFilter_t *smoothi
for (int i = 0; i < PRIMARY_CHANNEL_COUNT; i++) {
if ((1 << i) & interpolationChannels) { // only update channels specified by rc_interp_ch
switch (smoothingData->inputFilterType) {
case RC_SMOOTHING_INPUT_PT1:
if (!smoothingData->filterInitialized) {
pt1FilterInit((pt1Filter_t*) &smoothingData->filter[i], pt1FilterGain(smoothingData->inputCutoffFrequency, dT));
@ -388,7 +388,7 @@ FAST_CODE_NOINLINE void rcSmoothingSetFilterCutoffs(rcSmoothingFilter_t *smoothi
pt1FilterUpdateCutoff((pt1Filter_t*) &smoothingData->filter[i], pt1FilterGain(smoothingData->inputCutoffFrequency, dT));
}
break;
case RC_SMOOTHING_INPUT_BIQUAD:
default:
if (!smoothingData->filterInitialized) {
@ -447,7 +447,7 @@ static FAST_CODE bool rcSmoothingAccumulateSample(rcSmoothingFilter_t *smoothing
}
// Determine if we need to caclulate filter cutoffs. If not then we can avoid
// examining the rx frame times completely
// examining the rx frame times completely
FAST_CODE_NOINLINE bool rcSmoothingAutoCalculate(void)
{
// if the input cutoff is 0 (auto) then we need to calculate cutoffs
@ -496,9 +496,9 @@ static FAST_CODE uint8_t processRcSmoothingFilter(void)
rcSmoothingData.derivativeCutoffSetting = rxConfig()->rc_smoothing_derivative_cutoff;
rcSmoothingResetAccumulation(&rcSmoothingData);
rcSmoothingData.inputCutoffFrequency = rcSmoothingData.inputCutoffSetting;
if (rcSmoothingData.derivativeFilterType != RC_SMOOTHING_DERIVATIVE_OFF) {
if ((currentPidProfile->ff_interpolate_sp != FF_INTERPOLATE_OFF) && (rcSmoothingData.derivativeCutoffSetting == 0)) {
// calculate the fixed derivative cutoff used for interpolated feedforward
@ -513,7 +513,7 @@ static FAST_CODE uint8_t processRcSmoothingFilter(void)
rcSmoothingData.derivativeCutoffFrequency = rcSmoothingData.derivativeCutoffSetting;
}
}
calculateCutoffs = rcSmoothingAutoCalculate();
// if we don't need to calculate cutoffs dynamically then the filters can be initialized now

View File

@ -80,7 +80,7 @@ bool isRangeActive(uint8_t auxChannelIndex, const channelRange_t *range) {
/*
* updateMasksForMac:
*
*
* The following are the possible logic states at each MAC update:
* AND NEW
* --- ---
@ -93,7 +93,7 @@ void updateMasksForMac(const modeActivationCondition_t *mac, boxBitmask_t *andMa
{
if (bitArrayGet(andMask, mac->modeId) || !bitArrayGet(newMask, mac->modeId)) {
bool bAnd = mac->modeLogic == MODELOGIC_AND;
if (!bAnd) { // OR mac
if (bActive) {
bitArrayClr(andMask, mac->modeId);

View File

@ -384,12 +384,12 @@ void tasksInit(void)
cfTask_t cfTasks[TASK_COUNT] = {
[TASK_SYSTEM] = DEFINE_TASK("SYSTEM", "LOAD", NULL, taskSystemLoad, TASK_PERIOD_HZ(10), TASK_PRIORITY_MEDIUM_HIGH),
[TASK_SYSTEM] = DEFINE_TASK("SYSTEM", "LOAD", NULL, taskSystemLoad, TASK_PERIOD_HZ(10), TASK_PRIORITY_MEDIUM_HIGH),
[TASK_MAIN] = DEFINE_TASK("SYSTEM", "UPDATE", NULL, taskMain, TASK_PERIOD_HZ(1000), TASK_PRIORITY_MEDIUM_HIGH),
[TASK_SERIAL] = DEFINE_TASK("SERIAL", NULL, NULL, taskHandleSerial, TASK_PERIOD_HZ(100), TASK_PRIORITY_LOW), // 100 Hz should be enough to flush up to 115 bytes @ 115200 baud
[TASK_BATTERY_ALERTS] = DEFINE_TASK("BATTERY_ALERTS", NULL, NULL, taskBatteryAlerts, TASK_PERIOD_HZ(5), TASK_PRIORITY_MEDIUM),
[TASK_BATTERY_VOLTAGE] = DEFINE_TASK("BATTERY_VOLTAGE", NULL, NULL, batteryUpdateVoltage, TASK_PERIOD_HZ(50), TASK_PRIORITY_MEDIUM),
[TASK_BATTERY_CURRENT] = DEFINE_TASK("BATTERY_CURRENT", NULL, NULL, batteryUpdateCurrentMeter, TASK_PERIOD_HZ(50), TASK_PRIORITY_MEDIUM),
[TASK_BATTERY_CURRENT] = DEFINE_TASK("BATTERY_CURRENT", NULL, NULL, batteryUpdateCurrentMeter, TASK_PERIOD_HZ(50), TASK_PRIORITY_MEDIUM),
#ifdef USE_TRANSPONDER
[TASK_TRANSPONDER] = DEFINE_TASK("TRANSPONDER", NULL, NULL, transponderUpdate, TASK_PERIOD_HZ(250), TASK_PRIORITY_LOW),

View File

@ -137,7 +137,7 @@ static void failsafeActivate(void)
failsafeState.active = true;
failsafeState.phase = FAILSAFE_LANDING;
ENABLE_FLIGHT_MODE(FAILSAFE_MODE);
failsafeState.landingShouldBeFinishedAt = millis() + failsafeConfig()->failsafe_off_delay * MILLIS_PER_TENTH_SECOND;
@ -233,7 +233,7 @@ void failsafeUpdateState(void)
failsafeState.receivingRxDataPeriodPreset = PERIOD_OF_1_SECONDS; // require 1 seconds of valid rxData
reprocessState = true;
} else if (!receivingRxData) {
if (millis() > failsafeState.throttleLowPeriod
if (millis() > failsafeState.throttleLowPeriod
#ifdef USE_GPS_RESCUE
&& failsafeConfig()->failsafe_procedure != FAILSAFE_PROCEDURE_GPS_RESCUE
#endif

View File

@ -82,7 +82,7 @@ typedef struct failsafeState_s {
bool monitoring;
bool active;
uint32_t rxDataFailurePeriod;
uint32_t rxDataRecoveryPeriod;
uint32_t rxDataRecoveryPeriod;
uint32_t validRxDataReceivedAt;
uint32_t validRxDataFailedAt;
uint32_t throttleLowPeriod; // throttle stick must have been below 'min_check' for this period

View File

@ -271,7 +271,7 @@ static void setBearing(int16_t desiredHeading)
}
errorAngle *= -GET_DIRECTION(rcControlsConfig()->yaw_control_reversed);
// Calculate a desired yaw rate based on a maximum limit beyond
// an error window and then scale the requested rate down inside
// the window as error approaches 0.
@ -329,7 +329,7 @@ static void rescueAttainPosition()
Altitude controller
*/
const int16_t altitudeError = rescueState.intent.targetAltitudeCm - rescueState.sensor.currentAltitudeCm;
// P component
if (ABS(altitudeError) > 0 && ABS(altitudeError) < GPS_RESCUE_ZVELOCITY_THRESHOLD) {
scalingRate = (float)altitudeError / GPS_RESCUE_ZVELOCITY_THRESHOLD;
@ -382,7 +382,7 @@ static void performSanityChecks()
static uint32_t previousTimeUs = 0; // Last time Stalled/LowSat was checked
static int8_t secondsStalled = 0; // Stalled movement detection
static uint16_t lastDistanceToHomeM = 0; // Fly Away detection
static int8_t secondsFlyingAway = 0;
static int8_t secondsFlyingAway = 0;
static int8_t secondsLowSats = 0; // Minimum sat detection
const uint32_t currentTimeUs = micros();
@ -583,24 +583,24 @@ void updateGPSRescueState(void)
// Minimum distance detection.
if (rescueState.sensor.distanceToHomeM < gpsRescueConfig()->minRescueDth) {
rescueState.failure = RESCUE_TOO_CLOSE;
// Never allow rescue mode to engage as a failsafe when too close.
if (rescueState.isFailsafe) {
setArmingDisabled(ARMING_DISABLED_ARM_SWITCH);
disarm(DISARM_REASON_GPS_RESCUE);
}
// When not in failsafe mode: leave it up to the sanity check setting.
}
newSpeed = gpsRescueConfig()->rescueGroundspeed;
//set new descent distance if actual distance to home is lower
//set new descent distance if actual distance to home is lower
if (rescueState.sensor.distanceToHomeM < gpsRescueConfig()->descentDistanceM) {
newDescentDistanceM = MAX(rescueState.sensor.distanceToHomeM - 5, GPS_RESCUE_MIN_DESCENT_DIST_M);
} else {
newDescentDistanceM = gpsRescueConfig()->descentDistanceM;
}
switch (gpsRescueConfig()->altitudeMode) {
case FIXED_ALT:
newAltitude = gpsRescueConfig()->initialAltitudeM * 100;
@ -653,7 +653,7 @@ void updateGPSRescueState(void)
// Only allow new altitude and new speed to be equal or lower than the current values (to prevent parabolic movement on overshoot)
const int32_t newAlt = MAX((lineSlope * rescueState.sensor.distanceToHomeM + lineOffsetM) * 100, 0);
// Start to decrease proportionally the quad's speed when the distance to home is less or equal than GPS_RESCUE_SLOWDOWN_DISTANCE_M
if (rescueState.sensor.distanceToHomeM <= GPS_RESCUE_SLOWDOWN_DISTANCE_M) {
newSpeed = gpsRescueConfig()->rescueGroundspeed * rescueState.sensor.distanceToHomeM / GPS_RESCUE_SLOWDOWN_DISTANCE_M;
@ -720,7 +720,7 @@ float gpsRescueGetThrottle(void)
// is based on the raw rcCommand value commanded by the pilot.
float commandedThrottle = scaleRangef(rescueThrottle, MAX(rxConfig()->mincheck, PWM_RANGE_MIN), PWM_RANGE_MAX, 0.0f, 1.0f);
commandedThrottle = constrainf(commandedThrottle, 0.0f, 1.0f);
return commandedThrottle;
}

View File

@ -46,7 +46,7 @@
// FFT_WINDOW_SIZE defaults to 32 (gyroanalyse.h)
// We get 16 frequency bins from 32 consecutive data values
// Bin 0 is DC and can't be used.
// Bin 0 is DC and can't be used.
// Only bins 1 to 15 are usable.
// A gyro sample is collected every gyro loop
@ -59,7 +59,7 @@
// Note that lower max requires more samples to be averaged, increasing precision but taking longer to get enough samples.
// For Bosch at 3200Hz gyro, max of 600, int(3200/1200) = 2, fftSamplingRateHz = 1600, range to 800hz
// For Bosch on XClass, better to set a max of 300, int(3200/600) = 5, fftSamplingRateHz = 640, range to 320Hz
//
//
// When sampleCount reaches maxSampleCount, the averaged gyro value is put into the circular buffer of 32 samples
// At 8k, with 600Hz max, maxSampleCount = 6, this happens every 6 * 0.125us, or every 0.75ms
// Hence to completely replace all 32 samples of the FFT input buffer with clean new data takes 24ms
@ -78,7 +78,7 @@
// Calculation steps 1 and 2 then calculate the fft output (32 data points) and put that back into the same fftData[i] array.
// We then use fftData[i] array for frequency centre calculations for that axis
// Each FFT output bin has width fftSamplingRateHz/32, ie 41.65Hz per bin at 1333Hz
// Each FFT output bin has width fftSamplingRateHz/32, ie 41.65Hz per bin at 1333Hz
// Usable bandwidth is half this, ie 666Hz if fftSamplingRateHz is 1333Hz, i.e. bin 1 is 41.65hz, bin 2 83.3hz etc
#define DYN_NOTCH_SMOOTH_HZ 4
@ -124,7 +124,7 @@ void gyroDataAnalyseInit(uint32_t targetLooptimeUs)
const int gyroLoopRateHz = lrintf((1.0f / targetLooptimeUs) * 1e6f);
samples = MAX(1, gyroLoopRateHz / (2 * dynNotchMaxHz)); //600hz, 8k looptime, 13.333
fftSamplingRateHz = gyroLoopRateHz / samples;
fftSamplingRateHz = gyroLoopRateHz / samples;
// eg 8k, user max 600hz, int(8000/1200) = 6 (6.666), fftSamplingRateHz = 1333hz, range 666Hz
// eg 4k, user max 600hz, int(4000/1200) = 3 (3.333), fftSamplingRateHz = 1333hz, range 666Hz
// eg 2k, user max 600hz, int(2000/1200) = 1 (1.666) fftSamplingRateHz = 2000hz, range 1000Hz
@ -278,7 +278,7 @@ static FAST_CODE_NOINLINE void gyroDataAnalyseUpdate(gyroAnalyseState_t *state,
}
case STEP_CALC_FREQUENCIES:
{
// identify max bin and max/min heights
// identify max bin and max/min heights
float dataMax = 0.0f;
float dataMin = 1.0f;
uint8_t binMax = 0;

View File

@ -178,7 +178,7 @@ void imuConfigure(uint16_t throttle_correction_angle, uint8_t throttle_correctio
fc_acc = calculateAccZLowPassFilterRCTimeConstant(5.0f); // Set to fix value
throttleAngleScale = calculateThrottleAngleScale(throttle_correction_angle);
throttleAngleValue = throttle_correction_value;
}
@ -591,7 +591,7 @@ void imuUpdateAttitude(timeUs_t currentTimeUs)
#endif
imuCalculateEstimatedAttitude(currentTimeUs);
IMU_UNLOCK;
// Update the throttle correction for angle and supply it to the mixer
int throttleAngleCorrection = 0;
if (throttleAngleValue && (FLIGHT_MODE(ANGLE_MODE) || FLIGHT_MODE(HORIZON_MODE)) && ARMING_FLAG(ARMED)) {

View File

@ -38,7 +38,7 @@ typedef struct laggedMovingAverageCombined_s {
} laggedMovingAverageCombined_t;
laggedMovingAverageCombined_t setpointDeltaAvg[XYZ_AXIS_COUNT];
static float prevSetpointSpeed[XYZ_AXIS_COUNT];
static float prevAcceleration[XYZ_AXIS_COUNT];
static float prevRawSetpoint[XYZ_AXIS_COUNT];
@ -63,7 +63,7 @@ void interpolatedSpInit(const pidProfile_t *pidProfile) {
FAST_CODE_NOINLINE float interpolatedSpApply(int axis, bool newRcFrame, ffInterpolationType_t type) {
if (newRcFrame) {
float rawSetpoint = getRawSetpoint(axis);
float rawSetpoint = getRawSetpoint(axis);
const float rxInterval = currentRxRefreshRate * 1e-6f;
const float rxRate = 1.0f / rxInterval;
@ -80,7 +80,7 @@ FAST_CODE_NOINLINE float interpolatedSpApply(int axis, bool newRcFrame, ffInterp
}
if (setpointSpeed == 0 && fabsf(rawSetpoint) < 0.98f * ffMaxRate[axis]) {
// identical packet detected, not at full deflection.
// identical packet detected, not at full deflection.
// first packet on leaving full deflection always gets full FF
if (holdCount[axis] == 0) {
// previous packet had movement

View File

@ -610,7 +610,7 @@ static void calculateThrottleAndCurrentMotorEndpoints(timeUs_t currentTimeUs)
DEBUG_SET(DEBUG_DYN_IDLE, 1, targetRpsChangeRate);
DEBUG_SET(DEBUG_DYN_IDLE, 2, error);
DEBUG_SET(DEBUG_DYN_IDLE, 3, minRps);
}
#endif
currentThrottleInputRange = rcCommandThrottleRange;
@ -679,14 +679,14 @@ static void applyFlipOverAfterCrashModeToMotors(void)
signPitch*currentMixer[i].pitch +
signRoll*currentMixer[i].roll +
signYaw*currentMixer[i].yaw;
if (motorOutputNormalised < 0) {
if (mixerConfig()->crashflip_motor_percent > 0) {
motorOutputNormalised = -motorOutputNormalised * (float)mixerConfig()->crashflip_motor_percent / 100.0f;
} else {
motorOutputNormalised = 0;
}
}
}
motorOutputNormalised = MIN(1.0f, flipPower * motorOutputNormalised);
float motorOutput = motorOutputMin + motorOutputNormalised * motorOutputRange;
@ -801,7 +801,7 @@ FAST_CODE_NOINLINE void mixTable(timeUs_t currentTimeUs, uint8_t vbatPidCompensa
activeMixer = &launchControlMixer[0];
}
#endif
// Calculate and Limit the PID sum
const float scaledAxisPidRoll =
constrainf(pidData[FD_ROLL].Sum, -currentPidProfile->pidSumLimit, currentPidProfile->pidSumLimit) / PID_MIXER_SCALING;
@ -838,7 +838,7 @@ FAST_CODE_NOINLINE void mixTable(timeUs_t currentTimeUs, uint8_t vbatPidCompensa
// 50% throttle provides the maximum authority for yaw recovery when airmode is not active.
// When airmode is active the throttle setting doesn't impact recovery authority.
if (yawSpinDetected && !airmodeEnabled) {
throttle = 0.5f; //
throttle = 0.5f; //
}
#endif // USE_YAW_SPIN_RECOVERY

View File

@ -652,7 +652,7 @@ void pidInitConfig(const pidProfile_t *pidProfile)
#endif
itermRotation = pidProfile->iterm_rotation;
antiGravityMode = pidProfile->antiGravityMode;
// Calculate the anti-gravity value that will trigger the OSD display.
// For classic AG it's either 1.0 for off and > 1.0 for on.
// For the new AG it's a continuous floating value so we want to trigger the OSD
@ -729,7 +729,7 @@ void pidInitConfig(const pidProfile_t *pidProfile)
thrustLinearizationReciprocal = 1.0f / thrustLinearization;
thrustLinearizationB = (1.0f - thrustLinearization) / (2.0f * thrustLinearization);
}
#endif
#endif
#if defined(USE_D_MIN)
for (int axis = FD_ROLL; axis <= FD_YAW; ++axis) {
const uint8_t dMin = pidProfile->d_min[axis];
@ -1004,7 +1004,7 @@ static FAST_CODE_NOINLINE float applyAcroTrainer(int axis, const rollAndPitchTri
if (acroTrainerAxisState[axis] != 0) {
ret = constrainf(((acroTrainerAngleLimit * angleSign) - currentAngle) * acroTrainerGain, -ACRO_TRAINER_SETPOINT_LIMIT, ACRO_TRAINER_SETPOINT_LIMIT);
} else {
// Not currently over the limit so project the angle based on current angle and
// gyro angular rate using a sliding window based on gyro rate (faster rotation means larger window.
// If the projected angle exceeds the limit then apply limiting to minimize overshoot.
@ -1021,7 +1021,7 @@ static FAST_CODE_NOINLINE float applyAcroTrainer(int axis, const rollAndPitchTri
if (resetIterm) {
pidData[axis].I = 0;
}
if (axis == acroTrainerDebugAxis) {
DEBUG_SET(DEBUG_ACRO_TRAINER, 0, lrintf(currentAngle * 10.0f));
DEBUG_SET(DEBUG_ACRO_TRAINER, 1, acroTrainerAxisState[axis]);
@ -1523,7 +1523,7 @@ void FAST_CODE pidController(const pidProfile_t *pidProfile, timeUs_t currentTim
if (yawSpinActive) {
pidData[axis].I = 0; // in yaw spin always disable I
if (axis <= FD_PITCH) {
// zero PIDs on pitch and roll leaving yaw P to correct spin
// zero PIDs on pitch and roll leaving yaw P to correct spin
pidData[axis].P = 0;
pidData[axis].D = 0;
pidData[axis].F = 0;

View File

@ -181,9 +181,9 @@ typedef struct pidProfile_s {
uint8_t idle_min_rpm; // minimum motor speed enforced by integrating p controller
uint8_t idle_adjustment_speed; // how quickly the integrating p controller tries to correct
uint8_t idle_p; // kP
uint8_t idle_pid_limit; // max P
uint8_t idle_pid_limit; // max P
uint8_t idle_max_increase; // max integrated correction
uint8_t ff_interpolate_sp; // Calculate FF from interpolated setpoint
uint8_t ff_max_rate_limit; // Maximum setpoint rate percentage for FF
uint8_t ff_spike_limit; // FF stick extrapolation lookahead period in ms

View File

@ -143,8 +143,8 @@ void calculateEstimatedAltitude(timeUs_t currentTimeUs)
}
baroAlt -= baroAltOffset;
gpsAlt -= gpsAltOffset;
if (haveGpsAlt && haveBaroAlt && positionConfig()->altSource == DEFAULT) {
estimatedAltitudeCm = gpsAlt * gpsTrust + baroAlt * (1 - gpsTrust);
#ifdef USE_VARIO
@ -162,9 +162,9 @@ void calculateEstimatedAltitude(timeUs_t currentTimeUs)
estimatedVario = calculateEstimatedVario(baroAlt, dTime);
#endif
}
DEBUG_SET(DEBUG_ALTITUDE, 0, (int32_t)(100 * gpsTrust));
DEBUG_SET(DEBUG_ALTITUDE, 1, baroAlt);
DEBUG_SET(DEBUG_ALTITUDE, 2, gpsAlt);

View File

@ -274,7 +274,7 @@ void gpsInit(void)
gpsSetState(GPS_UNKNOWN);
gpsData.lastMessage = millis();
if (gpsConfig()->provider == GPS_MSP) { // no serial ports used when GPS_MSP is configured
gpsSetState(GPS_INITIALIZED);
return;
@ -543,7 +543,7 @@ void gpsUpdate(timeUs_t currentTimeUs)
gpsData.messageState = GPS_MESSAGE_STATE_PEDESTRIAN_TO_AIRBORNE;
gpsData.state_position = 0;
}
if (gpsData.messageState == GPS_MESSAGE_STATE_PEDESTRIAN_TO_AIRBORNE) {
if (gpsData.messageState == GPS_MESSAGE_STATE_PEDESTRIAN_TO_AIRBORNE) {
if (gpsData.state_position < sizeof(ubloxAirborne)) {
if (isSerialTransmitBufferEmpty(gpsPort)) {
serialWrite(gpsPort, ubloxAirborne[gpsData.state_position]);

View File

@ -78,7 +78,7 @@ static bool rcdeviceRespCtxQueuePush(rcdeviceWaitingResponseQueue *queue, rcdevi
}
queue->itemCount += 1;
queue->tailPos = newTailPos;
return true;
}
@ -358,7 +358,7 @@ static rcdeviceResponseParseContext_t* getWaitingResponse(timeMs_t currentTimeMs
return respCtx;
}
void rcdeviceReceive(timeUs_t currentTimeUs)
void rcdeviceReceive(timeUs_t currentTimeUs)
{
UNUSED(currentTimeUs);
@ -393,7 +393,7 @@ void rcdeviceReceive(timeUs_t currentTimeUs)
uint8_t crcFromPacket = respCtx->recvBuf[3];
respCtx->recvBuf[3] = respCtx->recvBuf[4]; // move packet tail field to crc field, and calc crc with first 4 bytes
uint8_t crc = crc8HighFirst(respCtx->recvBuf, 4);
respCtx->result = crc == crcFromPacket ? RCDEVICE_RESP_SUCCESS : RCDEVICE_RESP_INCORRECT_CRC;
} else {
respCtx->result = RCDEVICE_RESP_INCORRECT_CRC;

View File

@ -75,7 +75,7 @@ static void rcdeviceCameraControlProcess(void)
uint8_t switchIndex = i - BOXCAMERA1;
if (IS_RC_MODE_ACTIVE(i)) {
// check last state of this mode, if it's true, then ignore it.
// Here is a logic to make a toggle control for this mode
if (switchStates[switchIndex].isActivated) {
@ -87,7 +87,7 @@ static void rcdeviceCameraControlProcess(void)
case BOXCAMERA1:
if (isFeatureSupported(RCDEVICE_PROTOCOL_FEATURE_SIMULATE_WIFI_BUTTON)) {
// avoid display wifi page when arming, in the next firmware(>2.0) of rcsplit we have change the wifi page logic:
// when the wifi was turn on it won't turn off the analog video output,
// when the wifi was turn on it won't turn off the analog video output,
// and just put a wifi indicator on the right top of the video output. here is for the old split firmware
if (!ARMING_FLAG(ARMED) && !(getArmingDisableFlags() & (ARMING_DISABLED_RUNAWAY_TAKEOFF | ARMING_DISABLED_CRASH_DETECTED))) {
behavior = RCDEVICE_PROTOCOL_CAM_CTRL_SIMULATE_WIFI_BTN;
@ -96,7 +96,7 @@ static void rcdeviceCameraControlProcess(void)
break;
case BOXCAMERA2:
if (isFeatureSupported(RCDEVICE_PROTOCOL_FEATURE_SIMULATE_POWER_BUTTON)) {
behavior = RCDEVICE_PROTOCOL_CAM_CTRL_SIMULATE_POWER_BTN;
behavior = RCDEVICE_PROTOCOL_CAM_CTRL_SIMULATE_POWER_BTN;
}
break;
case BOXCAMERA3:
@ -128,7 +128,7 @@ static void rcdeviceSimulationOSDCableFailed(rcdeviceResponseParseContext_t *ctx
if (operationID == RCDEVICE_PROTOCOL_5KEY_CONNECTION_CLOSE) {
return;
}
}
}
}
static void rcdeviceSimulationRespHandle(rcdeviceResponseParseContext_t *ctx)

View File

@ -728,7 +728,7 @@ uint32_t emfat_cma_time_from_unix(uint32_t tim)
/* Days are what is left over (+1) from all that. */
ymd[2] = day + 1;
return EMFAT_ENCODE_CMA_TIME(ymd[2], ymd[1], ymd[0], hms[0], hms[1], hms[2]);
}

View File

@ -72,154 +72,154 @@ static const char readme_file[] =
#ifdef USE_EMFAT_ICON
static const char icon_file[] =
{
0x00, 0x00, 0x01, 0x00, 0x01, 0x00, 0x18, 0x18, 0x00, 0x00, 0x01, 0x00, 0x20, 0x00, 0x28, 0x09,
0x00, 0x00, 0x16, 0x00, 0x00, 0x00, 0x28, 0x00, 0x00, 0x00, 0x18, 0x00, 0x00, 0x00, 0x30, 0x00,
0x00, 0x00, 0x01, 0x00, 0x20, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00,
0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0xfc, 0xfc,
0xfc, 0xde, 0xfc, 0xfc, 0xfc, 0xee, 0xfb, 0xfb, 0xfb, 0xee, 0xfb, 0xfb, 0xfb, 0xee, 0xfd, 0xfd,
0xfd, 0xee, 0xfd, 0xfd, 0xfd, 0xee, 0xfd, 0xfd, 0xfd, 0xee, 0xfc, 0xfc, 0xfc, 0xee, 0xfb, 0xfb,
0xfb, 0xee, 0xfc, 0xfc, 0xfc, 0xee, 0xfb, 0xfb, 0xfb, 0xee, 0xfd, 0xfd, 0xfd, 0xee, 0xfd, 0xfd,
0xfd, 0xee, 0xfd, 0xfd, 0xfd, 0xee, 0xfd, 0xfd, 0xfd, 0xee, 0xfb, 0xfb, 0xfb, 0xee, 0xfc, 0xfc,
0xfc, 0xee, 0xfb, 0xfb, 0xfb, 0xee, 0xfb, 0xfb, 0xfb, 0xee, 0xfd, 0xfd, 0xfd, 0xee, 0xfd, 0xfd,
0xfd, 0xee, 0xfd, 0xfd, 0xfd, 0xee, 0xfd, 0xfd, 0xfd, 0xee, 0xfc, 0xfc, 0xfc, 0xde, 0xfb, 0xfb,
0xfb, 0xf4, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff,
0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff,
0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff,
0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff,
0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff,
0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xfc, 0xfc, 0xfc, 0xf4, 0xfd, 0xfd,
0xfd, 0xee, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xfe, 0xfe, 0xfe, 0xff, 0xfd, 0xfd,
0xfd, 0xff, 0xfe, 0xfe, 0xfe, 0xff, 0xfd, 0xfd, 0xfd, 0xff, 0xfd, 0xfd, 0xfd, 0xff, 0xff, 0xff,
0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xfd, 0xfd, 0xfd, 0xff, 0xff, 0xff,
0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff,
0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xfe, 0xfe, 0xfe, 0xff, 0xfd, 0xfd, 0xfd, 0xff, 0xfe, 0xfe,
0xfe, 0xff, 0xfd, 0xfd, 0xfd, 0xff, 0xff, 0xff, 0xff, 0xff, 0xfd, 0xfd, 0xfd, 0xee, 0xfd, 0xfd,
0xfd, 0xee, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xfe, 0xfe, 0xfe, 0xff, 0xfc, 0xfc,
0xfc, 0xff, 0xfe, 0xfe, 0xfe, 0xff, 0xfd, 0xfd, 0xfd, 0xff, 0xfe, 0xfe, 0xfe, 0xff, 0xff, 0xff,
0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xf9, 0xfb,
0xfc, 0xff, 0xd7, 0xdd, 0xe1, 0xff, 0xc7, 0xc3, 0xc2, 0xff, 0xce, 0xce, 0xce, 0xff, 0xe2, 0xe4,
0xe5, 0xff, 0xfd, 0xfc, 0xfc, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xfe, 0xfe,
0xfe, 0xff, 0xfd, 0xfd, 0xfd, 0xff, 0xff, 0xff, 0xff, 0xff, 0xfd, 0xfd, 0xfd, 0xee, 0xfb, 0xfb,
0xfb, 0xee, 0xff, 0xff, 0xff, 0xff, 0xfe, 0xfe, 0xfe, 0xff, 0xfd, 0xfd, 0xfd, 0xff, 0xff, 0xff,
0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xfd, 0xfd, 0xfd, 0xff, 0xfe, 0xfe,
0xfe, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xb0, 0xad, 0xad, 0xff, 0x3a, 0x89,
0xa8, 0xff, 0x03, 0xb5, 0xed, 0xff, 0x20, 0x57, 0x6c, 0xff, 0x36, 0x25, 0x1f, 0xff, 0x34, 0x52,
0x5e, 0xff, 0x4f, 0x65, 0x6e, 0xff, 0x8a, 0x86, 0x84, 0xff, 0xd8, 0xd8, 0xd8, 0xff, 0xff, 0xff,
0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xfc, 0xfc, 0xfc, 0xee, 0xfa, 0xfa,
0xfa, 0xee, 0xff, 0xff, 0xff, 0xff, 0xfd, 0xfd, 0xfd, 0xff, 0xfd, 0xfd, 0xfd, 0xff, 0xff, 0xff,
0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xfd, 0xfd, 0xfd, 0xff, 0xfc, 0xfc,
0xfc, 0xff, 0xff, 0xff, 0xff, 0xff, 0xb7, 0xb2, 0xb1, 0xff, 0x2a, 0x1d, 0x18, 0xff, 0x33, 0x2a,
0x26, 0xff, 0x25, 0x68, 0x7f, 0xff, 0x16, 0x90, 0xbe, 0xff, 0x3a, 0x38, 0x37, 0xff, 0x37, 0x38,
0x38, 0xff, 0x31, 0x35, 0x37, 0xff, 0x29, 0x28, 0x27, 0xff, 0x34, 0x34, 0x34, 0xff, 0x93, 0x93,
0x93, 0xff, 0xf3, 0xf3, 0xf3, 0xff, 0xff, 0xff, 0xff, 0xff, 0xfb, 0xfb, 0xfb, 0xee, 0xfd, 0xfd,
0xfd, 0xee, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xfe, 0xfe, 0xfe, 0xff, 0xfe, 0xfe,
0xfe, 0xff, 0xff, 0xff, 0xff, 0xff, 0xfe, 0xfe, 0xfe, 0xff, 0xfd, 0xfd, 0xfd, 0xff, 0xff, 0xff,
0xff, 0xff, 0xff, 0xfc, 0xf8, 0xff, 0x4f, 0xa0, 0xbf, 0xff, 0x0d, 0x8c, 0xb8, 0xff, 0x2c, 0x62,
0x76, 0xff, 0x3e, 0x31, 0x2e, 0xff, 0x36, 0x46, 0x4d, 0xff, 0x38, 0x41, 0x44, 0xff, 0x3b, 0x39,
0x38, 0xff, 0x37, 0x36, 0x35, 0xff, 0x2c, 0x2c, 0x2c, 0xff, 0x28, 0x28, 0x28, 0xff, 0x83, 0x83,
0x83, 0xff, 0x77, 0x77, 0x77, 0xff, 0xd5, 0xd5, 0xd5, 0xff, 0xfd, 0xfd, 0xfd, 0xee, 0xfd, 0xfd,
0xfd, 0xee, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xfe, 0xfe, 0xfe, 0xff, 0xfc, 0xfc,
0xfc, 0xff, 0xfd, 0xfd, 0xfd, 0xff, 0xfc, 0xfc, 0xfc, 0xff, 0xfe, 0xfe, 0xfe, 0xff, 0xff, 0xff,
0xff, 0xff, 0xff, 0xfd, 0xfb, 0xff, 0x5f, 0x98, 0xad, 0xff, 0x1a, 0x5c, 0x73, 0xff, 0x30, 0x5a,
0x6a, 0xff, 0x38, 0x42, 0x46, 0xff, 0x3c, 0x35, 0x33, 0xff, 0x39, 0x38, 0x37, 0xff, 0x2b, 0x2b,
0x2b, 0xff, 0x3c, 0x3c, 0x3c, 0xff, 0x83, 0x83, 0x83, 0xff, 0xc2, 0xc2, 0xc2, 0xff, 0xd2, 0xd2,
0xd2, 0xff, 0xa9, 0xa9, 0xa9, 0xff, 0x86, 0x86, 0x86, 0xff, 0xdf, 0xdf, 0xdf, 0xee, 0xfc, 0xfc,
0xfc, 0xee, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xfd, 0xfd, 0xfd, 0xff, 0xff, 0xff,
0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xfd, 0xfd, 0xfd, 0xff, 0xff, 0xff,
0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xc3, 0xba, 0xb7, 0xff, 0x2c, 0x21, 0x1d, 0xff, 0x38, 0x30,
0x2d, 0xff, 0x3c, 0x3a, 0x39, 0xff, 0x34, 0x35, 0x35, 0xff, 0x2e, 0x2e, 0x2e, 0xff, 0x78, 0x78,
0x78, 0xff, 0xdf, 0xdf, 0xdf, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff,
0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xfe, 0xfe, 0xfe, 0xff, 0xeb, 0xeb, 0xeb, 0xee, 0xfa, 0xfa,
0xfa, 0xee, 0xfe, 0xfe, 0xfe, 0xff, 0xfc, 0xfc, 0xfc, 0xff, 0xfd, 0xfd, 0xfd, 0xff, 0xff, 0xff,
0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xfd, 0xfd, 0xfd, 0xff, 0xfc, 0xfc,
0xfc, 0xff, 0xfd, 0xfd, 0xfd, 0xff, 0xff, 0xff, 0xff, 0xff, 0xb3, 0xb0, 0xaf, 0xff, 0x3d, 0x31,
0x2c, 0xff, 0x33, 0x30, 0x2f, 0xff, 0x49, 0x4a, 0x4a, 0xff, 0xcb, 0xcb, 0xcb, 0xff, 0xff, 0xff,
0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xfd, 0xfd, 0xfd, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff,
0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xfd, 0xfd, 0xfd, 0xee, 0xfc, 0xfc,
0xfc, 0xee, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xfd, 0xfd, 0xfd, 0xff, 0xff, 0xff,
0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff,
0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xd3, 0xe2, 0xe8, 0xff, 0x1c, 0x85,
0xae, 0xff, 0x2f, 0x44, 0x4c, 0xff, 0x41, 0x3c, 0x3a, 0xff, 0x9a, 0x9a, 0x9a, 0xff, 0xf9, 0xf9,
0xf9, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff,
0xff, 0xff, 0xf9, 0xf9, 0xf9, 0xff, 0xf8, 0xf8, 0xf8, 0xff, 0xfd, 0xfd, 0xfd, 0xee, 0xfd, 0xfd,
0xfd, 0xee, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xfe, 0xfe, 0xfe, 0xff, 0xff, 0xff,
0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xf8, 0xf8, 0xf8, 0xff, 0xf5, 0xf5,
0xf5, 0xff, 0xf9, 0xf9, 0xf9, 0xff, 0xff, 0xff, 0xff, 0xff, 0x8a, 0xd0, 0xea, 0xff, 0x00, 0xb0,
0xf7, 0xff, 0x36, 0x49, 0x51, 0xff, 0x39, 0x33, 0x31, 0xff, 0x1f, 0x1f, 0x1f, 0xff, 0x98, 0x98,
0x98, 0xff, 0xe2, 0xe2, 0xe2, 0xff, 0x9b, 0x9b, 0x9b, 0xff, 0x71, 0x71, 0x71, 0xff, 0x72, 0x72,
0x72, 0xff, 0x63, 0x63, 0x63, 0xff, 0xef, 0xef, 0xef, 0xff, 0xfd, 0xfd, 0xfd, 0xee, 0xfd, 0xfd,
0xfd, 0xee, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xf4, 0xf4,
0xf4, 0xff, 0xae, 0xae, 0xae, 0xff, 0x8c, 0x8c, 0x8c, 0xff, 0x86, 0x86, 0x86, 0xff, 0x84, 0x84,
0x84, 0xff, 0x86, 0x86, 0x86, 0xff, 0x91, 0x8a, 0x87, 0xff, 0x48, 0x7a, 0x8d, 0xff, 0x00, 0x9c,
0xd7, 0xff, 0x3a, 0x3e, 0x3f, 0xff, 0x39, 0x36, 0x35, 0xff, 0x35, 0x35, 0x35, 0xff, 0x42, 0x42,
0x42, 0xff, 0x3b, 0x3b, 0x3b, 0xff, 0x31, 0x31, 0x31, 0xff, 0x92, 0x92, 0x92, 0xff, 0x90, 0x90,
0x90, 0xff, 0x7b, 0x7b, 0x7b, 0xff, 0xff, 0xff, 0xff, 0xff, 0xfd, 0xfd, 0xfd, 0xee, 0xfb, 0xfb,
0xfb, 0xee, 0xfe, 0xfe, 0xfe, 0xff, 0xff, 0xff, 0xff, 0xff, 0xde, 0xde, 0xde, 0xff, 0x80, 0x80,
0x80, 0xff, 0xb1, 0xb1, 0xb1, 0xff, 0xe6, 0xe6, 0xe6, 0xff, 0xf9, 0xf9, 0xf9, 0xff, 0xff, 0xff,
0xff, 0xff, 0xea, 0xea, 0xea, 0xff, 0x81, 0x80, 0x80, 0xff, 0x49, 0x42, 0x40, 0xff, 0x55, 0x8e,
0xa3, 0xff, 0x1f, 0x5b, 0x72, 0xff, 0x35, 0x3a, 0x3c, 0xff, 0x43, 0x41, 0x41, 0xff, 0x35, 0x35,
0x35, 0xff, 0x2a, 0x2a, 0x2a, 0xff, 0xbe, 0xbe, 0xbe, 0xff, 0xe8, 0xe8, 0xe8, 0xff, 0x6f, 0x6f,
0x6f, 0xff, 0xe7, 0xe7, 0xe7, 0xff, 0xff, 0xff, 0xff, 0xff, 0xfb, 0xfb, 0xfb, 0xee, 0xfb, 0xfb,
0xfb, 0xee, 0xff, 0xff, 0xff, 0xff, 0xf5, 0xf5, 0xf5, 0xff, 0x7b, 0x7b, 0x7b, 0xff, 0xe0, 0xe0,
0xe0, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xf8, 0xf8, 0xf8, 0xff, 0xb8, 0xb8,
0xb8, 0xff, 0x7d, 0x7d, 0x7d, 0xff, 0xa3, 0xa3, 0xa3, 0xff, 0xd2, 0xd2, 0xd2, 0xff, 0x87, 0x7c,
0x77, 0xff, 0x5a, 0x57, 0x55, 0xff, 0xca, 0xcb, 0xcb, 0xff, 0x82, 0x82, 0x82, 0xff, 0x23, 0x23,
0x23, 0xff, 0x38, 0x38, 0x38, 0xff, 0x43, 0x43, 0x43, 0xff, 0x5d, 0x5d, 0x5d, 0xff, 0xd9, 0xd9,
0xd9, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xfc, 0xfc, 0xfc, 0xee, 0xfd, 0xfd,
0xfd, 0xee, 0xff, 0xff, 0xff, 0xff, 0xa1, 0xa1, 0xa1, 0xff, 0xb6, 0xb6, 0xb6, 0xff, 0xff, 0xff,
0xff, 0xff, 0xfb, 0xfb, 0xfb, 0xff, 0xdb, 0xdb, 0xdb, 0xff, 0xb1, 0xb1, 0xb1, 0xff, 0xc7, 0xc7,
0xc7, 0xff, 0xea, 0xea, 0xea, 0xff, 0xa6, 0xa6, 0xa6, 0xff, 0x60, 0x60, 0x60, 0xff, 0x9f, 0x9f,
0x9f, 0xff, 0xfd, 0xfd, 0xfd, 0xff, 0xff, 0xff, 0xff, 0xff, 0xd1, 0xd1, 0xd1, 0xff, 0x4e, 0x4e,
0x4e, 0xff, 0x29, 0x29, 0x29, 0xff, 0x73, 0x73, 0x73, 0xff, 0xeb, 0xeb, 0xeb, 0xff, 0xff, 0xff,
0xff, 0xff, 0xfd, 0xfd, 0xfd, 0xff, 0xff, 0xff, 0xff, 0xff, 0xfd, 0xfd, 0xfd, 0xee, 0xfd, 0xfd,
0xfd, 0xee, 0xec, 0xec, 0xec, 0xff, 0x90, 0x90, 0x90, 0xff, 0xff, 0xff, 0xff, 0xff, 0xfe, 0xfe,
0xfe, 0xff, 0xf3, 0xf3, 0xf3, 0xff, 0xf0, 0xf0, 0xf0, 0xff, 0xff, 0xff, 0xff, 0xff, 0xb7, 0xb7,
0xb7, 0xff, 0x61, 0x61, 0x61, 0xff, 0x89, 0x89, 0x89, 0xff, 0xeb, 0xeb, 0xeb, 0xff, 0xff, 0xff,
0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xfc, 0xfc, 0xfc, 0xff, 0xdc, 0xdc, 0xdc, 0xff, 0x99, 0x99,
0x99, 0xff, 0xbc, 0xbc, 0xbc, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xfe, 0xfe,
0xfe, 0xff, 0xfd, 0xfd, 0xfd, 0xff, 0xff, 0xff, 0xff, 0xff, 0xfd, 0xfd, 0xfd, 0xee, 0xfd, 0xfd,
0xfd, 0xee, 0x98, 0x98, 0x98, 0xff, 0x9c, 0x9c, 0x9c, 0xff, 0xf9, 0xf9, 0xf9, 0xff, 0xff, 0xff,
0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xc5, 0xc5, 0xc5, 0xff, 0x66, 0x66, 0x66, 0xff, 0x76, 0x76,
0x76, 0xff, 0xdb, 0xdb, 0xdb, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff,
0xff, 0xff, 0xfb, 0xfb, 0xfb, 0xff, 0xdd, 0xdd, 0xdd, 0xff, 0xcd, 0xcd, 0xcd, 0xff, 0xf7, 0xf7,
0xf7, 0xff, 0xff, 0xff, 0xff, 0xff, 0xfe, 0xfe, 0xfe, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff,
0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xfc, 0xfc, 0xfc, 0xee, 0xda, 0xda,
0xda, 0xee, 0x48, 0x48, 0x48, 0xff, 0x75, 0x75, 0x75, 0xff, 0xff, 0xff, 0xff, 0xff, 0xd5, 0xd5,
0xd5, 0xff, 0x72, 0x72, 0x72, 0xff, 0x6a, 0x6a, 0x6a, 0xff, 0xc8, 0xc8, 0xc8, 0xff, 0xff, 0xff,
0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xfc, 0xfc, 0xfc, 0xff, 0xfe, 0xfe, 0xfe, 0xff, 0xff, 0xff,
0xff, 0xff, 0xfd, 0xfd, 0xfd, 0xff, 0xfe, 0xfe, 0xfe, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff,
0xff, 0xff, 0xfd, 0xfd, 0xfd, 0xff, 0xfd, 0xfd, 0xfd, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff,
0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xfb, 0xfb, 0xfb, 0xee, 0xeb, 0xeb,
0xeb, 0xee, 0xaf, 0xaf, 0xaf, 0xff, 0xb0, 0xb0, 0xb0, 0xff, 0x8b, 0x8b, 0x8b, 0xff, 0x60, 0x60,
0x60, 0xff, 0xb3, 0xb3, 0xb3, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff,
0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xfd, 0xfd, 0xfd, 0xff, 0xfe, 0xfe,
0xfe, 0xff, 0xff, 0xff, 0xff, 0xff, 0xfd, 0xfd, 0xfd, 0xff, 0xfe, 0xfe, 0xfe, 0xff, 0xff, 0xff,
0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xfd, 0xfd, 0xfd, 0xff, 0xfe, 0xfe, 0xfe, 0xff, 0xff, 0xff,
0xff, 0xff, 0xfe, 0xfe, 0xfe, 0xff, 0xff, 0xff, 0xff, 0xff, 0xfd, 0xfd, 0xfd, 0xee, 0xfd, 0xfd,
0xfd, 0xee, 0x66, 0x66, 0x66, 0xff, 0x54, 0x54, 0x54, 0xff, 0xa0, 0xa0, 0xa0, 0xff, 0xfa, 0xfa,
0xfa, 0xff, 0xff, 0xff, 0xff, 0xff, 0xfe, 0xfe, 0xfe, 0xff, 0xfe, 0xfe, 0xfe, 0xff, 0xff, 0xff,
0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xfd, 0xfd, 0xfd, 0xff, 0xfd, 0xfd,
0xfd, 0xff, 0xfd, 0xfd, 0xfd, 0xff, 0xfc, 0xfc, 0xfc, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff,
0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xfe, 0xfe, 0xfe, 0xff, 0xfc, 0xfc, 0xfc, 0xff, 0xfd, 0xfd,
0xfd, 0xff, 0xfc, 0xfc, 0xfc, 0xff, 0xff, 0xff, 0xff, 0xff, 0xfd, 0xfd, 0xfd, 0xee, 0xce, 0xce,
0xce, 0xee, 0x98, 0x98, 0x98, 0xff, 0xef, 0xef, 0xef, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff,
0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xfd, 0xfd, 0xfd, 0xff, 0xff, 0xff,
0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xfe, 0xfe, 0xfe, 0xff, 0xfd, 0xfd, 0xfd, 0xff, 0xff, 0xff,
0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xfe, 0xfe, 0xfe, 0xff, 0xfe, 0xfe, 0xfe, 0xff, 0xff, 0xff,
0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xfd, 0xfd, 0xfd, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff,
0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xfd, 0xfd, 0xfd, 0xee, 0xf6, 0xf6,
0xf6, 0xf4, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff,
0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff,
0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff,
0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff,
0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff,
0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xfb, 0xfb, 0xfb, 0xf4, 0xfd, 0xfd,
0xfd, 0xde, 0xfd, 0xfd, 0xfd, 0xee, 0xfd, 0xfd, 0xfd, 0xee, 0xfc, 0xfc, 0xfc, 0xee, 0xfd, 0xfd,
0xfd, 0xee, 0xfd, 0xfd, 0xfd, 0xee, 0xfd, 0xfd, 0xfd, 0xee, 0xfc, 0xfc, 0xfc, 0xee, 0xfd, 0xfd,
0xfd, 0xee, 0xfd, 0xfd, 0xfd, 0xee, 0xfd, 0xfd, 0xfd, 0xee, 0xfc, 0xfc, 0xfc, 0xee, 0xfd, 0xfd,
0xfd, 0xee, 0xfd, 0xfd, 0xfd, 0xee, 0xfc, 0xfc, 0xfc, 0xee, 0xfc, 0xfc, 0xfc, 0xee, 0xfd, 0xfd,
0xfd, 0xee, 0xfd, 0xfd, 0xfd, 0xee, 0xfb, 0xfb, 0xfb, 0xee, 0xfd, 0xfd, 0xfd, 0xee, 0xfd, 0xfd,
0xfd, 0xee, 0xfd, 0xfd, 0xfd, 0xee, 0xfd, 0xfd, 0xfd, 0xee, 0xfd, 0xfd, 0xfd, 0xde,
0x00, 0x00, 0x01, 0x00, 0x01, 0x00, 0x18, 0x18, 0x00, 0x00, 0x01, 0x00, 0x20, 0x00, 0x28, 0x09,
0x00, 0x00, 0x16, 0x00, 0x00, 0x00, 0x28, 0x00, 0x00, 0x00, 0x18, 0x00, 0x00, 0x00, 0x30, 0x00,
0x00, 0x00, 0x01, 0x00, 0x20, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00,
0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0xfc, 0xfc,
0xfc, 0xde, 0xfc, 0xfc, 0xfc, 0xee, 0xfb, 0xfb, 0xfb, 0xee, 0xfb, 0xfb, 0xfb, 0xee, 0xfd, 0xfd,
0xfd, 0xee, 0xfd, 0xfd, 0xfd, 0xee, 0xfd, 0xfd, 0xfd, 0xee, 0xfc, 0xfc, 0xfc, 0xee, 0xfb, 0xfb,
0xfb, 0xee, 0xfc, 0xfc, 0xfc, 0xee, 0xfb, 0xfb, 0xfb, 0xee, 0xfd, 0xfd, 0xfd, 0xee, 0xfd, 0xfd,
0xfd, 0xee, 0xfd, 0xfd, 0xfd, 0xee, 0xfd, 0xfd, 0xfd, 0xee, 0xfb, 0xfb, 0xfb, 0xee, 0xfc, 0xfc,
0xfc, 0xee, 0xfb, 0xfb, 0xfb, 0xee, 0xfb, 0xfb, 0xfb, 0xee, 0xfd, 0xfd, 0xfd, 0xee, 0xfd, 0xfd,
0xfd, 0xee, 0xfd, 0xfd, 0xfd, 0xee, 0xfd, 0xfd, 0xfd, 0xee, 0xfc, 0xfc, 0xfc, 0xde, 0xfb, 0xfb,
0xfb, 0xf4, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff,
0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff,
0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff,
0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff,
0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff,
0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xfc, 0xfc, 0xfc, 0xf4, 0xfd, 0xfd,
0xfd, 0xee, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xfe, 0xfe, 0xfe, 0xff, 0xfd, 0xfd,
0xfd, 0xff, 0xfe, 0xfe, 0xfe, 0xff, 0xfd, 0xfd, 0xfd, 0xff, 0xfd, 0xfd, 0xfd, 0xff, 0xff, 0xff,
0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xfd, 0xfd, 0xfd, 0xff, 0xff, 0xff,
0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff,
0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xfe, 0xfe, 0xfe, 0xff, 0xfd, 0xfd, 0xfd, 0xff, 0xfe, 0xfe,
0xfe, 0xff, 0xfd, 0xfd, 0xfd, 0xff, 0xff, 0xff, 0xff, 0xff, 0xfd, 0xfd, 0xfd, 0xee, 0xfd, 0xfd,
0xfd, 0xee, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xfe, 0xfe, 0xfe, 0xff, 0xfc, 0xfc,
0xfc, 0xff, 0xfe, 0xfe, 0xfe, 0xff, 0xfd, 0xfd, 0xfd, 0xff, 0xfe, 0xfe, 0xfe, 0xff, 0xff, 0xff,
0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xf9, 0xfb,
0xfc, 0xff, 0xd7, 0xdd, 0xe1, 0xff, 0xc7, 0xc3, 0xc2, 0xff, 0xce, 0xce, 0xce, 0xff, 0xe2, 0xe4,
0xe5, 0xff, 0xfd, 0xfc, 0xfc, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xfe, 0xfe,
0xfe, 0xff, 0xfd, 0xfd, 0xfd, 0xff, 0xff, 0xff, 0xff, 0xff, 0xfd, 0xfd, 0xfd, 0xee, 0xfb, 0xfb,
0xfb, 0xee, 0xff, 0xff, 0xff, 0xff, 0xfe, 0xfe, 0xfe, 0xff, 0xfd, 0xfd, 0xfd, 0xff, 0xff, 0xff,
0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xfd, 0xfd, 0xfd, 0xff, 0xfe, 0xfe,
0xfe, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xb0, 0xad, 0xad, 0xff, 0x3a, 0x89,
0xa8, 0xff, 0x03, 0xb5, 0xed, 0xff, 0x20, 0x57, 0x6c, 0xff, 0x36, 0x25, 0x1f, 0xff, 0x34, 0x52,
0x5e, 0xff, 0x4f, 0x65, 0x6e, 0xff, 0x8a, 0x86, 0x84, 0xff, 0xd8, 0xd8, 0xd8, 0xff, 0xff, 0xff,
0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xfc, 0xfc, 0xfc, 0xee, 0xfa, 0xfa,
0xfa, 0xee, 0xff, 0xff, 0xff, 0xff, 0xfd, 0xfd, 0xfd, 0xff, 0xfd, 0xfd, 0xfd, 0xff, 0xff, 0xff,
0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xfd, 0xfd, 0xfd, 0xff, 0xfc, 0xfc,
0xfc, 0xff, 0xff, 0xff, 0xff, 0xff, 0xb7, 0xb2, 0xb1, 0xff, 0x2a, 0x1d, 0x18, 0xff, 0x33, 0x2a,
0x26, 0xff, 0x25, 0x68, 0x7f, 0xff, 0x16, 0x90, 0xbe, 0xff, 0x3a, 0x38, 0x37, 0xff, 0x37, 0x38,
0x38, 0xff, 0x31, 0x35, 0x37, 0xff, 0x29, 0x28, 0x27, 0xff, 0x34, 0x34, 0x34, 0xff, 0x93, 0x93,
0x93, 0xff, 0xf3, 0xf3, 0xf3, 0xff, 0xff, 0xff, 0xff, 0xff, 0xfb, 0xfb, 0xfb, 0xee, 0xfd, 0xfd,
0xfd, 0xee, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xfe, 0xfe, 0xfe, 0xff, 0xfe, 0xfe,
0xfe, 0xff, 0xff, 0xff, 0xff, 0xff, 0xfe, 0xfe, 0xfe, 0xff, 0xfd, 0xfd, 0xfd, 0xff, 0xff, 0xff,
0xff, 0xff, 0xff, 0xfc, 0xf8, 0xff, 0x4f, 0xa0, 0xbf, 0xff, 0x0d, 0x8c, 0xb8, 0xff, 0x2c, 0x62,
0x76, 0xff, 0x3e, 0x31, 0x2e, 0xff, 0x36, 0x46, 0x4d, 0xff, 0x38, 0x41, 0x44, 0xff, 0x3b, 0x39,
0x38, 0xff, 0x37, 0x36, 0x35, 0xff, 0x2c, 0x2c, 0x2c, 0xff, 0x28, 0x28, 0x28, 0xff, 0x83, 0x83,
0x83, 0xff, 0x77, 0x77, 0x77, 0xff, 0xd5, 0xd5, 0xd5, 0xff, 0xfd, 0xfd, 0xfd, 0xee, 0xfd, 0xfd,
0xfd, 0xee, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xfe, 0xfe, 0xfe, 0xff, 0xfc, 0xfc,
0xfc, 0xff, 0xfd, 0xfd, 0xfd, 0xff, 0xfc, 0xfc, 0xfc, 0xff, 0xfe, 0xfe, 0xfe, 0xff, 0xff, 0xff,
0xff, 0xff, 0xff, 0xfd, 0xfb, 0xff, 0x5f, 0x98, 0xad, 0xff, 0x1a, 0x5c, 0x73, 0xff, 0x30, 0x5a,
0x6a, 0xff, 0x38, 0x42, 0x46, 0xff, 0x3c, 0x35, 0x33, 0xff, 0x39, 0x38, 0x37, 0xff, 0x2b, 0x2b,
0x2b, 0xff, 0x3c, 0x3c, 0x3c, 0xff, 0x83, 0x83, 0x83, 0xff, 0xc2, 0xc2, 0xc2, 0xff, 0xd2, 0xd2,
0xd2, 0xff, 0xa9, 0xa9, 0xa9, 0xff, 0x86, 0x86, 0x86, 0xff, 0xdf, 0xdf, 0xdf, 0xee, 0xfc, 0xfc,
0xfc, 0xee, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xfd, 0xfd, 0xfd, 0xff, 0xff, 0xff,
0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xfd, 0xfd, 0xfd, 0xff, 0xff, 0xff,
0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xc3, 0xba, 0xb7, 0xff, 0x2c, 0x21, 0x1d, 0xff, 0x38, 0x30,
0x2d, 0xff, 0x3c, 0x3a, 0x39, 0xff, 0x34, 0x35, 0x35, 0xff, 0x2e, 0x2e, 0x2e, 0xff, 0x78, 0x78,
0x78, 0xff, 0xdf, 0xdf, 0xdf, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff,
0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xfe, 0xfe, 0xfe, 0xff, 0xeb, 0xeb, 0xeb, 0xee, 0xfa, 0xfa,
0xfa, 0xee, 0xfe, 0xfe, 0xfe, 0xff, 0xfc, 0xfc, 0xfc, 0xff, 0xfd, 0xfd, 0xfd, 0xff, 0xff, 0xff,
0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xfd, 0xfd, 0xfd, 0xff, 0xfc, 0xfc,
0xfc, 0xff, 0xfd, 0xfd, 0xfd, 0xff, 0xff, 0xff, 0xff, 0xff, 0xb3, 0xb0, 0xaf, 0xff, 0x3d, 0x31,
0x2c, 0xff, 0x33, 0x30, 0x2f, 0xff, 0x49, 0x4a, 0x4a, 0xff, 0xcb, 0xcb, 0xcb, 0xff, 0xff, 0xff,
0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xfd, 0xfd, 0xfd, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff,
0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xfd, 0xfd, 0xfd, 0xee, 0xfc, 0xfc,
0xfc, 0xee, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xfd, 0xfd, 0xfd, 0xff, 0xff, 0xff,
0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff,
0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xd3, 0xe2, 0xe8, 0xff, 0x1c, 0x85,
0xae, 0xff, 0x2f, 0x44, 0x4c, 0xff, 0x41, 0x3c, 0x3a, 0xff, 0x9a, 0x9a, 0x9a, 0xff, 0xf9, 0xf9,
0xf9, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff,
0xff, 0xff, 0xf9, 0xf9, 0xf9, 0xff, 0xf8, 0xf8, 0xf8, 0xff, 0xfd, 0xfd, 0xfd, 0xee, 0xfd, 0xfd,
0xfd, 0xee, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xfe, 0xfe, 0xfe, 0xff, 0xff, 0xff,
0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xf8, 0xf8, 0xf8, 0xff, 0xf5, 0xf5,
0xf5, 0xff, 0xf9, 0xf9, 0xf9, 0xff, 0xff, 0xff, 0xff, 0xff, 0x8a, 0xd0, 0xea, 0xff, 0x00, 0xb0,
0xf7, 0xff, 0x36, 0x49, 0x51, 0xff, 0x39, 0x33, 0x31, 0xff, 0x1f, 0x1f, 0x1f, 0xff, 0x98, 0x98,
0x98, 0xff, 0xe2, 0xe2, 0xe2, 0xff, 0x9b, 0x9b, 0x9b, 0xff, 0x71, 0x71, 0x71, 0xff, 0x72, 0x72,
0x72, 0xff, 0x63, 0x63, 0x63, 0xff, 0xef, 0xef, 0xef, 0xff, 0xfd, 0xfd, 0xfd, 0xee, 0xfd, 0xfd,
0xfd, 0xee, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xf4, 0xf4,
0xf4, 0xff, 0xae, 0xae, 0xae, 0xff, 0x8c, 0x8c, 0x8c, 0xff, 0x86, 0x86, 0x86, 0xff, 0x84, 0x84,
0x84, 0xff, 0x86, 0x86, 0x86, 0xff, 0x91, 0x8a, 0x87, 0xff, 0x48, 0x7a, 0x8d, 0xff, 0x00, 0x9c,
0xd7, 0xff, 0x3a, 0x3e, 0x3f, 0xff, 0x39, 0x36, 0x35, 0xff, 0x35, 0x35, 0x35, 0xff, 0x42, 0x42,
0x42, 0xff, 0x3b, 0x3b, 0x3b, 0xff, 0x31, 0x31, 0x31, 0xff, 0x92, 0x92, 0x92, 0xff, 0x90, 0x90,
0x90, 0xff, 0x7b, 0x7b, 0x7b, 0xff, 0xff, 0xff, 0xff, 0xff, 0xfd, 0xfd, 0xfd, 0xee, 0xfb, 0xfb,
0xfb, 0xee, 0xfe, 0xfe, 0xfe, 0xff, 0xff, 0xff, 0xff, 0xff, 0xde, 0xde, 0xde, 0xff, 0x80, 0x80,
0x80, 0xff, 0xb1, 0xb1, 0xb1, 0xff, 0xe6, 0xe6, 0xe6, 0xff, 0xf9, 0xf9, 0xf9, 0xff, 0xff, 0xff,
0xff, 0xff, 0xea, 0xea, 0xea, 0xff, 0x81, 0x80, 0x80, 0xff, 0x49, 0x42, 0x40, 0xff, 0x55, 0x8e,
0xa3, 0xff, 0x1f, 0x5b, 0x72, 0xff, 0x35, 0x3a, 0x3c, 0xff, 0x43, 0x41, 0x41, 0xff, 0x35, 0x35,
0x35, 0xff, 0x2a, 0x2a, 0x2a, 0xff, 0xbe, 0xbe, 0xbe, 0xff, 0xe8, 0xe8, 0xe8, 0xff, 0x6f, 0x6f,
0x6f, 0xff, 0xe7, 0xe7, 0xe7, 0xff, 0xff, 0xff, 0xff, 0xff, 0xfb, 0xfb, 0xfb, 0xee, 0xfb, 0xfb,
0xfb, 0xee, 0xff, 0xff, 0xff, 0xff, 0xf5, 0xf5, 0xf5, 0xff, 0x7b, 0x7b, 0x7b, 0xff, 0xe0, 0xe0,
0xe0, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xf8, 0xf8, 0xf8, 0xff, 0xb8, 0xb8,
0xb8, 0xff, 0x7d, 0x7d, 0x7d, 0xff, 0xa3, 0xa3, 0xa3, 0xff, 0xd2, 0xd2, 0xd2, 0xff, 0x87, 0x7c,
0x77, 0xff, 0x5a, 0x57, 0x55, 0xff, 0xca, 0xcb, 0xcb, 0xff, 0x82, 0x82, 0x82, 0xff, 0x23, 0x23,
0x23, 0xff, 0x38, 0x38, 0x38, 0xff, 0x43, 0x43, 0x43, 0xff, 0x5d, 0x5d, 0x5d, 0xff, 0xd9, 0xd9,
0xd9, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xfc, 0xfc, 0xfc, 0xee, 0xfd, 0xfd,
0xfd, 0xee, 0xff, 0xff, 0xff, 0xff, 0xa1, 0xa1, 0xa1, 0xff, 0xb6, 0xb6, 0xb6, 0xff, 0xff, 0xff,
0xff, 0xff, 0xfb, 0xfb, 0xfb, 0xff, 0xdb, 0xdb, 0xdb, 0xff, 0xb1, 0xb1, 0xb1, 0xff, 0xc7, 0xc7,
0xc7, 0xff, 0xea, 0xea, 0xea, 0xff, 0xa6, 0xa6, 0xa6, 0xff, 0x60, 0x60, 0x60, 0xff, 0x9f, 0x9f,
0x9f, 0xff, 0xfd, 0xfd, 0xfd, 0xff, 0xff, 0xff, 0xff, 0xff, 0xd1, 0xd1, 0xd1, 0xff, 0x4e, 0x4e,
0x4e, 0xff, 0x29, 0x29, 0x29, 0xff, 0x73, 0x73, 0x73, 0xff, 0xeb, 0xeb, 0xeb, 0xff, 0xff, 0xff,
0xff, 0xff, 0xfd, 0xfd, 0xfd, 0xff, 0xff, 0xff, 0xff, 0xff, 0xfd, 0xfd, 0xfd, 0xee, 0xfd, 0xfd,
0xfd, 0xee, 0xec, 0xec, 0xec, 0xff, 0x90, 0x90, 0x90, 0xff, 0xff, 0xff, 0xff, 0xff, 0xfe, 0xfe,
0xfe, 0xff, 0xf3, 0xf3, 0xf3, 0xff, 0xf0, 0xf0, 0xf0, 0xff, 0xff, 0xff, 0xff, 0xff, 0xb7, 0xb7,
0xb7, 0xff, 0x61, 0x61, 0x61, 0xff, 0x89, 0x89, 0x89, 0xff, 0xeb, 0xeb, 0xeb, 0xff, 0xff, 0xff,
0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xfc, 0xfc, 0xfc, 0xff, 0xdc, 0xdc, 0xdc, 0xff, 0x99, 0x99,
0x99, 0xff, 0xbc, 0xbc, 0xbc, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xfe, 0xfe,
0xfe, 0xff, 0xfd, 0xfd, 0xfd, 0xff, 0xff, 0xff, 0xff, 0xff, 0xfd, 0xfd, 0xfd, 0xee, 0xfd, 0xfd,
0xfd, 0xee, 0x98, 0x98, 0x98, 0xff, 0x9c, 0x9c, 0x9c, 0xff, 0xf9, 0xf9, 0xf9, 0xff, 0xff, 0xff,
0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xc5, 0xc5, 0xc5, 0xff, 0x66, 0x66, 0x66, 0xff, 0x76, 0x76,
0x76, 0xff, 0xdb, 0xdb, 0xdb, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff,
0xff, 0xff, 0xfb, 0xfb, 0xfb, 0xff, 0xdd, 0xdd, 0xdd, 0xff, 0xcd, 0xcd, 0xcd, 0xff, 0xf7, 0xf7,
0xf7, 0xff, 0xff, 0xff, 0xff, 0xff, 0xfe, 0xfe, 0xfe, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff,
0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xfc, 0xfc, 0xfc, 0xee, 0xda, 0xda,
0xda, 0xee, 0x48, 0x48, 0x48, 0xff, 0x75, 0x75, 0x75, 0xff, 0xff, 0xff, 0xff, 0xff, 0xd5, 0xd5,
0xd5, 0xff, 0x72, 0x72, 0x72, 0xff, 0x6a, 0x6a, 0x6a, 0xff, 0xc8, 0xc8, 0xc8, 0xff, 0xff, 0xff,
0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xfc, 0xfc, 0xfc, 0xff, 0xfe, 0xfe, 0xfe, 0xff, 0xff, 0xff,
0xff, 0xff, 0xfd, 0xfd, 0xfd, 0xff, 0xfe, 0xfe, 0xfe, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff,
0xff, 0xff, 0xfd, 0xfd, 0xfd, 0xff, 0xfd, 0xfd, 0xfd, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff,
0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xfb, 0xfb, 0xfb, 0xee, 0xeb, 0xeb,
0xeb, 0xee, 0xaf, 0xaf, 0xaf, 0xff, 0xb0, 0xb0, 0xb0, 0xff, 0x8b, 0x8b, 0x8b, 0xff, 0x60, 0x60,
0x60, 0xff, 0xb3, 0xb3, 0xb3, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff,
0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xfd, 0xfd, 0xfd, 0xff, 0xfe, 0xfe,
0xfe, 0xff, 0xff, 0xff, 0xff, 0xff, 0xfd, 0xfd, 0xfd, 0xff, 0xfe, 0xfe, 0xfe, 0xff, 0xff, 0xff,
0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xfd, 0xfd, 0xfd, 0xff, 0xfe, 0xfe, 0xfe, 0xff, 0xff, 0xff,
0xff, 0xff, 0xfe, 0xfe, 0xfe, 0xff, 0xff, 0xff, 0xff, 0xff, 0xfd, 0xfd, 0xfd, 0xee, 0xfd, 0xfd,
0xfd, 0xee, 0x66, 0x66, 0x66, 0xff, 0x54, 0x54, 0x54, 0xff, 0xa0, 0xa0, 0xa0, 0xff, 0xfa, 0xfa,
0xfa, 0xff, 0xff, 0xff, 0xff, 0xff, 0xfe, 0xfe, 0xfe, 0xff, 0xfe, 0xfe, 0xfe, 0xff, 0xff, 0xff,
0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xfd, 0xfd, 0xfd, 0xff, 0xfd, 0xfd,
0xfd, 0xff, 0xfd, 0xfd, 0xfd, 0xff, 0xfc, 0xfc, 0xfc, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff,
0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xfe, 0xfe, 0xfe, 0xff, 0xfc, 0xfc, 0xfc, 0xff, 0xfd, 0xfd,
0xfd, 0xff, 0xfc, 0xfc, 0xfc, 0xff, 0xff, 0xff, 0xff, 0xff, 0xfd, 0xfd, 0xfd, 0xee, 0xce, 0xce,
0xce, 0xee, 0x98, 0x98, 0x98, 0xff, 0xef, 0xef, 0xef, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff,
0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xfd, 0xfd, 0xfd, 0xff, 0xff, 0xff,
0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xfe, 0xfe, 0xfe, 0xff, 0xfd, 0xfd, 0xfd, 0xff, 0xff, 0xff,
0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xfe, 0xfe, 0xfe, 0xff, 0xfe, 0xfe, 0xfe, 0xff, 0xff, 0xff,
0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xfd, 0xfd, 0xfd, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff,
0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xfd, 0xfd, 0xfd, 0xee, 0xf6, 0xf6,
0xf6, 0xf4, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff,
0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff,
0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff,
0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff,
0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff,
0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xfb, 0xfb, 0xfb, 0xf4, 0xfd, 0xfd,
0xfd, 0xde, 0xfd, 0xfd, 0xfd, 0xee, 0xfd, 0xfd, 0xfd, 0xee, 0xfc, 0xfc, 0xfc, 0xee, 0xfd, 0xfd,
0xfd, 0xee, 0xfd, 0xfd, 0xfd, 0xee, 0xfd, 0xfd, 0xfd, 0xee, 0xfc, 0xfc, 0xfc, 0xee, 0xfd, 0xfd,
0xfd, 0xee, 0xfd, 0xfd, 0xfd, 0xee, 0xfd, 0xfd, 0xfd, 0xee, 0xfc, 0xfc, 0xfc, 0xee, 0xfd, 0xfd,
0xfd, 0xee, 0xfd, 0xfd, 0xfd, 0xee, 0xfc, 0xfc, 0xfc, 0xee, 0xfc, 0xfc, 0xfc, 0xee, 0xfd, 0xfd,
0xfd, 0xee, 0xfd, 0xfd, 0xfd, 0xee, 0xfb, 0xfb, 0xfb, 0xee, 0xfd, 0xfd, 0xfd, 0xee, 0xfd, 0xfd,
0xfd, 0xee, 0xfd, 0xfd, 0xfd, 0xee, 0xfd, 0xfd, 0xfd, 0xee, 0xfd, 0xfd, 0xfd, 0xde,
};
#define ICON_SIZE (sizeof(icon_file))

View File

@ -21,7 +21,7 @@
/*
* Author: jflyper (https://github.com/jflyper)
*/
#include "platform.h"
#include "common/time.h"

View File

@ -41,7 +41,7 @@
#define STORAGE_LUN_NBR 1
static const uint8_t STORAGE_Inquirydata[] =
static const uint8_t STORAGE_Inquirydata[] =
{
0x00, 0x80, 0x02, 0x02,
#ifdef USE_HAL_DRIVER

View File

@ -2389,7 +2389,7 @@ static mspResult_e mspProcessInCommand(mspDescriptor_t srcDesc, int16_t cmdMSP,
case MSP_SET_RESET_CURR_PID:
resetPidProfile(currentPidProfile);
break;
case MSP_SET_SENSOR_ALIGNMENT: {
// maintain backwards compatibility for API < 1.41
const uint8_t gyroAlignment = sbufReadU8(src);
@ -2537,7 +2537,7 @@ static mspResult_e mspProcessInCommand(mspDescriptor_t srcDesc, int16_t cmdMSP,
sbufReadU16(src);
#endif
}
// reinitialize the gyro filters with the new values
validateAndFixGyroConfig();

View File

@ -43,7 +43,7 @@ void pgResetFn_motorConfig(motorConfig_t *motorConfig)
motorConfig->dev.motorPwmProtocol = PWM_TYPE_BRUSHED;
motorConfig->dev.useUnsyncedPwm = true;
#else
#ifdef USE_BRUSHED_ESC_AUTODETECT
#ifdef USE_BRUSHED_ESC_AUTODETECT
if (getDetectedMotorType() == MOTOR_BRUSHED) {
motorConfig->minthrottle = 1000;
motorConfig->dev.motorPwmRate = BRUSHED_MOTORS_PWM_RATE;
@ -51,7 +51,7 @@ void pgResetFn_motorConfig(motorConfig_t *motorConfig)
motorConfig->dev.useUnsyncedPwm = true;
} else
#endif // USE_BRUSHED_ESC_AUTODETECT
{
{
motorConfig->minthrottle = 1070;
motorConfig->dev.motorPwmRate = BRUSHLESS_MOTORS_PWM_RATE;
motorConfig->dev.motorPwmProtocol = PWM_TYPE_ONESHOT125;
@ -68,10 +68,10 @@ void pgResetFn_motorConfig(motorConfig_t *motorConfig)
#ifdef USE_TIMER
for (int motorIndex = 0; motorIndex < MAX_SUPPORTED_MOTORS; motorIndex++) {
motorConfig->dev.ioTags[motorIndex] = timerioTagGetByUsage(TIM_USE_MOTOR, motorIndex);
motorConfig->dev.ioTags[motorIndex] = timerioTagGetByUsage(TIM_USE_MOTOR, motorIndex);
}
#endif
motorConfig->motorPoleCount = 14; // Most brushes motors that we use are 14 poles
#ifdef USE_DSHOT_BITBANG

View File

@ -45,7 +45,7 @@ typedef void (pgResetFunc)(void * /* base */);
typedef struct pgRegistry_s {
pgn_t pgn; // The parameter group number, the top 4 bits are reserved for version
uint8_t length; // The number of elements in the group
uint8_t length; // The number of elements in the group
uint16_t size; // Size of the group in RAM, the top 4 bits are reserved for flags
uint8_t *address; // Address of the group in RAM.
uint8_t *copy; // Address of the copy in RAM.

View File

@ -207,7 +207,7 @@ static void crsfCheckRssi(uint32_t currentTimeUs) {
#ifdef USE_RX_LINK_QUALITY_INFO
if (linkQualitySource == LQ_SOURCE_RX_PROTOCOL_CRSF) {
setLinkQualityDirect(0);
rxSetRfMode(0);
rxSetRfMode(0);
}
#endif
}

View File

@ -244,11 +244,11 @@ bool srxl2ProcessControlData(const Srxl2Header* header, rxRuntimeState_t *rxRunt
bool srxl2ProcessPacket(const Srxl2Header* header, rxRuntimeState_t *rxRuntimeState)
{
switch (header->packetType) {
case Handshake:
case Handshake:
return srxl2ProcessHandshake(header);
case ControlData:
case ControlData:
return srxl2ProcessControlData(header, rxRuntimeState);
default:
default:
DEBUG_PRINTF("Other packet type, ID: %x \r\n", header->packetType);
break;
}
@ -474,7 +474,7 @@ void srxl2RxWriteData(const void *data, int len)
const uint16_t crc = crc16_ccitt_update(0, (uint8_t*)data, len - 2);
((uint8_t*)data)[len-2] = ((uint8_t *) &crc)[1] & 0xFF;
((uint8_t*)data)[len-1] = ((uint8_t *) &crc)[0] & 0xFF;
len = MIN(len, (int)sizeof(writeBuffer));
memcpy(writeBuffer, data, len);
writeBufferIdx = len;

View File

@ -353,7 +353,7 @@ bool accInit(uint16_t accSampleRateHz)
#ifdef USE_MULTI_GYRO
if (gyroConfig()->gyro_to_use == GYRO_CONFIG_USE_GYRO_2) {
alignment = gyroDeviceConfig(1)->alignment;
customAlignment = &gyroDeviceConfig(1)->customAlignment;
}
#endif

View File

@ -59,7 +59,7 @@ typedef struct batteryConfig_s {
uint8_t vbathysteresis; // hysteresis for alarm, default 1 = 0.1V
uint16_t vbatfullcellvoltage; // Cell voltage at which the battery is deemed to be "full" 0.01V units, default is 410 (4.1V)
uint8_t forceBatteryCellCount; // Number of cells in battery, used for overwriting auto-detected cell count if someone has issues with it.
uint8_t vbatLpfPeriod; // Period of the cutoff frequency for the Vbat filter (in 0.1 s)
uint8_t ibatLpfPeriod; // Period of the cutoff frequency for the Ibat filter (in 0.1 s)

View File

@ -147,7 +147,7 @@ bool compassDetect(magDev_t *dev, uint8_t *alignment)
if (!instance) {
return false;
}
busdev->bustype = BUSTYPE_SPI;
spiBusSetInstance(busdev, instance);
busdev->busdev_u.spi.csnPin = IOGetByTag(compassConfig()->mag_spi_csn);
@ -310,7 +310,7 @@ bool compassInit(void)
if (compassConfig()->mag_alignment != ALIGN_DEFAULT) {
magDev.magAlignment = compassConfig()->mag_alignment;
}
buildRotationMatrixFromAlignment(&compassConfig()->mag_customAlignment, &magDev.rotationMatrix);
return true;

View File

@ -163,7 +163,7 @@ PG_REGISTER_WITH_RESET_FN(gyroConfig_t, gyroConfig, PG_GYRO_CONFIG, 8);
#endif
void pgResetFn_gyroConfig(gyroConfig_t *gyroConfig)
{
{
gyroConfig->gyroCalibrationDuration = 125; // 1.25 seconds
gyroConfig->gyroMovementCalibrationThreshold = 48;
gyroConfig->gyro_hardware_lpf = GYRO_HARDWARE_LPF_NORMAL;
@ -595,7 +595,7 @@ static void dynLpfFilterInit()
default:
dynLpfFilter = DYN_LPF_NONE;
break;
}
}
} else {
dynLpfFilter = DYN_LPF_NONE;
}
@ -937,7 +937,7 @@ FAST_CODE int32_t gyroSlewLimiter(gyroSensor_t *gyroSensor, int axis)
#ifdef USE_GYRO_OVERFLOW_CHECK
static FAST_CODE_NOINLINE void handleOverflow(timeUs_t currentTimeUs)
{
// This will need to be revised if we ever allow different sensor types to be
// This will need to be revised if we ever allow different sensor types to be
// used simultaneously. In that case the scale might be different between sensors.
// It's complicated by the fact that we're using filtered gyro data here which is
// after both sensors are scaled and averaged.
@ -970,7 +970,7 @@ static FAST_CODE void checkForOverflow(timeUs_t currentTimeUs)
// check for overflow in the axes set in overflowAxisMask
gyroOverflow_e overflowCheck = GYRO_OVERFLOW_NONE;
// This will need to be revised if we ever allow different sensor types to be
// This will need to be revised if we ever allow different sensor types to be
// used simultaneously. In that case the scale might be different between sensors.
// It's complicated by the fact that we're using filtered gyro data here which is
// after both sensors are scaled and averaged.

View File

@ -776,7 +776,7 @@ void initSrxlTelemetry(void)
// and feature is enabled, if so, set SRXL telemetry enabled
if (srxlRxIsActive()) {
srxlTelemetryEnabled = true;
srxl2 = false;
srxl2 = false;
#if defined(USE_SERIALRX_SRXL2)
} else if (srxl2RxIsActive()) {
srxlTelemetryEnabled = true;