mirror of
https://github.com/iNavFlight/inav.git
synced 2025-07-19 06:15:14 +03:00
Whitespace tidy
This commit is contained in:
parent
f4850845df
commit
fd7d770fb1
101 changed files with 448 additions and 448 deletions
|
@ -91,7 +91,7 @@ PG_RESET_TEMPLATE(blackboxConfig_t, blackboxConfig,
|
|||
.rate_denom = 1,
|
||||
#ifdef SDCARD_DETECT_INVERTED
|
||||
.invertedCardDetection = 1,
|
||||
#else
|
||||
#else
|
||||
.invertedCardDetection = 0,
|
||||
#endif
|
||||
);
|
||||
|
|
|
@ -31,7 +31,7 @@ void assertFailed2(const char * file, int line)
|
|||
assertFailureLine = line;
|
||||
}
|
||||
#if defined(USE_ASSERT_STOP)
|
||||
while(1) {
|
||||
while (1) {
|
||||
__asm("BKPT #0\n") ; // Break into the debugger
|
||||
}
|
||||
#endif
|
||||
|
@ -44,7 +44,7 @@ void assertFailed1(int line)
|
|||
assertFailureLine = line;
|
||||
}
|
||||
#if defined(USE_ASSERT_STOP)
|
||||
while(1) {
|
||||
while (1) {
|
||||
__asm("BKPT #0\n") ; // Break into the debugger
|
||||
}
|
||||
#endif
|
||||
|
|
|
@ -326,8 +326,8 @@ void arraySubInt32(int32_t *dest, int32_t *array1, int32_t *array2, int count)
|
|||
*/
|
||||
void sensorCalibrationResetState(sensorCalibrationState_t * state)
|
||||
{
|
||||
for(int i = 0; i < 4; i++){
|
||||
for(int j = 0; j < 4; j++){
|
||||
for (int i = 0; i < 4; i++){
|
||||
for (int j = 0; j < 4; j++){
|
||||
state->XtX[i][j] = 0;
|
||||
}
|
||||
|
||||
|
|
|
@ -87,7 +87,7 @@ extern const uint8_t __pg_resetdata_end[];
|
|||
|
||||
#define PG_FOREACH_PROFILE(_name) \
|
||||
PG_FOREACH(_name) \
|
||||
if(pgIsSystem(_name)) \
|
||||
if (pgIsSystem(_name)) \
|
||||
continue; \
|
||||
else \
|
||||
/**/
|
||||
|
@ -98,7 +98,7 @@ extern const uint8_t __pg_resetdata_end[];
|
|||
do { \
|
||||
extern const pgRegistry_t _name ##_Registry; \
|
||||
pgResetCurrent(&_name ## _Registry); \
|
||||
} while(0) \
|
||||
} while (0) \
|
||||
/**/
|
||||
|
||||
// Declare system config
|
||||
|
|
|
@ -126,7 +126,7 @@ void adcHardwareInit(drv_adc_config_t *init)
|
|||
for (int i = ADC_CHN_1; i < ADC_CHN_COUNT; i++) {
|
||||
if (!adcConfig[i].tag)
|
||||
continue;
|
||||
|
||||
|
||||
adcDevice_t * adc = &adcHardware[adcConfig[i].adcDevice];
|
||||
|
||||
IOInit(IOGetByTag(adcConfig[i].tag), OWNER_ADC, RESOURCE_ADC_CH1 + (i - ADC_CHN_1), 0);
|
||||
|
|
|
@ -180,7 +180,7 @@ void adcHardwareInit(drv_adc_config_t *init)
|
|||
for (int i = ADC_CHN_1; i < ADC_CHN_COUNT; i++) {
|
||||
if (!adcConfig[i].tag)
|
||||
continue;
|
||||
|
||||
|
||||
adcDevice_t * adc = &adcHardware[adcConfig[i].adcDevice];
|
||||
|
||||
IOInit(IOGetByTag(adcConfig[i].tag), OWNER_ADC, RESOURCE_ADC_CH1 + (i - ADC_CHN_1), 0);
|
||||
|
|
|
@ -154,7 +154,7 @@ void adcHardwareInit(drv_adc_config_t *init)
|
|||
for (int i = ADC_CHN_1; i < ADC_CHN_COUNT; i++) {
|
||||
if (!adcConfig[i].tag)
|
||||
continue;
|
||||
|
||||
|
||||
adcDevice_t * adc = &adcHardware[adcConfig[i].adcDevice];
|
||||
|
||||
IOInit(IOGetByTag(adcConfig[i].tag), OWNER_ADC, RESOURCE_ADC_CH1 + (i - ADC_CHN_1), 0);
|
||||
|
|
|
@ -152,7 +152,7 @@ static void adcInstanceInit(ADCDevice adcDevice)
|
|||
|
||||
//HAL_CLEANINVALIDATECACHE((uint32_t*)&adcValues[adcDevice], configuredAdcChannels);
|
||||
/*##-4- Start the conversion process #######################################*/
|
||||
if(HAL_ADC_Start_DMA(&adc->ADCHandle, (uint32_t*)&adcValues[adcDevice], adc->usedChannelCount) != HAL_OK)
|
||||
if (HAL_ADC_Start_DMA(&adc->ADCHandle, (uint32_t*)&adcValues[adcDevice], adc->usedChannelCount) != HAL_OK)
|
||||
{
|
||||
/* Start Conversation Error */
|
||||
}
|
||||
|
@ -166,7 +166,7 @@ void adcHardwareInit(drv_adc_config_t *init)
|
|||
for (int i = ADC_CHN_1; i < ADC_CHN_COUNT; i++) {
|
||||
if (!adcConfig[i].tag)
|
||||
continue;
|
||||
|
||||
|
||||
adcDevice_t * adc = &adcHardware[adcConfig[i].adcDevice];
|
||||
|
||||
IOInit(IOGetByTag(adcConfig[i].tag), OWNER_ADC, RESOURCE_ADC_CH1 + (i - ADC_CHN_1), 0);
|
||||
|
|
|
@ -143,18 +143,18 @@ static void bmp280_start_up(void)
|
|||
static void bmp280_get_up(void)
|
||||
{
|
||||
uint8_t data[BMP280_DATA_FRAME_SIZE];
|
||||
|
||||
|
||||
//error free measurements
|
||||
static int32_t bmp280_up_valid;
|
||||
static int32_t bmp280_ut_valid;
|
||||
|
||||
|
||||
//read data from sensor
|
||||
bool ack = i2cRead(BARO_I2C_INSTANCE, BMP280_I2C_ADDR, BMP280_PRESSURE_MSB_REG, BMP280_DATA_FRAME_SIZE, data);
|
||||
|
||||
|
||||
//check if pressure and temperature readings are valid, otherwise use previous measurements from the moment
|
||||
|
||||
if(ack){
|
||||
|
||||
if (ack){
|
||||
|
||||
bmp280_up = (int32_t)((((uint32_t)(data[0])) << 12) | (((uint32_t)(data[1])) << 4) | ((uint32_t)data[2] >> 4));
|
||||
bmp280_ut = (int32_t)((((uint32_t)(data[3])) << 12) | (((uint32_t)(data[4])) << 4) | ((uint32_t)data[5] >> 4));
|
||||
|
||||
|
@ -165,10 +165,10 @@ static void bmp280_get_up(void)
|
|||
{
|
||||
//assign previous valid measurements
|
||||
bmp280_up= bmp280_up_valid;
|
||||
bmp280_ut= bmp280_ut_valid;
|
||||
bmp280_ut= bmp280_ut_valid;
|
||||
}
|
||||
|
||||
|
||||
|
||||
|
||||
}
|
||||
#endif
|
||||
|
||||
|
|
|
@ -251,7 +251,7 @@ bool ms56xxDetect(baroDev_t *baro, baroSensor_e baroType)
|
|||
}
|
||||
#elif defined(USE_BARO_MS5607)
|
||||
baro->calculate = ms5607_calculate;
|
||||
#else
|
||||
#else
|
||||
baro->calculate = ms5611_calculate;
|
||||
#endif
|
||||
|
||||
|
|
|
@ -183,12 +183,12 @@ bool i2cWriteBuffer(I2CDevice device, uint8_t addr_, uint8_t reg_, uint8_t len_,
|
|||
|
||||
HAL_StatusTypeDef status;
|
||||
|
||||
if(reg_ == 0xFF)
|
||||
if (reg_ == 0xFF)
|
||||
status = HAL_I2C_Master_Transmit(&i2cHandle[device].Handle,addr_ << 1,data, len_, I2C_DEFAULT_TIMEOUT);
|
||||
else
|
||||
status = HAL_I2C_Mem_Write(&i2cHandle[device].Handle,addr_ << 1, reg_, I2C_MEMADD_SIZE_8BIT,data, len_, I2C_DEFAULT_TIMEOUT);
|
||||
|
||||
if(status != HAL_OK)
|
||||
if (status != HAL_OK)
|
||||
return i2cHandleHardwareFailure(device);
|
||||
|
||||
return true;
|
||||
|
@ -212,12 +212,12 @@ bool i2cRead(I2CDevice device, uint8_t addr_, uint8_t reg_, uint8_t len, uint8_t
|
|||
|
||||
HAL_StatusTypeDef status;
|
||||
|
||||
if(reg_ == 0xFF)
|
||||
if (reg_ == 0xFF)
|
||||
status = HAL_I2C_Master_Receive(&i2cHandle[device].Handle,addr_ << 1,buf, len, I2C_DEFAULT_TIMEOUT);
|
||||
else
|
||||
status = HAL_I2C_Mem_Read(&i2cHandle[device].Handle,addr_ << 1, reg_, I2C_MEMADD_SIZE_8BIT,buf, len, I2C_DEFAULT_TIMEOUT);
|
||||
|
||||
if(status != HAL_OK)
|
||||
if (status != HAL_OK)
|
||||
return i2cHandleHardwareFailure(device);
|
||||
|
||||
return true;
|
||||
|
|
|
@ -142,7 +142,7 @@ void spiInitDevice(SPIDevice device)
|
|||
IOInit(IOGetByTag(spi->mosi), OWNER_SPI, RESOURCE_SPI_MOSI, device + 1);
|
||||
|
||||
#if defined(STM32F3) || defined(STM32F4) || defined(STM32F7)
|
||||
if(spi->sdcard == true)
|
||||
if (spi->sdcard == true)
|
||||
IOConfigGPIOAF(IOGetByTag(spi->sck), SPI_IO_AF_SCK_CFG_LOW, spi->af);
|
||||
else
|
||||
IOConfigGPIOAF(IOGetByTag(spi->sck), SPI_IO_AF_SCK_CFG_HIGH, spi->af);
|
||||
|
@ -255,7 +255,7 @@ uint8_t spiTransferByte(SPI_TypeDef *instance, uint8_t in)
|
|||
bool spiIsBusBusy(SPI_TypeDef *instance)
|
||||
{
|
||||
SPIDevice device = spiDeviceByInstance(instance);
|
||||
if(spiHardwareMap[device].hspi.State == HAL_SPI_STATE_BUSY)
|
||||
if (spiHardwareMap[device].hspi.State == HAL_SPI_STATE_BUSY)
|
||||
return true;
|
||||
else
|
||||
return false;
|
||||
|
@ -268,11 +268,11 @@ bool spiTransfer(SPI_TypeDef *instance, uint8_t *out, const uint8_t *in, int len
|
|||
|
||||
#define SPI_DEFAULT_TIMEOUT 10
|
||||
|
||||
if(!out) // Tx only
|
||||
if (!out) // Tx only
|
||||
{
|
||||
status = HAL_SPI_Transmit(&spiHardwareMap[device].hspi, (uint8_t *)in, len, SPI_DEFAULT_TIMEOUT);
|
||||
}
|
||||
else if(!in) // Rx only
|
||||
else if (!in) // Rx only
|
||||
{
|
||||
status = HAL_SPI_Receive(&spiHardwareMap[device].hspi, out, len, SPI_DEFAULT_TIMEOUT);
|
||||
}
|
||||
|
@ -281,7 +281,7 @@ bool spiTransfer(SPI_TypeDef *instance, uint8_t *out, const uint8_t *in, int len
|
|||
status = HAL_SPI_TransmitReceive(&spiHardwareMap[device].hspi, (uint8_t *)in, out, len, SPI_DEFAULT_TIMEOUT);
|
||||
}
|
||||
|
||||
if( status != HAL_OK)
|
||||
if ( status != HAL_OK)
|
||||
spiTimeoutUserCallback(instance);
|
||||
|
||||
return true;
|
||||
|
|
|
@ -70,7 +70,7 @@ void softSpiInit(const softSPIDevice_t *dev)
|
|||
|
||||
uint8_t softSpiTransferByte(const softSPIDevice_t *dev, uint8_t byte)
|
||||
{
|
||||
for(int ii = 0; ii < 8; ++ii) {
|
||||
for (int ii = 0; ii < 8; ++ii) {
|
||||
if (byte & 0x80) {
|
||||
IOHi(IOGetByTag(dev->mosiTag));
|
||||
} else {
|
||||
|
|
|
@ -104,7 +104,7 @@ typedef enum {
|
|||
|
||||
static queuedReadState_t queuedRead = { false, 0, 0};
|
||||
|
||||
/* We have AK8963 connected internally to MPU9250 I2C master. Accessing the compass sensor requires
|
||||
/* We have AK8963 connected internally to MPU9250 I2C master. Accessing the compass sensor requires
|
||||
* setting up the MPU's I2C host. We have separate implementation of SPI read/write functions to access
|
||||
* the MPU registers
|
||||
*/
|
||||
|
|
|
@ -193,7 +193,7 @@ void i2c_OLED_clear_display(void)
|
|||
i2c_OLED_send_cmd(0x40); // Display start line register to 0
|
||||
i2c_OLED_send_cmd(0); // Set low col address to 0
|
||||
i2c_OLED_send_cmd(0x10); // Set high col address to 0
|
||||
for(uint16_t i = 0; i < 1024; i++) { // fill the display's RAM with graphic... 128*64 pixel picture
|
||||
for (uint16_t i = 0; i < 1024; i++) { // fill the display's RAM with graphic... 128*64 pixel picture
|
||||
i2c_OLED_send_byte(0x00); // clear
|
||||
}
|
||||
i2c_OLED_send_cmd(0x81); // Setup CONTRAST CONTROL, following byte is the contrast Value... always a 2 byte instruction
|
||||
|
@ -207,7 +207,7 @@ void i2c_OLED_clear_display_quick(void)
|
|||
i2c_OLED_send_cmd(0x40); // Display start line register to 0
|
||||
i2c_OLED_send_cmd(0); // Set low col address to 0
|
||||
i2c_OLED_send_cmd(0x10); // Set high col address to 0
|
||||
for(uint16_t i = 0; i < 1024; i++) { // fill the display's RAM with graphic... 128*64 pixel picture
|
||||
for (uint16_t i = 0; i < 1024; i++) { // fill the display's RAM with graphic... 128*64 pixel picture
|
||||
i2c_OLED_send_byte(0x00); // clear
|
||||
}
|
||||
}
|
||||
|
|
|
@ -63,7 +63,7 @@ typedef enum {
|
|||
dmaDescriptors[i].irqHandlerCallback(&dmaDescriptors[i]);\
|
||||
}
|
||||
|
||||
#define DMA_CLEAR_FLAG(d, flag) if(d->flagsShift > 31) d->dma->HIFCR = (flag << (d->flagsShift - 32)); else d->dma->LIFCR = (flag << d->flagsShift)
|
||||
#define DMA_CLEAR_FLAG(d, flag) if (d->flagsShift > 31) d->dma->HIFCR = (flag << (d->flagsShift - 32)); else d->dma->LIFCR = (flag << d->flagsShift)
|
||||
#define DMA_GET_FLAG_STATUS(d, flag) (d->flagsShift > 31 ? d->dma->HISR & (flag << (d->flagsShift - 32)): d->dma->LISR & (flag << d->flagsShift))
|
||||
|
||||
|
||||
|
|
|
@ -76,7 +76,7 @@ static void enableDmaClock(uint32_t rcc)
|
|||
/* Delay after an RCC peripheral clock enabling */
|
||||
tmpreg = READ_BIT(RCC->AHB1ENR, rcc);
|
||||
UNUSED(tmpreg);
|
||||
} while(0);
|
||||
} while (0);
|
||||
}
|
||||
|
||||
void dmaInit(dmaHandlerIdentifier_e identifier, resourceOwner_t owner, uint8_t resourceIndex)
|
||||
|
@ -97,7 +97,7 @@ void dmaSetHandler(dmaHandlerIdentifier_e identifier, dmaCallbackHandlerFuncPtr
|
|||
/* Delay after an RCC peripheral clock enabling */
|
||||
tmpreg = READ_BIT(RCC->AHB1ENR, dmaDescriptors[identifier].rcc);
|
||||
UNUSED(tmpreg);
|
||||
} while(0);
|
||||
} while (0);
|
||||
|
||||
dmaDescriptors[identifier].irqHandlerCallback = callback;
|
||||
dmaDescriptors[identifier].userParam = userParam;
|
||||
|
|
|
@ -73,7 +73,7 @@ void EXTIConfig(IO_t io, extiCallbackRec_t *cb, int irqPriority, ioConfig_t conf
|
|||
(void)config;
|
||||
int chIdx;
|
||||
chIdx = IO_GPIOPinIdx(io);
|
||||
if(chIdx < 0)
|
||||
if (chIdx < 0)
|
||||
return;
|
||||
extiChannelRec_t *rec = &extiChannelRecs[chIdx];
|
||||
int group = extiGroups[chIdx];
|
||||
|
@ -91,7 +91,7 @@ void EXTIConfig(IO_t io, extiCallbackRec_t *cb, int irqPriority, ioConfig_t conf
|
|||
|
||||
//EXTI_ClearITPendingBit(extiLine);
|
||||
|
||||
if(extiGroupPriority[group] > irqPriority) {
|
||||
if (extiGroupPriority[group] > irqPriority) {
|
||||
extiGroupPriority[group] = irqPriority;
|
||||
HAL_NVIC_SetPriority(extiGroupIRQn[group], NVIC_PRIORITY_BASE(irqPriority), NVIC_PRIORITY_SUB(irqPriority));
|
||||
HAL_NVIC_EnableIRQ(extiGroupIRQn[group]);
|
||||
|
@ -103,7 +103,7 @@ void EXTIConfig(IO_t io, extiCallbackRec_t *cb, int irqPriority, EXTITrigger_Typ
|
|||
{
|
||||
int chIdx;
|
||||
chIdx = IO_GPIOPinIdx(io);
|
||||
if(chIdx < 0)
|
||||
if (chIdx < 0)
|
||||
return;
|
||||
|
||||
// we have only 16 extiChannelRecs
|
||||
|
@ -133,7 +133,7 @@ void EXTIConfig(IO_t io, extiCallbackRec_t *cb, int irqPriority, EXTITrigger_Typ
|
|||
EXTIInit.EXTI_LineCmd = ENABLE;
|
||||
EXTI_Init(&EXTIInit);
|
||||
|
||||
if(extiGroupPriority[group] > irqPriority) {
|
||||
if (extiGroupPriority[group] > irqPriority) {
|
||||
extiGroupPriority[group] = irqPriority;
|
||||
|
||||
NVIC_InitTypeDef NVIC_InitStructure;
|
||||
|
@ -153,7 +153,7 @@ void EXTIRelease(IO_t io)
|
|||
|
||||
int chIdx;
|
||||
chIdx = IO_GPIOPinIdx(io);
|
||||
if(chIdx < 0)
|
||||
if (chIdx < 0)
|
||||
return;
|
||||
|
||||
// we have only 16 extiChannelRecs
|
||||
|
@ -167,18 +167,18 @@ void EXTIEnable(IO_t io, bool enable)
|
|||
{
|
||||
#if defined(STM32F1) || defined(STM32F4) || defined(STM32F7)
|
||||
uint32_t extiLine = IO_EXTI_Line(io);
|
||||
if(!extiLine)
|
||||
if (!extiLine)
|
||||
return;
|
||||
if(enable)
|
||||
if (enable)
|
||||
EXTI->IMR |= extiLine;
|
||||
else
|
||||
EXTI->IMR &= ~extiLine;
|
||||
#elif defined(STM32F303xC)
|
||||
int extiLine = IO_EXTI_Line(io);
|
||||
if(extiLine < 0)
|
||||
if (extiLine < 0)
|
||||
return;
|
||||
// assume extiLine < 32 (valid for all EXTI pins)
|
||||
if(enable)
|
||||
if (enable)
|
||||
EXTI->IMR |= 1 << extiLine;
|
||||
else
|
||||
EXTI->IMR &= ~(1 << extiLine);
|
||||
|
@ -191,7 +191,7 @@ void EXTI_IRQHandler(void)
|
|||
{
|
||||
uint32_t exti_active = EXTI->IMR & EXTI->PR;
|
||||
|
||||
while(exti_active) {
|
||||
while (exti_active) {
|
||||
unsigned idx = 31 - __builtin_clz(exti_active);
|
||||
uint32_t mask = 1 << idx;
|
||||
extiChannelRecs[idx].handler->fn(extiChannelRecs[idx].handler);
|
||||
|
|
|
@ -25,9 +25,9 @@
|
|||
# define LED0_OFF ledSet(0, false)
|
||||
# define LED0_ON ledSet(0, true)
|
||||
#else
|
||||
# define LED0_TOGGLE do {} while(0)
|
||||
# define LED0_OFF do {} while(0)
|
||||
# define LED0_ON do {} while(0)
|
||||
# define LED0_TOGGLE do {} while (0)
|
||||
# define LED0_OFF do {} while (0)
|
||||
# define LED0_ON do {} while (0)
|
||||
#endif
|
||||
|
||||
#ifdef LED1
|
||||
|
@ -35,9 +35,9 @@
|
|||
# define LED1_OFF ledSet(1, false)
|
||||
# define LED1_ON ledSet(1, true)
|
||||
#else
|
||||
# define LED1_TOGGLE do {} while(0)
|
||||
# define LED1_OFF do {} while(0)
|
||||
# define LED1_ON do {} while(0)
|
||||
# define LED1_TOGGLE do {} while (0)
|
||||
# define LED1_OFF do {} while (0)
|
||||
# define LED1_ON do {} while (0)
|
||||
#endif
|
||||
|
||||
#ifdef LED2
|
||||
|
@ -45,9 +45,9 @@
|
|||
# define LED2_OFF ledSet(2, false)
|
||||
# define LED2_ON ledSet(2, true)
|
||||
#else
|
||||
# define LED2_TOGGLE do {} while(0)
|
||||
# define LED2_OFF do {} while(0)
|
||||
# define LED2_ON do {} while(0)
|
||||
# define LED2_TOGGLE do {} while (0)
|
||||
# define LED2_OFF do {} while (0)
|
||||
# define LED2_ON do {} while (0)
|
||||
#endif
|
||||
|
||||
void ledInit(bool alternative_led);
|
||||
|
|
|
@ -50,7 +50,7 @@ static TIM_HandleTypeDef TimHandle;
|
|||
|
||||
void HAL_TIM_PWM_PulseFinishedCallback(TIM_HandleTypeDef *htim)
|
||||
{
|
||||
if(htim->Instance==WS2811_TIMER)
|
||||
if (htim->Instance==WS2811_TIMER)
|
||||
{
|
||||
//HAL_TIM_PWM_Stop_DMA(&TimHandle,WS2811_TIMER_CHANNEL);
|
||||
ws2811LedDataTransferInProgress = 0;
|
||||
|
@ -117,7 +117,7 @@ void HAL_TIM_PWM_MspInit(TIM_HandleTypeDef *htim)
|
|||
dmaSetHandler(WS2811_DMA_HANDLER_IDENTIFER, WS2811_DMA_IRQHandler, NVIC_PRIO_WS2811_DMA, timDMASource);
|
||||
|
||||
/* Initialize TIMx DMA handle */
|
||||
if(HAL_DMA_Init(htim->hdma[timDMASource]) != HAL_OK)
|
||||
if (HAL_DMA_Init(htim->hdma[timDMASource]) != HAL_OK)
|
||||
{
|
||||
/* Initialization Error */
|
||||
return;
|
||||
|
@ -132,7 +132,7 @@ void ws2811LedStripHardwareInit(void)
|
|||
TimHandle.Init.Period = 135; // 800kHz
|
||||
TimHandle.Init.ClockDivision = TIM_CLOCKDIVISION_DIV1;
|
||||
TimHandle.Init.CounterMode = TIM_COUNTERMODE_UP;
|
||||
if(HAL_TIM_PWM_Init(&TimHandle) != HAL_OK)
|
||||
if (HAL_TIM_PWM_Init(&TimHandle) != HAL_OK)
|
||||
{
|
||||
/* Initialization Error */
|
||||
return;
|
||||
|
@ -148,7 +148,7 @@ void ws2811LedStripHardwareInit(void)
|
|||
TIM_OCInitStructure.OCNIdleState = TIM_OCNIDLESTATE_RESET;
|
||||
TIM_OCInitStructure.OCFastMode = TIM_OCFAST_DISABLE;
|
||||
|
||||
if(HAL_TIM_PWM_ConfigChannel(&TimHandle, &TIM_OCInitStructure, WS2811_TIMER_CHANNEL) != HAL_OK)
|
||||
if (HAL_TIM_PWM_ConfigChannel(&TimHandle, &TIM_OCInitStructure, WS2811_TIMER_CHANNEL) != HAL_OK)
|
||||
{
|
||||
/* Configuration Error */
|
||||
return;
|
||||
|
@ -168,7 +168,7 @@ void ws2811LedStripDMAEnable(void)
|
|||
return;
|
||||
}
|
||||
|
||||
if( HAL_TIM_PWM_Start_DMA(&TimHandle, WS2811_TIMER_CHANNEL, ledStripDMABuffer, WS2811_DMA_BUFFER_SIZE) != HAL_OK)
|
||||
if ( HAL_TIM_PWM_Start_DMA(&TimHandle, WS2811_TIMER_CHANNEL, ledStripDMABuffer, WS2811_DMA_BUFFER_SIZE) != HAL_OK)
|
||||
{
|
||||
/* Starting PWM generation Error */
|
||||
ws2811LedDataTransferInProgress = 0;
|
||||
|
|
|
@ -77,7 +77,7 @@ void ws2811LedStripHardwareInit(void)
|
|||
if (timerHardware == NULL) {
|
||||
return;
|
||||
}
|
||||
|
||||
|
||||
timer = timerHardware->tim;
|
||||
|
||||
ws2811IO = IOGetByTag(IO_TAG(WS2811_PIN));
|
||||
|
|
|
@ -213,7 +213,7 @@ void max7456ReInit(void)
|
|||
|
||||
ENABLE_MAX7456;
|
||||
|
||||
switch(videoSignalCfg) {
|
||||
switch (videoSignalCfg) {
|
||||
case PAL:
|
||||
videoSignalReg = VIDEO_MODE_PAL | OSD_ENABLE;
|
||||
break;
|
||||
|
@ -235,7 +235,7 @@ void max7456ReInit(void)
|
|||
}
|
||||
|
||||
// set all rows to same charactor black/white level
|
||||
for(x = 0; x < maxScreenRows; x++) {
|
||||
for (x = 0; x < maxScreenRows; x++) {
|
||||
max7456Send(MAX7456ADD_RB0 + x, BWBRIGHTNESS);
|
||||
}
|
||||
|
||||
|
@ -404,7 +404,7 @@ void max7456WriteNvm(uint8_t char_address, const uint8_t *font_data)
|
|||
|
||||
max7456Send(MAX7456ADD_CMAH, char_address); // set start address high
|
||||
|
||||
for(x = 0; x < 54; x++) {
|
||||
for (x = 0; x < 54; x++) {
|
||||
max7456Send(MAX7456ADD_CMAL, x); //set start address low
|
||||
max7456Send(MAX7456ADD_CMDI, font_data[x]);
|
||||
#ifdef LED0_TOGGLE
|
||||
|
|
|
@ -30,7 +30,7 @@
|
|||
|
||||
/*
|
||||
* NXP MPXV7002DP differential pressure sensor
|
||||
*
|
||||
*
|
||||
*/
|
||||
#define PITOT_ADC_VOLTAGE_SCALER (2.0f / 1.0f) // MPXV7002DP is 5V device, assumed resistive divider 1K:1K
|
||||
#define PITOT_ADC_VOLTAGE_ZERO (2.5f) // Pressure offset is 2.5V
|
||||
|
|
|
@ -67,7 +67,7 @@ static void ms4525_start(void)
|
|||
|
||||
static void ms4525_read(void)
|
||||
{
|
||||
if(i2cRead( PITOT_I2C_INSTANCE, MS4525_ADDR, 0xFF, 4, rxbuf )) {
|
||||
if (i2cRead( PITOT_I2C_INSTANCE, MS4525_ADDR, 0xFF, 4, rxbuf )) {
|
||||
ms4525_up = (rxbuf[0] << 8) | (rxbuf[1] << 0);
|
||||
ms4525_ut = ((rxbuf[2] << 8) | (rxbuf[3] << 0))>>5;
|
||||
}
|
||||
|
|
|
@ -50,11 +50,11 @@ void detectBrushedESC(void)
|
|||
} else {
|
||||
hardwareMotorType = MOTOR_BRUSHED;
|
||||
}
|
||||
|
||||
|
||||
return;
|
||||
}
|
||||
}
|
||||
|
||||
|
||||
// Not found = assume brushless
|
||||
hardwareMotorType = MOTOR_BRUSHLESS;
|
||||
}
|
||||
|
|
|
@ -186,7 +186,7 @@ pwmIOConfiguration_t *pwmInit(drv_pwm_config_t *init)
|
|||
else if (init->useChannelForwarding && (timerHardwarePtr->usageFlags & TIM_USE_MC_CHNFW)) {
|
||||
type = MAP_TO_SERVO_OUTPUT;
|
||||
}
|
||||
else
|
||||
else
|
||||
#endif
|
||||
if (timerHardwarePtr->usageFlags & TIM_USE_MC_MOTOR) {
|
||||
type = MAP_TO_MOTOR_OUTPUT;
|
||||
|
|
|
@ -68,7 +68,7 @@ static void pwmOCConfig(TIM_TypeDef *tim, uint8_t channel, uint16_t value, uint8
|
|||
{
|
||||
#if defined(USE_HAL_DRIVER)
|
||||
TIM_HandleTypeDef* Handle = timerFindTimerHandle(tim);
|
||||
if(Handle == NULL) return;
|
||||
if (Handle == NULL) return;
|
||||
|
||||
TIM_OC_InitTypeDef TIM_OCInitStructure;
|
||||
|
||||
|
@ -116,7 +116,7 @@ static pwmOutputPort_t *pwmOutConfig(const timerHardware_t *timerHardware, uint8
|
|||
pwmOutputPort_t *p = &pwmOutputPorts[allocatedOutputPortCount++];
|
||||
#if defined(USE_HAL_DRIVER)
|
||||
TIM_HandleTypeDef* Handle = timerFindTimerHandle(timerHardware->tim);
|
||||
if(Handle == NULL) return p;
|
||||
if (Handle == NULL) return p;
|
||||
#endif
|
||||
|
||||
configTimeBase(timerHardware->tim, period, mhz);
|
||||
|
@ -142,7 +142,7 @@ static pwmOutputPort_t *pwmOutConfig(const timerHardware_t *timerHardware, uint8
|
|||
pwmOCConfig(timerHardware->tim, timerHardware->channel, value, timerHardware->output & TIMER_OUTPUT_INVERTED);
|
||||
|
||||
#if defined(USE_HAL_DRIVER)
|
||||
if(timerHardware->output & TIMER_OUTPUT_N_CHANNEL)
|
||||
if (timerHardware->output & TIMER_OUTPUT_N_CHANNEL)
|
||||
HAL_TIMEx_PWMN_Start(Handle, timerHardware->channel);
|
||||
else
|
||||
HAL_TIM_PWM_Start(Handle, timerHardware->channel);
|
||||
|
@ -310,10 +310,10 @@ void pwmWriteServo(uint8_t index, uint16_t value)
|
|||
#ifdef BEEPER_PWM
|
||||
void pwmWriteBeeper(bool onoffBeep)
|
||||
{
|
||||
if(beeperPwm == NULL)
|
||||
if (beeperPwm == NULL)
|
||||
return;
|
||||
|
||||
if(onoffBeep == true) {
|
||||
|
||||
if (onoffBeep == true) {
|
||||
*beeperPwm->ccr = (1000000 / beeperFrequency) / 2;
|
||||
} else {
|
||||
*beeperPwm->ccr = 0;
|
||||
|
|
|
@ -356,7 +356,7 @@ static void pwmEdgeCallback(timerCCHandlerRec_t *cbRec, captureCompare_t capture
|
|||
void pwmICConfig(TIM_TypeDef *tim, uint8_t channel, uint16_t polarity)
|
||||
{
|
||||
TIM_HandleTypeDef* Handle = timerFindTimerHandle(tim);
|
||||
if(Handle == NULL) return;
|
||||
if (Handle == NULL) return;
|
||||
|
||||
TIM_IC_InitTypeDef TIM_ICInitStructure;
|
||||
|
||||
|
|
|
@ -120,7 +120,7 @@ void hcsr04_update(void)
|
|||
// The speed of sound is 340 m/s or approx. 29 microseconds per centimeter.
|
||||
// The ping travels out and back, so to find the distance of the
|
||||
// object we take half of the distance traveled.
|
||||
// 340 m/s = 0.034 cm/microsecond = 29.41176471 *2 = 58.82352941 rounded to 59
|
||||
// 340 m/s = 0.034 cm/microsecond = 29.41176471 *2 = 58.82352941 rounded to 59
|
||||
|
||||
lastCalculatedDistance = hcsr04SonarPulseTravelTime / 59;
|
||||
if (lastCalculatedDistance > HCSR04_MAX_RANGE_CM) {
|
||||
|
@ -131,7 +131,7 @@ void hcsr04_update(void)
|
|||
// No measurement within reasonable time - indicate failure
|
||||
lastCalculatedDistance = RANGEFINDER_HARDWARE_FAILURE;
|
||||
}
|
||||
|
||||
|
||||
// Trigger a new measurement
|
||||
lastMeasurementStartedAt = timeNowMs;
|
||||
hcsr04_start_reading();
|
||||
|
@ -218,7 +218,7 @@ bool hcsr04Detect(rangefinderDev_t *dev, const rangefinderHardwarePins_t * range
|
|||
return true;
|
||||
}
|
||||
else {
|
||||
// Not detected - free resources
|
||||
// Not detected - free resources
|
||||
IORelease(triggerIO);
|
||||
IORelease(echoIO);
|
||||
return false;
|
||||
|
|
|
@ -92,7 +92,7 @@ static void uartReconfigure(uartPort_t *uartPort)
|
|||
|
||||
usartConfigurePinInversion(uartPort);
|
||||
|
||||
if(uartPort->port.options & SERIAL_BIDIR)
|
||||
if (uartPort->port.options & SERIAL_BIDIR)
|
||||
USART_HalfDuplexCmd(uartPort->USARTx, ENABLE);
|
||||
else
|
||||
USART_HalfDuplexCmd(uartPort->USARTx, DISABLE);
|
||||
|
|
|
@ -41,7 +41,7 @@
|
|||
static void usartConfigurePinInversion(uartPort_t *uartPort) {
|
||||
bool inverted = uartPort->port.options & SERIAL_INVERTED;
|
||||
|
||||
if(inverted)
|
||||
if (inverted)
|
||||
{
|
||||
if (uartPort->port.mode & MODE_RX)
|
||||
{
|
||||
|
@ -88,7 +88,7 @@ static void uartReconfigure(uartPort_t *uartPort)
|
|||
|
||||
usartConfigurePinInversion(uartPort);
|
||||
|
||||
if(uartPort->port.options & SERIAL_BIDIR)
|
||||
if (uartPort->port.options & SERIAL_BIDIR)
|
||||
{
|
||||
HAL_HalfDuplex_Init(&uartPort->Handle);
|
||||
}
|
||||
|
@ -161,9 +161,9 @@ static void uartReconfigure(uartPort_t *uartPort)
|
|||
|
||||
HAL_DMA_DeInit(&uartPort->txDMAHandle);
|
||||
HAL_StatusTypeDef status = HAL_DMA_Init(&uartPort->txDMAHandle);
|
||||
if(status != HAL_OK)
|
||||
if (status != HAL_OK)
|
||||
{
|
||||
while(1);
|
||||
while (1);
|
||||
}
|
||||
/* Associate the initialized DMA handle to the UART handle */
|
||||
__HAL_LINKDMA(&uartPort->Handle, hdmatx, uartPort->txDMAHandle);
|
||||
|
@ -253,7 +253,7 @@ void uartStartTxDMA(uartPort_t *s)
|
|||
uint16_t size = 0;
|
||||
uint32_t fromwhere=0;
|
||||
HAL_UART_StateTypeDef state = HAL_UART_GetState(&s->Handle);
|
||||
if((state & HAL_UART_STATE_BUSY_TX) == HAL_UART_STATE_BUSY_TX)
|
||||
if ((state & HAL_UART_STATE_BUSY_TX) == HAL_UART_STATE_BUSY_TX)
|
||||
return;
|
||||
|
||||
if (s->port.txBufferHead > s->port.txBufferTail) {
|
||||
|
|
|
@ -299,7 +299,7 @@ void uartIrqHandler(uartPort_t *s)
|
|||
{
|
||||
UART_HandleTypeDef *huart = &s->Handle;
|
||||
/* UART in mode Receiver ---------------------------------------------------*/
|
||||
if((__HAL_UART_GET_IT(huart, UART_IT_RXNE) != RESET))
|
||||
if ((__HAL_UART_GET_IT(huart, UART_IT_RXNE) != RESET))
|
||||
{
|
||||
uint8_t rbyte = (uint8_t)(huart->Instance->RDR & (uint8_t)0xff);
|
||||
|
||||
|
@ -318,37 +318,37 @@ void uartIrqHandler(uartPort_t *s)
|
|||
}
|
||||
|
||||
/* UART parity error interrupt occurred -------------------------------------*/
|
||||
if((__HAL_UART_GET_IT(huart, UART_IT_PE) != RESET))
|
||||
if ((__HAL_UART_GET_IT(huart, UART_IT_PE) != RESET))
|
||||
{
|
||||
__HAL_UART_CLEAR_IT(huart, UART_CLEAR_PEF);
|
||||
}
|
||||
|
||||
/* UART frame error interrupt occurred --------------------------------------*/
|
||||
if((__HAL_UART_GET_IT(huart, UART_IT_FE) != RESET))
|
||||
if ((__HAL_UART_GET_IT(huart, UART_IT_FE) != RESET))
|
||||
{
|
||||
__HAL_UART_CLEAR_IT(huart, UART_CLEAR_FEF);
|
||||
}
|
||||
|
||||
/* UART noise error interrupt occurred --------------------------------------*/
|
||||
if((__HAL_UART_GET_IT(huart, UART_IT_NE) != RESET))
|
||||
if ((__HAL_UART_GET_IT(huart, UART_IT_NE) != RESET))
|
||||
{
|
||||
__HAL_UART_CLEAR_IT(huart, UART_CLEAR_NEF);
|
||||
}
|
||||
|
||||
/* UART Over-Run interrupt occurred -----------------------------------------*/
|
||||
if((__HAL_UART_GET_IT(huart, UART_IT_ORE) != RESET))
|
||||
if ((__HAL_UART_GET_IT(huart, UART_IT_ORE) != RESET))
|
||||
{
|
||||
__HAL_UART_CLEAR_IT(huart, UART_CLEAR_OREF);
|
||||
}
|
||||
|
||||
/* UART in mode Transmitter ------------------------------------------------*/
|
||||
if((__HAL_UART_GET_IT(huart, UART_IT_TXE) != RESET))
|
||||
if ((__HAL_UART_GET_IT(huart, UART_IT_TXE) != RESET))
|
||||
{
|
||||
HAL_UART_IRQHandler(huart);
|
||||
}
|
||||
|
||||
/* UART in mode Transmitter (transmission end) -----------------------------*/
|
||||
if((__HAL_UART_GET_IT(huart, UART_IT_TC) != RESET))
|
||||
if ((__HAL_UART_GET_IT(huart, UART_IT_TC) != RESET))
|
||||
{
|
||||
HAL_UART_IRQHandler(huart);
|
||||
handleUsartTxDma(s);
|
||||
|
@ -428,7 +428,7 @@ uartPort_t *serialUART(UARTDevice device, uint32_t baudRate, portMode_t mode, po
|
|||
//HAL_NVIC_SetPriority(uart->txIrq, NVIC_PRIORITY_BASE(uart->txPriority), NVIC_PRIORITY_SUB(uart->txPriority));
|
||||
//HAL_NVIC_EnableIRQ(uart->txIrq);
|
||||
|
||||
if(!s->rxDMAChannel)
|
||||
if (!s->rxDMAChannel)
|
||||
{
|
||||
HAL_NVIC_SetPriority(uart->rxIrq, NVIC_PRIORITY_BASE(uart->rxPriority), NVIC_PRIORITY_SUB(uart->rxPriority));
|
||||
HAL_NVIC_EnableIRQ(uart->rxIrq);
|
||||
|
|
|
@ -24,9 +24,9 @@
|
|||
#define BEEP_OFF systemBeep(false)
|
||||
#define BEEP_ON systemBeep(true)
|
||||
#else
|
||||
#define BEEP_TOGGLE do {} while(0)
|
||||
#define BEEP_OFF do {} while(0)
|
||||
#define BEEP_ON do {} while(0)
|
||||
#define BEEP_TOGGLE do {} while (0)
|
||||
#define BEEP_OFF do {} while (0)
|
||||
#define BEEP_ON do {} while (0)
|
||||
#endif
|
||||
|
||||
typedef struct beeperDevConfig_s {
|
||||
|
|
|
@ -78,7 +78,7 @@ static uint8_t lookupTimerIndex(const TIM_TypeDef *tim)
|
|||
#define _CASE(i) _CASE_(TIM##i##_BASE, TIMER_INDEX(i))
|
||||
|
||||
// let gcc do the work, switch should be quite optimized
|
||||
switch((unsigned)tim >> _CASE_SHF) {
|
||||
switch ((unsigned)tim >> _CASE_SHF) {
|
||||
#if USED_TIMERS & TIM_N(1)
|
||||
_CASE(1);
|
||||
#endif
|
||||
|
@ -254,7 +254,7 @@ void timerConfigure(const timerHardware_t *timerHardwarePtr, uint16_t period, ui
|
|||
timerNVICConfigure(irq, NVIC_PRIO_TIMER);
|
||||
|
||||
// HACK - enable second IRQ on timers that need it
|
||||
switch(irq) {
|
||||
switch (irq) {
|
||||
#if defined(STM32F10X)
|
||||
case TIM1_CC_IRQn:
|
||||
timerNVICConfigure(TIM1_UP_IRQn, NVIC_PRIO_TIMER);
|
||||
|
@ -287,14 +287,14 @@ void timerConfigure(const timerHardware_t *timerHardwarePtr, uint16_t period, ui
|
|||
void timerChInit(const timerHardware_t *timHw, channelType_t type, int irqPriority, uint8_t irq)
|
||||
{
|
||||
unsigned channel = timHw - timerHardware;
|
||||
if(channel >= USABLE_TIMER_CHANNEL_COUNT)
|
||||
if (channel >= USABLE_TIMER_CHANNEL_COUNT)
|
||||
return;
|
||||
|
||||
timerChannelInfo[channel].type = type;
|
||||
unsigned timer = lookupTimerIndex(timHw->tim);
|
||||
if(timer >= USED_TIMER_COUNT)
|
||||
if (timer >= USED_TIMER_COUNT)
|
||||
return;
|
||||
if(irqPriority < timerInfo[timer].priority) {
|
||||
if (irqPriority < timerInfo[timer].priority) {
|
||||
// it would be better to set priority in the end, but current startup sequence is not ready
|
||||
configTimeBase(usedTimers[timer], 0, 1);
|
||||
TIM_Cmd(usedTimers[timer], ENABLE);
|
||||
|
@ -321,8 +321,8 @@ void timerChOvrHandlerInit(timerOvrHandlerRec_t *self, timerOvrHandlerCallback *
|
|||
static void timerChConfig_UpdateOverflow(timerConfig_t *cfg, TIM_TypeDef *tim) {
|
||||
timerOvrHandlerRec_t **chain = &cfg->overflowCallbackActive;
|
||||
ATOMIC_BLOCK(NVIC_PRIO_TIMER) {
|
||||
for(int i = 0; i < CC_CHANNELS_PER_TIMER; i++)
|
||||
if(cfg->overflowCallback[i]) {
|
||||
for (int i = 0; i < CC_CHANNELS_PER_TIMER; i++)
|
||||
if (cfg->overflowCallback[i]) {
|
||||
*chain = cfg->overflowCallback[i];
|
||||
chain = &cfg->overflowCallback[i]->next;
|
||||
}
|
||||
|
@ -340,13 +340,13 @@ void timerChConfigCallbacks(const timerHardware_t *timHw, timerCCHandlerRec_t *e
|
|||
return;
|
||||
}
|
||||
uint8_t channelIndex = lookupChannelIndex(timHw->channel);
|
||||
if(edgeCallback == NULL) // disable irq before changing callback to NULL
|
||||
if (edgeCallback == NULL) // disable irq before changing callback to NULL
|
||||
TIM_ITConfig(timHw->tim, TIM_IT_CCx(timHw->channel), DISABLE);
|
||||
// setup callback info
|
||||
timerConfig[timerIndex].edgeCallback[channelIndex] = edgeCallback;
|
||||
timerConfig[timerIndex].overflowCallback[channelIndex] = overflowCallback;
|
||||
// enable channel IRQ
|
||||
if(edgeCallback)
|
||||
if (edgeCallback)
|
||||
TIM_ITConfig(timHw->tim, TIM_IT_CCx(timHw->channel), ENABLE);
|
||||
|
||||
timerChConfig_UpdateOverflow(&timerConfig[timerIndex], timHw->tim);
|
||||
|
@ -365,9 +365,9 @@ void timerChConfigCallbacksDual(const timerHardware_t *timHw, timerCCHandlerRec_
|
|||
uint16_t chHi = timHw->channel | TIM_Channel_2; // upper channel
|
||||
uint8_t channelIndex = lookupChannelIndex(chLo); // get index of lower channel
|
||||
|
||||
if(edgeCallbackLo == NULL) // disable irq before changing setting callback to NULL
|
||||
if (edgeCallbackLo == NULL) // disable irq before changing setting callback to NULL
|
||||
TIM_ITConfig(timHw->tim, TIM_IT_CCx(chLo), DISABLE);
|
||||
if(edgeCallbackHi == NULL) // disable irq before changing setting callback to NULL
|
||||
if (edgeCallbackHi == NULL) // disable irq before changing setting callback to NULL
|
||||
TIM_ITConfig(timHw->tim, TIM_IT_CCx(chHi), DISABLE);
|
||||
|
||||
// setup callback info
|
||||
|
@ -377,11 +377,11 @@ void timerChConfigCallbacksDual(const timerHardware_t *timHw, timerCCHandlerRec_
|
|||
timerConfig[timerIndex].overflowCallback[channelIndex + 1] = NULL;
|
||||
|
||||
// enable channel IRQs
|
||||
if(edgeCallbackLo) {
|
||||
if (edgeCallbackLo) {
|
||||
TIM_ClearFlag(timHw->tim, TIM_IT_CCx(chLo));
|
||||
TIM_ITConfig(timHw->tim, TIM_IT_CCx(chLo), ENABLE);
|
||||
}
|
||||
if(edgeCallbackHi) {
|
||||
if (edgeCallbackHi) {
|
||||
TIM_ClearFlag(timHw->tim, TIM_IT_CCx(chHi));
|
||||
TIM_ITConfig(timHw->tim, TIM_IT_CCx(chHi), ENABLE);
|
||||
}
|
||||
|
@ -427,8 +427,8 @@ static unsigned getFilter(unsigned ticks)
|
|||
16*5, 16*6, 16*8,
|
||||
32*5, 32*6, 32*8
|
||||
};
|
||||
for(unsigned i = 1; i < ARRAYLEN(ftab); i++)
|
||||
if(ftab[i] > ticks)
|
||||
for (unsigned i = 1; i < ARRAYLEN(ftab); i++)
|
||||
if (ftab[i] > ticks)
|
||||
return i - 1;
|
||||
return 0x0f;
|
||||
}
|
||||
|
@ -503,7 +503,7 @@ void timerChConfigOC(const timerHardware_t* timHw, bool outEnable, bool stateHig
|
|||
TIM_OCInitTypeDef TIM_OCInitStructure;
|
||||
|
||||
TIM_OCStructInit(&TIM_OCInitStructure);
|
||||
if(outEnable) {
|
||||
if (outEnable) {
|
||||
TIM_OCInitStructure.TIM_OCMode = TIM_OCMode_Inactive;
|
||||
TIM_OCInitStructure.TIM_OutputState = TIM_OutputState_Enable;
|
||||
if (timHw->output & TIMER_OUTPUT_INVERTED) {
|
||||
|
@ -540,17 +540,17 @@ static void timCCxHandler(TIM_TypeDef *tim, timerConfig_t *timerConfig)
|
|||
unsigned tim_status;
|
||||
tim_status = tim->SR & tim->DIER;
|
||||
#if 1
|
||||
while(tim_status) {
|
||||
while (tim_status) {
|
||||
// flags will be cleared by reading CCR in dual capture, make sure we call handler correctly
|
||||
// currrent order is highest bit first. Code should not rely on specific order (it will introduce race conditions anyway)
|
||||
unsigned bit = __builtin_clz(tim_status);
|
||||
unsigned mask = ~(0x80000000 >> bit);
|
||||
tim->SR = mask;
|
||||
tim_status &= mask;
|
||||
switch(bit) {
|
||||
switch (bit) {
|
||||
case __builtin_clz(TIM_IT_Update): {
|
||||
|
||||
if(timerConfig->forcedOverflowTimerValue != 0){
|
||||
if (timerConfig->forcedOverflowTimerValue != 0){
|
||||
capture = timerConfig->forcedOverflowTimerValue - 1;
|
||||
timerConfig->forcedOverflowTimerValue = 0;
|
||||
} else {
|
||||
|
@ -558,7 +558,7 @@ static void timCCxHandler(TIM_TypeDef *tim, timerConfig_t *timerConfig)
|
|||
}
|
||||
|
||||
timerOvrHandlerRec_t *cb = timerConfig->overflowCallbackActive;
|
||||
while(cb) {
|
||||
while (cb) {
|
||||
cb->fn(cb, capture);
|
||||
cb = cb->next;
|
||||
}
|
||||
|
@ -583,7 +583,7 @@ static void timCCxHandler(TIM_TypeDef *tim, timerConfig_t *timerConfig)
|
|||
tim->SR = ~TIM_IT_Update;
|
||||
capture = tim->ARR;
|
||||
timerOvrHandlerRec_t *cb = timerConfig->overflowCallbackActive;
|
||||
while(cb) {
|
||||
while (cb) {
|
||||
cb->fn(cb, capture);
|
||||
cb = cb->next;
|
||||
}
|
||||
|
@ -710,10 +710,10 @@ void timerInit(void)
|
|||
#endif
|
||||
|
||||
// initialize timer channel structures
|
||||
for(int i = 0; i < USABLE_TIMER_CHANNEL_COUNT; i++) {
|
||||
for (int i = 0; i < USABLE_TIMER_CHANNEL_COUNT; i++) {
|
||||
timerChannelInfo[i].type = TYPE_FREE;
|
||||
}
|
||||
for(int i = 0; i < USED_TIMER_COUNT; i++) {
|
||||
for (int i = 0; i < USED_TIMER_COUNT; i++) {
|
||||
timerInfo[i].priority = ~0;
|
||||
}
|
||||
}
|
||||
|
@ -724,18 +724,18 @@ void timerInit(void)
|
|||
void timerStart(void)
|
||||
{
|
||||
#if 0
|
||||
for(unsigned timer = 0; timer < USED_TIMER_COUNT; timer++) {
|
||||
for (unsigned timer = 0; timer < USED_TIMER_COUNT; timer++) {
|
||||
int priority = -1;
|
||||
int irq = -1;
|
||||
for(unsigned hwc = 0; hwc < USABLE_TIMER_CHANNEL_COUNT; hwc++)
|
||||
if((timerChannelInfo[hwc].type != TYPE_FREE) && (timerHardware[hwc].tim == usedTimers[timer])) {
|
||||
for (unsigned hwc = 0; hwc < USABLE_TIMER_CHANNEL_COUNT; hwc++)
|
||||
if ((timerChannelInfo[hwc].type != TYPE_FREE) && (timerHardware[hwc].tim == usedTimers[timer])) {
|
||||
// TODO - move IRQ to timer info
|
||||
irq = timerHardware[hwc].irq;
|
||||
}
|
||||
// TODO - aggregate required timer paramaters
|
||||
configTimeBase(usedTimers[timer], 0, 1);
|
||||
TIM_Cmd(usedTimers[timer], ENABLE);
|
||||
if(priority >= 0) { // maybe none of the channels was configured
|
||||
if (priority >= 0) { // maybe none of the channels was configured
|
||||
NVIC_InitTypeDef NVIC_InitStructure;
|
||||
|
||||
NVIC_InitStructure.NVIC_IRQChannel = irq;
|
||||
|
|
|
@ -86,7 +86,7 @@ static uint8_t lookupTimerIndex(const TIM_TypeDef *tim)
|
|||
#define _CASE(i) _CASE_(TIM##i##_BASE, TIMER_INDEX(i))
|
||||
|
||||
// let gcc do the work, switch should be quite optimized
|
||||
switch((unsigned)tim >> _CASE_SHF) {
|
||||
switch ((unsigned)tim >> _CASE_SHF) {
|
||||
#if USED_TIMERS & TIM_N(1)
|
||||
_CASE(1);
|
||||
#endif
|
||||
|
@ -247,7 +247,7 @@ void configTimeBase(TIM_TypeDef *tim, uint16_t period, uint8_t mhz)
|
|||
if (timerIndex >= USED_TIMER_COUNT) {
|
||||
return;
|
||||
}
|
||||
if(timeHandle[timerIndex].Handle.Instance == tim)
|
||||
if (timeHandle[timerIndex].Handle.Instance == tim)
|
||||
{
|
||||
// already configured
|
||||
return;
|
||||
|
@ -256,7 +256,7 @@ void configTimeBase(TIM_TypeDef *tim, uint16_t period, uint8_t mhz)
|
|||
timeHandle[timerIndex].Handle.Instance = tim;
|
||||
|
||||
timeHandle[timerIndex].Handle.Init.Period = (period - 1) & 0xffff; // AKA TIMx_ARR
|
||||
if(tim == TIM1 || tim == TIM8 || tim == TIM9 || tim == TIM10 || tim == TIM11)
|
||||
if (tim == TIM1 || tim == TIM8 || tim == TIM9 || tim == TIM10 || tim == TIM11)
|
||||
timeHandle[timerIndex].Handle.Init.Prescaler = (HAL_RCC_GetPCLK2Freq() * 2 / ((uint32_t)mhz * 1000000)) - 1;
|
||||
else
|
||||
timeHandle[timerIndex].Handle.Init.Prescaler = (HAL_RCC_GetPCLK1Freq() * 2 * 2 / ((uint32_t)mhz * 1000000)) - 1;
|
||||
|
@ -266,7 +266,7 @@ void configTimeBase(TIM_TypeDef *tim, uint16_t period, uint8_t mhz)
|
|||
timeHandle[timerIndex].Handle.Init.RepetitionCounter = 0x0000;
|
||||
|
||||
HAL_TIM_Base_Init(&timeHandle[timerIndex].Handle);
|
||||
if(tim == TIM1 || tim == TIM2 || tim == TIM3 || tim == TIM4 || tim == TIM5 || tim == TIM8 || tim == TIM9)
|
||||
if (tim == TIM1 || tim == TIM2 || tim == TIM3 || tim == TIM4 || tim == TIM5 || tim == TIM8 || tim == TIM9)
|
||||
{
|
||||
TIM_ClockConfigTypeDef sClockSourceConfig;
|
||||
sClockSourceConfig.ClockFilter = 0;
|
||||
|
@ -278,7 +278,7 @@ void configTimeBase(TIM_TypeDef *tim, uint16_t period, uint8_t mhz)
|
|||
return;
|
||||
}
|
||||
}
|
||||
if(tim == TIM1 || tim == TIM2 || tim == TIM3 || tim == TIM4 || tim == TIM5 || tim == TIM8 )
|
||||
if (tim == TIM1 || tim == TIM2 || tim == TIM3 || tim == TIM4 || tim == TIM5 || tim == TIM8 )
|
||||
{
|
||||
TIM_MasterConfigTypeDef sMasterConfig;
|
||||
sMasterConfig.MasterOutputTrigger = TIM_TRGO_RESET;
|
||||
|
@ -302,11 +302,11 @@ void timerConfigure(const timerHardware_t *timerHardwarePtr, uint16_t period, ui
|
|||
|
||||
configTimeBase(timerHardwarePtr->tim, period, mhz);
|
||||
HAL_TIM_Base_Start(&timeHandle[timerIndex].Handle);
|
||||
|
||||
|
||||
uint8_t irq = timerInputIrq(timerHardwarePtr->tim);
|
||||
timerNVICConfigure(irq);
|
||||
// HACK - enable second IRQ on timers that need it
|
||||
switch(irq) {
|
||||
switch (irq) {
|
||||
|
||||
case TIM1_CC_IRQn:
|
||||
timerNVICConfigure(TIM1_UP_TIM10_IRQn);
|
||||
|
@ -326,14 +326,14 @@ void timerChInit(const timerHardware_t *timHw, channelType_t type, int irqPriori
|
|||
return;
|
||||
}
|
||||
unsigned channel = timHw - timerHardware;
|
||||
if(channel >= USABLE_TIMER_CHANNEL_COUNT)
|
||||
if (channel >= USABLE_TIMER_CHANNEL_COUNT)
|
||||
return;
|
||||
|
||||
timerChannelInfo[channel].type = type;
|
||||
unsigned timer = lookupTimerIndex(timHw->tim);
|
||||
if(timer >= USED_TIMER_COUNT)
|
||||
if (timer >= USED_TIMER_COUNT)
|
||||
return;
|
||||
if(irqPriority < timerInfo[timer].priority) {
|
||||
if (irqPriority < timerInfo[timer].priority) {
|
||||
// it would be better to set priority in the end, but current startup sequence is not ready
|
||||
configTimeBase(usedTimers[timer], 0, 1);
|
||||
HAL_TIM_Base_Start(&timeHandle[timerIndex].Handle);
|
||||
|
@ -365,15 +365,15 @@ static void timerChConfig_UpdateOverflow(timerConfig_t *cfg, TIM_TypeDef *tim) {
|
|||
|
||||
timerOvrHandlerRec_t **chain = &cfg->overflowCallbackActive;
|
||||
ATOMIC_BLOCK(NVIC_PRIO_TIMER) {
|
||||
for(int i = 0; i < CC_CHANNELS_PER_TIMER; i++)
|
||||
if(cfg->overflowCallback[i]) {
|
||||
for (int i = 0; i < CC_CHANNELS_PER_TIMER; i++)
|
||||
if (cfg->overflowCallback[i]) {
|
||||
*chain = cfg->overflowCallback[i];
|
||||
chain = &cfg->overflowCallback[i]->next;
|
||||
}
|
||||
*chain = NULL;
|
||||
}
|
||||
// enable or disable IRQ
|
||||
if(cfg->overflowCallbackActive)
|
||||
if (cfg->overflowCallbackActive)
|
||||
__HAL_TIM_ENABLE_IT(&timeHandle[timerIndex].Handle, TIM_IT_UPDATE);
|
||||
else
|
||||
__HAL_TIM_DISABLE_IT(&timeHandle[timerIndex].Handle, TIM_IT_UPDATE);
|
||||
|
@ -387,13 +387,13 @@ void timerChConfigCallbacks(const timerHardware_t *timHw, timerCCHandlerRec_t *e
|
|||
return;
|
||||
}
|
||||
uint8_t channelIndex = lookupChannelIndex(timHw->channel);
|
||||
if(edgeCallback == NULL) // disable irq before changing callback to NULL
|
||||
if (edgeCallback == NULL) // disable irq before changing callback to NULL
|
||||
__HAL_TIM_DISABLE_IT(&timeHandle[timerIndex].Handle, TIM_IT_CCx(timHw->channel));
|
||||
// setup callback info
|
||||
timerConfig[timerIndex].edgeCallback[channelIndex] = edgeCallback;
|
||||
timerConfig[timerIndex].overflowCallback[channelIndex] = overflowCallback;
|
||||
// enable channel IRQ
|
||||
if(edgeCallback)
|
||||
if (edgeCallback)
|
||||
__HAL_TIM_ENABLE_IT(&timeHandle[timerIndex].Handle, TIM_IT_CCx(timHw->channel));
|
||||
|
||||
timerChConfig_UpdateOverflow(&timerConfig[timerIndex], timHw->tim);
|
||||
|
@ -412,9 +412,9 @@ void timerChConfigCallbacksDual(const timerHardware_t *timHw, timerCCHandlerRec_
|
|||
uint16_t chHi = timHw->channel | TIM_CHANNEL_2; // upper channel
|
||||
uint8_t channelIndex = lookupChannelIndex(chLo); // get index of lower channel
|
||||
|
||||
if(edgeCallbackLo == NULL) // disable irq before changing setting callback to NULL
|
||||
if (edgeCallbackLo == NULL) // disable irq before changing setting callback to NULL
|
||||
__HAL_TIM_DISABLE_IT(&timeHandle[timerIndex].Handle, TIM_IT_CCx(chLo));
|
||||
if(edgeCallbackHi == NULL) // disable irq before changing setting callback to NULL
|
||||
if (edgeCallbackHi == NULL) // disable irq before changing setting callback to NULL
|
||||
__HAL_TIM_DISABLE_IT(&timeHandle[timerIndex].Handle, TIM_IT_CCx(chHi));
|
||||
|
||||
// setup callback info
|
||||
|
@ -424,11 +424,11 @@ void timerChConfigCallbacksDual(const timerHardware_t *timHw, timerCCHandlerRec_
|
|||
timerConfig[timerIndex].overflowCallback[channelIndex + 1] = NULL;
|
||||
|
||||
// enable channel IRQs
|
||||
if(edgeCallbackLo) {
|
||||
if (edgeCallbackLo) {
|
||||
__HAL_TIM_CLEAR_FLAG(&timeHandle[timerIndex].Handle, TIM_IT_CCx(chLo));
|
||||
__HAL_TIM_ENABLE_IT(&timeHandle[timerIndex].Handle, TIM_IT_CCx(chLo));
|
||||
}
|
||||
if(edgeCallbackHi) {
|
||||
if (edgeCallbackHi) {
|
||||
__HAL_TIM_CLEAR_FLAG(&timeHandle[timerIndex].Handle, TIM_IT_CCx(chHi));
|
||||
__HAL_TIM_ENABLE_IT(&timeHandle[timerIndex].Handle, TIM_IT_CCx(chHi));
|
||||
}
|
||||
|
@ -447,7 +447,7 @@ void timerChITConfigDualLo(const timerHardware_t *timHw, FunctionalState newStat
|
|||
return;
|
||||
}
|
||||
|
||||
if(newState)
|
||||
if (newState)
|
||||
__HAL_TIM_ENABLE_IT(&timeHandle[timerIndex].Handle, TIM_IT_CCx(timHw->channel&~TIM_CHANNEL_2));
|
||||
else
|
||||
__HAL_TIM_DISABLE_IT(&timeHandle[timerIndex].Handle, TIM_IT_CCx(timHw->channel&~TIM_CHANNEL_2));
|
||||
|
@ -466,7 +466,7 @@ void timerChITConfig(const timerHardware_t *timHw, FunctionalState newState)
|
|||
return;
|
||||
}
|
||||
|
||||
if(newState)
|
||||
if (newState)
|
||||
__HAL_TIM_ENABLE_IT(&timeHandle[timerIndex].Handle, TIM_IT_CCx(timHw->channel));
|
||||
else
|
||||
__HAL_TIM_DISABLE_IT(&timeHandle[timerIndex].Handle, TIM_IT_CCx(timHw->channel));
|
||||
|
@ -509,8 +509,8 @@ static unsigned getFilter(unsigned ticks)
|
|||
16*5, 16*6, 16*8,
|
||||
32*5, 32*6, 32*8
|
||||
};
|
||||
for(unsigned i = 1; i < ARRAYLEN(ftab); i++)
|
||||
if(ftab[i] > ticks)
|
||||
for (unsigned i = 1; i < ARRAYLEN(ftab); i++)
|
||||
if (ftab[i] > ticks)
|
||||
return i - 1;
|
||||
return 0x0f;
|
||||
}
|
||||
|
@ -519,7 +519,7 @@ static unsigned getFilter(unsigned ticks)
|
|||
void timerChConfigIC(const timerHardware_t *timHw, bool polarityRising, unsigned inputFilterTicks)
|
||||
{
|
||||
unsigned timer = lookupTimerIndex(timHw->tim);
|
||||
if(timer >= USED_TIMER_COUNT)
|
||||
if (timer >= USED_TIMER_COUNT)
|
||||
return;
|
||||
|
||||
TIM_IC_InitTypeDef TIM_ICInitStructure;
|
||||
|
@ -536,7 +536,7 @@ void timerChConfigIC(const timerHardware_t *timHw, bool polarityRising, unsigned
|
|||
void timerChConfigICDual(const timerHardware_t *timHw, bool polarityRising, unsigned inputFilterTicks)
|
||||
{
|
||||
unsigned timer = lookupTimerIndex(timHw->tim);
|
||||
if(timer >= USED_TIMER_COUNT)
|
||||
if (timer >= USED_TIMER_COUNT)
|
||||
return;
|
||||
|
||||
TIM_IC_InitTypeDef TIM_ICInitStructure;
|
||||
|
@ -586,7 +586,7 @@ volatile timCCR_t* timerChCCR(const timerHardware_t *timHw)
|
|||
void timerChConfigOC(const timerHardware_t* timHw, bool outEnable, bool stateHigh)
|
||||
{
|
||||
unsigned timer = lookupTimerIndex(timHw->tim);
|
||||
if(timer >= USED_TIMER_COUNT)
|
||||
if (timer >= USED_TIMER_COUNT)
|
||||
return;
|
||||
|
||||
TIM_OC_InitTypeDef TIM_OCInitStructure;
|
||||
|
@ -600,7 +600,7 @@ void timerChConfigOC(const timerHardware_t* timHw, bool outEnable, bool stateHig
|
|||
|
||||
HAL_TIM_OC_ConfigChannel(&timeHandle[timer].Handle, &TIM_OCInitStructure, timHw->channel);
|
||||
|
||||
if(outEnable) {
|
||||
if (outEnable) {
|
||||
TIM_OCInitStructure.OCMode = TIM_OCMODE_INACTIVE;
|
||||
HAL_TIM_OC_ConfigChannel(&timeHandle[timer].Handle, &TIM_OCInitStructure, timHw->channel);
|
||||
HAL_TIM_OC_Start(&timeHandle[timer].Handle, timHw->channel);
|
||||
|
@ -617,17 +617,17 @@ static void timCCxHandler(TIM_TypeDef *tim, timerConfig_t *timerConfig)
|
|||
unsigned tim_status;
|
||||
tim_status = tim->SR & tim->DIER;
|
||||
#if 1
|
||||
while(tim_status) {
|
||||
while (tim_status) {
|
||||
// flags will be cleared by reading CCR in dual capture, make sure we call handler correctly
|
||||
// currrent order is highest bit first. Code should not rely on specific order (it will introduce race conditions anyway)
|
||||
unsigned bit = __builtin_clz(tim_status);
|
||||
unsigned mask = ~(0x80000000 >> bit);
|
||||
tim->SR = mask;
|
||||
tim_status &= mask;
|
||||
switch(bit) {
|
||||
switch (bit) {
|
||||
case __builtin_clz(TIM_IT_UPDATE): {
|
||||
|
||||
if(timerConfig->forcedOverflowTimerValue != 0){
|
||||
if (timerConfig->forcedOverflowTimerValue != 0){
|
||||
capture = timerConfig->forcedOverflowTimerValue - 1;
|
||||
timerConfig->forcedOverflowTimerValue = 0;
|
||||
} else {
|
||||
|
@ -635,7 +635,7 @@ static void timCCxHandler(TIM_TypeDef *tim, timerConfig_t *timerConfig)
|
|||
}
|
||||
|
||||
timerOvrHandlerRec_t *cb = timerConfig->overflowCallbackActive;
|
||||
while(cb) {
|
||||
while (cb) {
|
||||
cb->fn(cb, capture);
|
||||
cb = cb->next;
|
||||
}
|
||||
|
@ -660,7 +660,7 @@ static void timCCxHandler(TIM_TypeDef *tim, timerConfig_t *timerConfig)
|
|||
tim->SR = ~TIM_IT_Update;
|
||||
capture = tim->ARR;
|
||||
timerOvrHandlerRec_t *cb = timerConfig->overflowCallbackActive;
|
||||
while(cb) {
|
||||
while (cb) {
|
||||
cb->fn(cb, capture);
|
||||
cb = cb->next;
|
||||
}
|
||||
|
@ -815,10 +815,10 @@ void timerInit(void)
|
|||
#endif
|
||||
|
||||
// initialize timer channel structures
|
||||
for(int i = 0; i < USABLE_TIMER_CHANNEL_COUNT; i++) {
|
||||
for (int i = 0; i < USABLE_TIMER_CHANNEL_COUNT; i++) {
|
||||
timerChannelInfo[i].type = TYPE_FREE;
|
||||
}
|
||||
for(int i = 0; i < USED_TIMER_COUNT; i++) {
|
||||
for (int i = 0; i < USED_TIMER_COUNT; i++) {
|
||||
timerInfo[i].priority = ~0;
|
||||
}
|
||||
}
|
||||
|
@ -829,18 +829,18 @@ void timerInit(void)
|
|||
void timerStart(void)
|
||||
{
|
||||
#if 0
|
||||
for(unsigned timer = 0; timer < USED_TIMER_COUNT; timer++) {
|
||||
for (unsigned timer = 0; timer < USED_TIMER_COUNT; timer++) {
|
||||
int priority = -1;
|
||||
int irq = -1;
|
||||
for(unsigned hwc = 0; hwc < USABLE_TIMER_CHANNEL_COUNT; hwc++)
|
||||
if((timerChannelInfo[hwc].type != TYPE_FREE) && (timerHardware[hwc].tim == usedTimers[timer])) {
|
||||
for (unsigned hwc = 0; hwc < USABLE_TIMER_CHANNEL_COUNT; hwc++)
|
||||
if ((timerChannelInfo[hwc].type != TYPE_FREE) && (timerHardware[hwc].tim == usedTimers[timer])) {
|
||||
// TODO - move IRQ to timer info
|
||||
irq = timerHardware[hwc].irq;
|
||||
}
|
||||
// TODO - aggregate required timer paramaters
|
||||
configTimeBase(usedTimers[timer], 0, 1);
|
||||
TIM_Cmd(usedTimers[timer], ENABLE);
|
||||
if(priority >= 0) { // maybe none of the channels was configured
|
||||
if (priority >= 0) { // maybe none of the channels was configured
|
||||
NVIC_InitTypeDef NVIC_InitStructure;
|
||||
|
||||
NVIC_InitStructure.NVIC_IRQChannel = irq;
|
||||
|
|
|
@ -51,7 +51,7 @@ void TIM_SelectOCxM_NoDisable(TIM_TypeDef* TIMx, uint16_t TIM_Channel, uint16_t
|
|||
tmp = (uint32_t) TIMx;
|
||||
tmp += CCMR_Offset;
|
||||
|
||||
if((TIM_Channel == TIM_Channel_1) ||(TIM_Channel == TIM_Channel_3)) {
|
||||
if ((TIM_Channel == TIM_Channel_1) ||(TIM_Channel == TIM_Channel_3)) {
|
||||
tmp += (TIM_Channel>>1);
|
||||
|
||||
/* Reset the OCxM bits in the CCMRx register */
|
||||
|
|
|
@ -51,7 +51,7 @@ void TIM_SelectOCxM_NoDisable(TIM_TypeDef* TIMx, uint16_t TIM_Channel, uint16_t
|
|||
tmp = (uint32_t) TIMx;
|
||||
tmp += CCMR_Offset;
|
||||
|
||||
if((TIM_Channel == TIM_Channel_1) ||(TIM_Channel == TIM_Channel_3)) {
|
||||
if ((TIM_Channel == TIM_Channel_1) ||(TIM_Channel == TIM_Channel_3)) {
|
||||
tmp += (TIM_Channel>>1);
|
||||
|
||||
/* Reset the OCxM bits in the CCMRx register */
|
||||
|
|
|
@ -47,7 +47,7 @@ void TIM_SelectOCxM_NoDisable(TIM_TypeDef* TIMx, uint16_t TIM_Channel, uint16_t
|
|||
tmp = (uint32_t) TIMx;
|
||||
tmp += CCMR_Offset;
|
||||
|
||||
if((TIM_Channel == TIM_CHANNEL_1) ||(TIM_Channel == TIM_CHANNEL_3)) {
|
||||
if ((TIM_Channel == TIM_CHANNEL_1) ||(TIM_Channel == TIM_CHANNEL_3)) {
|
||||
tmp += (TIM_Channel>>1);
|
||||
|
||||
/* Reset the OCxM bits in the CCMRx register */
|
||||
|
|
|
@ -1096,7 +1096,7 @@ static void printValuePointer(const clivalue_t *var, const void *valuePointer, u
|
|||
return; // return from case for float only
|
||||
}
|
||||
|
||||
switch(var->type & VALUE_MODE_MASK) {
|
||||
switch (var->type & VALUE_MODE_MASK) {
|
||||
case MODE_MAX:
|
||||
case MODE_DIRECT:
|
||||
if ((var->type & VALUE_TYPE_MASK) == VAR_UINT32)
|
||||
|
@ -1529,7 +1529,7 @@ static void cliSerial(char *cmdline)
|
|||
break;
|
||||
}
|
||||
|
||||
switch(i) {
|
||||
switch (i) {
|
||||
case 0:
|
||||
if (baudRateIndex < BAUD_1200 || baudRateIndex > BAUD_2470000) {
|
||||
continue;
|
||||
|
@ -1582,7 +1582,7 @@ static void cliSerialPassthrough(char *cmdline)
|
|||
int index = 0;
|
||||
|
||||
while (tok != NULL) {
|
||||
switch(index) {
|
||||
switch (index) {
|
||||
case 0:
|
||||
id = atoi(tok);
|
||||
break;
|
||||
|
@ -2038,7 +2038,7 @@ static void cliModeColor(char *cmdline)
|
|||
int modeIdx = args[MODE];
|
||||
int funIdx = args[FUNCTION];
|
||||
int color = args[COLOR];
|
||||
if(!setModeColor(modeIdx, funIdx, color)) {
|
||||
if (!setModeColor(modeIdx, funIdx, color)) {
|
||||
cliShowParseError();
|
||||
return;
|
||||
}
|
||||
|
@ -2697,7 +2697,7 @@ static void cliMap(char *cmdline)
|
|||
|
||||
static const char *checkCommand(const char *cmdLine, const char *command)
|
||||
{
|
||||
if(!strncasecmp(cmdLine, command, strlen(command)) // command names match
|
||||
if (!strncasecmp(cmdLine, command, strlen(command)) // command names match
|
||||
&& !isalnum((unsigned)cmdLine[strlen(command)])) { // next characted in bufffer is not alphanumeric (command is correctly terminated)
|
||||
return cmdLine + strlen(command) + 1;
|
||||
} else {
|
||||
|
@ -3016,7 +3016,7 @@ static void cliSet(char *cmdline)
|
|||
switch (mode) {
|
||||
case MODE_MAX:
|
||||
case MODE_DIRECT: {
|
||||
if(*eqptr != 0 && strspn(eqptr, "0123456789.+-") == strlen(eqptr)) {
|
||||
if (*eqptr != 0 && strspn(eqptr, "0123456789.+-") == strlen(eqptr)) {
|
||||
int32_t value = 0;
|
||||
uint32_t uvalue = 0;
|
||||
float valuef = 0;
|
||||
|
@ -3613,11 +3613,11 @@ void cliProcess(void)
|
|||
|
||||
const clicmd_t *cmd;
|
||||
for (cmd = cmdTable; cmd < cmdTable + ARRAYLEN(cmdTable); cmd++) {
|
||||
if(!strncasecmp(cliBuffer, cmd->name, strlen(cmd->name)) // command names match
|
||||
if (!strncasecmp(cliBuffer, cmd->name, strlen(cmd->name)) // command names match
|
||||
&& !isalnum((unsigned)cliBuffer[strlen(cmd->name)])) // next characted in bufffer is not alphanumeric (command is correctly terminated)
|
||||
break;
|
||||
}
|
||||
if(cmd < cmdTable + ARRAYLEN(cmdTable))
|
||||
if (cmd < cmdTable + ARRAYLEN(cmdTable))
|
||||
cmd->func(cliBuffer + strlen(cmd->name) + 1);
|
||||
else
|
||||
cliPrint("Unknown command, try 'help'");
|
||||
|
|
|
@ -461,7 +461,7 @@ static void activateConfig(void)
|
|||
activateControlRateConfig();
|
||||
|
||||
resetAdjustmentStates();
|
||||
|
||||
|
||||
updateUsedModeActivationConditionFlags();
|
||||
|
||||
failsafeReset();
|
||||
|
|
|
@ -478,7 +478,7 @@ void processRx(timeUs_t currentTimeUs)
|
|||
// Handle passthrough mode
|
||||
if (STATE(FIXED_WING)) {
|
||||
if ((IS_RC_MODE_ACTIVE(BOXPASSTHRU) && !navigationRequiresAngleMode() && !failsafeRequiresAngleMode()) || // Normal activation of passthrough
|
||||
(!ARMING_FLAG(ARMED) && isCalibrating())){ // Backup - if we are not armed - enforce passthrough while calibrating
|
||||
(!ARMING_FLAG(ARMED) && isCalibrating())){ // Backup - if we are not armed - enforce passthrough while calibrating
|
||||
ENABLE_FLIGHT_MODE(PASSTHRU_MODE);
|
||||
} else {
|
||||
DISABLE_FLIGHT_MODE(PASSTHRU_MODE);
|
||||
|
|
|
@ -669,7 +669,7 @@ static bool mspFcProcessOutCommand(uint8_t cmdMSP, sbuf_t *dst, mspPostProcessFn
|
|||
sbufWriteU8(dst, (uint8_t)constrain(vbat, 0, 255));
|
||||
sbufWriteU16(dst, (uint16_t)constrain(mAhDrawn, 0, 0xFFFF)); // milliamp hours drawn from battery
|
||||
sbufWriteU16(dst, rssi);
|
||||
if(batteryConfig()->multiwiiCurrentMeterOutput) {
|
||||
if (batteryConfig()->multiwiiCurrentMeterOutput) {
|
||||
sbufWriteU16(dst, (uint16_t)constrain(amperage * 10, 0, 0xFFFF)); // send amperage in 0.001 A steps. Negative range is truncated to zero
|
||||
} else
|
||||
sbufWriteU16(dst, (int16_t)constrain(amperage, -0x8000, 0x7FFF)); // send amperage in 0.01 A steps, range is -320A to 320A
|
||||
|
@ -1746,7 +1746,7 @@ static mspResult_e mspFcProcessInCommand(uint8_t cmdMSP, sbuf_t *src)
|
|||
positionEstimationConfigMutable()->w_xy_gps_p = constrainf(sbufReadU16(src) / 100.0f, 0.0f, 10.0f);
|
||||
positionEstimationConfigMutable()->w_xy_gps_v = constrainf(sbufReadU16(src) / 100.0f, 0.0f, 10.0f);
|
||||
gpsConfigMutable()->gpsMinSats = constrain(sbufReadU8(src), 5, 10);
|
||||
positionEstimationConfigMutable()->use_gps_velned = constrain(sbufReadU8(src), 0, 1);
|
||||
positionEstimationConfigMutable()->use_gps_velned = constrain(sbufReadU8(src), 0, 1);
|
||||
#endif
|
||||
break;
|
||||
|
||||
|
|
|
@ -206,7 +206,7 @@ static void applyStepAdjustment(controlRateConfig_t *controlRateConfig, uint8_t
|
|||
beeperConfirmationBeeps(1);
|
||||
}
|
||||
int newValue;
|
||||
switch(adjustmentFunction) {
|
||||
switch (adjustmentFunction) {
|
||||
case ADJUSTMENT_RC_EXPO:
|
||||
newValue = constrain((int)controlRateConfig->rcExpo8 + delta, 0, 100); // FIXME magic numbers repeated in serial_cli.c
|
||||
controlRateConfig->rcExpo8 = newValue;
|
||||
|
@ -316,7 +316,7 @@ static void applySelectAdjustment(uint8_t adjustmentFunction, uint8_t position)
|
|||
{
|
||||
bool applied = false;
|
||||
|
||||
switch(adjustmentFunction) {
|
||||
switch (adjustmentFunction) {
|
||||
case ADJUSTMENT_RATE_PROFILE:
|
||||
if (getCurrentControlRateProfile() != position) {
|
||||
changeControlRateProfile(position);
|
||||
|
|
|
@ -280,7 +280,7 @@ void processRcStickPositions(throttleStatus_e throttleStatus, bool disarm_kill_s
|
|||
beeper(success ? BEEPER_ACTION_SUCCESS : BEEPER_ACTION_FAIL);
|
||||
}
|
||||
#endif
|
||||
|
||||
|
||||
// Multiple configuration profiles
|
||||
if (rcSticks == THR_LO + YAW_LO + PIT_CE + ROL_LO) // ROLL left -> Profile 1
|
||||
i = 1;
|
||||
|
|
|
@ -89,7 +89,7 @@ typedef enum {
|
|||
|
||||
extern uint32_t stateFlags;
|
||||
|
||||
typedef enum {
|
||||
typedef enum {
|
||||
FLM_MANUAL,
|
||||
FLM_ACRO,
|
||||
FLM_ANGLE,
|
||||
|
|
|
@ -13,7 +13,7 @@ void statsOnDisarm(void);
|
|||
|
||||
#else
|
||||
|
||||
#define statsOnArm() do {} while(0)
|
||||
#define statsOnDisarm() do {} while(0)
|
||||
#define statsOnArm() do {} while (0)
|
||||
#define statsOnDisarm() do {} while (0)
|
||||
|
||||
#endif
|
||||
|
|
|
@ -343,7 +343,7 @@ static void imuMahonyAHRSupdate(float dt, float gx, float gy, float gz,
|
|||
}
|
||||
|
||||
// Compute and apply integral feedback if enabled
|
||||
if(imuRuntimeConfig.dcm_ki_mag > 0.0f) {
|
||||
if (imuRuntimeConfig.dcm_ki_mag > 0.0f) {
|
||||
// Stop integrating if spinning beyond the certain limit
|
||||
if (spin_rate_sq < sq(DEGREES_TO_RADIANS(SPIN_RATE_LIMIT))) {
|
||||
integralMagX += imuRuntimeConfig.dcm_ki_mag * ex * dt; // integral error scaled by Ki
|
||||
|
@ -382,7 +382,7 @@ static void imuMahonyAHRSupdate(float dt, float gx, float gy, float gz,
|
|||
ez = (ax * rMat[2][1] - ay * rMat[2][0]);
|
||||
|
||||
// Compute and apply integral feedback if enabled
|
||||
if(imuRuntimeConfig.dcm_ki_acc > 0.0f) {
|
||||
if (imuRuntimeConfig.dcm_ki_acc > 0.0f) {
|
||||
// Stop integrating if spinning beyond the certain limit
|
||||
if (spin_rate_sq < sq(DEGREES_TO_RADIANS(SPIN_RATE_LIMIT))) {
|
||||
integralAccX += imuRuntimeConfig.dcm_ki_acc * ex * dt; // integral error scaled by Ki
|
||||
|
|
|
@ -255,7 +255,7 @@ static const mixer_t mixerTable[] = {
|
|||
//DEF_MIXER( MIXER_DUALCOPTER, PLATFORM_MULTIROTOR, 0, false, false, NULL ),
|
||||
//DEF_MIXER( MIXER_SINGLECOPTER, PLATFORM_MULTIROTOR, 0, false, false, NULL ),
|
||||
|
||||
#if !defined(DISABLE_UNCOMMON_MIXERS)
|
||||
#if !defined(DISABLE_UNCOMMON_MIXERS)
|
||||
DEF_MIXER( MIXER_Y4, PLATFORM_MULTIROTOR, 4, false, false, mixerY4 ),
|
||||
DEF_MIXER( MIXER_ATAIL4, PLATFORM_MULTIROTOR, 4, false, false, mixerAtail4 ),
|
||||
DEF_MIXER( MIXER_VTAIL4, PLATFORM_MULTIROTOR, 4, false, false, mixerVtail4 ),
|
||||
|
@ -281,7 +281,7 @@ const mixer_t * findMixer(mixerMode_e mixerMode)
|
|||
{
|
||||
#ifndef USE_QUAD_MIXER_ONLY
|
||||
for (unsigned ii = 0; ii < sizeof(mixerTable)/sizeof(mixerTable[0]); ii++) {
|
||||
if (mixerTable[ii].mixerMode == mixerMode)
|
||||
if (mixerTable[ii].mixerMode == mixerMode)
|
||||
return &mixerTable[ii];
|
||||
}
|
||||
#else
|
||||
|
|
|
@ -204,7 +204,7 @@ void pidInit(void)
|
|||
}
|
||||
|
||||
// Calculate max overall tilt (max pitch + max roll combined) as a limit to heading hold
|
||||
headingHoldCosZLimit = cos_approx(DECIDEGREES_TO_RADIANS(pidProfile()->max_angle_inclination[FD_ROLL])) *
|
||||
headingHoldCosZLimit = cos_approx(DECIDEGREES_TO_RADIANS(pidProfile()->max_angle_inclination[FD_ROLL])) *
|
||||
cos_approx(DECIDEGREES_TO_RADIANS(pidProfile()->max_angle_inclination[FD_PITCH]));
|
||||
}
|
||||
|
||||
|
@ -213,7 +213,7 @@ bool pidInitFilters(void)
|
|||
{
|
||||
const uint32_t refreshRate = getPidUpdateRate();
|
||||
notchFilterApplyFn = nullFilterApply;
|
||||
if(refreshRate != 0 && pidProfile()->dterm_soft_notch_hz != 0){
|
||||
if (refreshRate != 0 && pidProfile()->dterm_soft_notch_hz != 0){
|
||||
notchFilterApplyFn = (filterApplyFnPtr)biquadFilterApply;
|
||||
for (int axis = 0; axis < 3; ++ axis) {
|
||||
biquadFilterInitNotch(&pidState[axis].deltaNotchFilter, refreshRate, pidProfile()->dterm_soft_notch_hz, pidProfile()->dterm_soft_notch_cutoff);
|
||||
|
|
|
@ -112,7 +112,7 @@ typedef struct pidAutotuneConfig_s {
|
|||
uint16_t fw_undershoot_time; // Time [ms] to detect sustained undershoot
|
||||
uint8_t fw_max_rate_threshold; // Threshold [%] of max rate to consider autotune detection
|
||||
uint8_t fw_ff_to_p_gain; // FF to P gain (strength relationship) [%]
|
||||
uint16_t fw_ff_to_i_time_constant; // FF to I time (defines time for I to reach the same level of response as FF) [ms]
|
||||
uint16_t fw_ff_to_i_time_constant; // FF to I time (defines time for I to reach the same level of response as FF) [ms]
|
||||
} pidAutotuneConfig_t;
|
||||
|
||||
PG_DECLARE_PROFILE(pidProfile_t, pidProfile);
|
||||
|
|
|
@ -195,7 +195,7 @@ void autotuneFixedWingUpdate(const flight_dynamics_index_t axis, float desiredRa
|
|||
const timeDelta_t stateTimeMs = currentTimeMs - tuneCurrent[axis].stateEnterTime;
|
||||
bool gainsUpdated = false;
|
||||
|
||||
switch(tuneCurrent[axis].state) {
|
||||
switch (tuneCurrent[axis].state) {
|
||||
case DEMAND_TOO_LOW:
|
||||
break;
|
||||
case DEMAND_OVERSHOOT:
|
||||
|
|
|
@ -241,7 +241,7 @@ void servosInit(void)
|
|||
|
||||
/*
|
||||
* Compute scaling factor for upper and lower servo throw
|
||||
*/
|
||||
*/
|
||||
for (uint8_t i = 0; i < MAX_SUPPORTED_SERVOS; i++) {
|
||||
servoMetadata[i].scaleMax = (servoParams(i)->max - servoParams(i)->middle) / 500.0f;
|
||||
servoMetadata[i].scaleMin = (servoParams(i)->middle - servoParams(i)->min) / 500.0f;
|
||||
|
@ -411,11 +411,11 @@ void servoMixer(float dT)
|
|||
for (int i = 0; i < servoRuleCount; i++) {
|
||||
const uint8_t target = currentServoMixer[i].targetChannel;
|
||||
const uint8_t from = currentServoMixer[i].inputSource;
|
||||
|
||||
|
||||
/*
|
||||
* Apply mixer speed limit. 1 [one] speed unit is defined as 10us/s:
|
||||
* Apply mixer speed limit. 1 [one] speed unit is defined as 10us/s:
|
||||
* 0 = no limiting
|
||||
* 1 = 10us/s -> full servo sweep (from 1000 to 2000) is performed in 100s
|
||||
* 1 = 10us/s -> full servo sweep (from 1000 to 2000) is performed in 100s
|
||||
* 10 = 100us/s -> full sweep (from 1000 to 2000) is performed in 10s
|
||||
* 100 = 1000us/s -> full sweep in 1s
|
||||
*/
|
||||
|
@ -425,7 +425,7 @@ void servoMixer(float dT)
|
|||
}
|
||||
|
||||
for (int i = 0; i < MAX_SUPPORTED_SERVOS; i++) {
|
||||
|
||||
|
||||
/*
|
||||
* Apply servo rate
|
||||
*/
|
||||
|
@ -433,7 +433,7 @@ void servoMixer(float dT)
|
|||
|
||||
/*
|
||||
* Perform acumulated servo output scaling to match servo min and max values
|
||||
* Important: is servo rate is > 100%, total servo output might be bigger than
|
||||
* Important: is servo rate is > 100%, total servo output might be bigger than
|
||||
* min/max
|
||||
*/
|
||||
if (servo[i] > 0) {
|
||||
|
@ -449,7 +449,7 @@ void servoMixer(float dT)
|
|||
|
||||
/*
|
||||
* Constrain servo position to min/max to prevent servo damage
|
||||
* If servo was saturated above min/max, that means that user most probably
|
||||
* If servo was saturated above min/max, that means that user most probably
|
||||
* allowed the situation when smix weight sum for an output was above 100
|
||||
*/
|
||||
servo[i] = constrain(servo[i], servoParams(i)->min, servoParams(i)->max);
|
||||
|
|
|
@ -258,7 +258,7 @@ void beeperConfirmationBeeps(uint8_t beepCount)
|
|||
|
||||
i = 0;
|
||||
cLimit = beepCount * 2;
|
||||
if(cLimit > MAX_MULTI_BEEPS)
|
||||
if (cLimit > MAX_MULTI_BEEPS)
|
||||
cLimit = MAX_MULTI_BEEPS; //stay within array size
|
||||
do {
|
||||
beep_multiBeeps[i++] = BEEPER_CONFIRMATION_BEEP_DURATION; // 20ms beep
|
||||
|
|
|
@ -323,10 +323,10 @@ static void bitmapDecompressAndShow(uint8_t *bitmap)
|
|||
bitmap++;
|
||||
uint16_t bitmapSize = (width * height) / 8;
|
||||
for (i = 0; i < bitmapSize; i++) {
|
||||
if(count == 0) {
|
||||
if (count == 0) {
|
||||
data = *bitmap;
|
||||
bitmap++;
|
||||
if(data == *bitmap) {
|
||||
if (data == *bitmap) {
|
||||
bitmap++;
|
||||
count = *bitmap;
|
||||
bitmap++;
|
||||
|
@ -503,7 +503,7 @@ void dashboardUpdate(timeUs_t currentTimeUs)
|
|||
return;
|
||||
}
|
||||
|
||||
switch(currentPageId) {
|
||||
switch (currentPageId) {
|
||||
case PAGE_WELCOME:
|
||||
showWelcomePage();
|
||||
break;
|
||||
|
|
|
@ -424,14 +424,14 @@ void gpsEnablePassthrough(serialPort_t *gpsPassthroughPort)
|
|||
waitForSerialPortToFinishTransmitting(gpsState.gpsPort);
|
||||
waitForSerialPortToFinishTransmitting(gpsPassthroughPort);
|
||||
|
||||
if(!(gpsState.gpsPort->mode & MODE_TX))
|
||||
if (!(gpsState.gpsPort->mode & MODE_TX))
|
||||
serialSetMode(gpsState.gpsPort, gpsState.gpsPort->mode | MODE_TX);
|
||||
|
||||
LED0_OFF;
|
||||
LED1_OFF;
|
||||
|
||||
char c;
|
||||
while(1) {
|
||||
while (1) {
|
||||
if (serialRxBytesWaiting(gpsState.gpsPort)) {
|
||||
LED0_ON;
|
||||
c = serialRead(gpsState.gpsPort);
|
||||
|
|
|
@ -110,7 +110,7 @@ bool gpsPollI2CNAV(void)
|
|||
bool gpsHandleI2CNAV(void)
|
||||
{
|
||||
// Process state
|
||||
switch(gpsState.state) {
|
||||
switch (gpsState.state) {
|
||||
default:
|
||||
return false;
|
||||
|
||||
|
|
|
@ -130,7 +130,7 @@ int32_t decodeLong(uint32_t idx, uint8_t mask)
|
|||
{
|
||||
union { uint32_t l; uint8_t b[4]; } val;
|
||||
val.l=idx;
|
||||
for(int i = 0; i < 4; i++) val.b[i] ^= mask;
|
||||
for (int i = 0; i < 4; i++) val.b[i] ^= mask;
|
||||
return val.l;
|
||||
}
|
||||
|
||||
|
@ -138,7 +138,7 @@ int16_t decodeShort(uint16_t idx, uint8_t mask)
|
|||
{
|
||||
union { uint16_t s; uint8_t b[2]; } val;
|
||||
val.s=idx;
|
||||
for(int i = 0; i < 2; i++) val.b[i] ^= mask;
|
||||
for (int i = 0; i < 2; i++) val.b[i] ^= mask;
|
||||
return val.s;
|
||||
}
|
||||
|
||||
|
@ -345,7 +345,7 @@ bool gpsHandleNAZA(void)
|
|||
bool hasNewData = gpsReceiveData();
|
||||
|
||||
// Process state
|
||||
switch(gpsState.state) {
|
||||
switch (gpsState.state) {
|
||||
default:
|
||||
return false;
|
||||
|
||||
|
|
|
@ -126,7 +126,7 @@ static bool gpsNewFrameNMEA(char c)
|
|||
|
||||
switch (gps_frame) {
|
||||
case FRAME_GGA: //************* GPGGA FRAME parsing
|
||||
switch(param) {
|
||||
switch (param) {
|
||||
// case 1: // Time information
|
||||
// break;
|
||||
case 2:
|
||||
|
@ -162,7 +162,7 @@ static bool gpsNewFrameNMEA(char c)
|
|||
}
|
||||
break;
|
||||
case FRAME_RMC: //************* GPRMC FRAME parsing
|
||||
switch(param) {
|
||||
switch (param) {
|
||||
case 7:
|
||||
gps_Msg.speed = ((grab_fields(string, 1) * 5144L) / 1000L); // speed in cm/s added by Mis
|
||||
break;
|
||||
|
@ -272,7 +272,7 @@ bool gpsHandleNMEA(void)
|
|||
bool hasNewData = gpsReceiveData();
|
||||
|
||||
// Process state
|
||||
switch(gpsState.state) {
|
||||
switch (gpsState.state) {
|
||||
default:
|
||||
return false;
|
||||
|
||||
|
|
|
@ -480,7 +480,7 @@ static bool gpsParceFrameUBLOX(void)
|
|||
_new_speed = true;
|
||||
break;
|
||||
case MSG_VER:
|
||||
if(_class == CLASS_MON) {
|
||||
if (_class == CLASS_MON) {
|
||||
//uint32_t swver = _buffer.ver.swVersion;
|
||||
gpsState.hwVersion = atoi(_buffer.ver.hwVersion);
|
||||
}
|
||||
|
@ -636,7 +636,7 @@ static bool gpsConfigure(void)
|
|||
#ifdef GPS_PROTO_UBLOX_NEO7PLUS
|
||||
configureMSG(MSG_CLASS_UBX, MSG_PVT, 0);
|
||||
}
|
||||
else if(gpsState.gpsConfig->provider == GPS_UBLOX7PLUS) {
|
||||
else if (gpsState.gpsConfig->provider == GPS_UBLOX7PLUS) {
|
||||
configureMSG(MSG_CLASS_UBX, MSG_POSLLH, 0);
|
||||
configureMSG(MSG_CLASS_UBX, MSG_STATUS, 0);
|
||||
configureMSG(MSG_CLASS_UBX, MSG_SOL, 0);
|
||||
|
@ -655,7 +655,7 @@ static bool gpsConfigure(void)
|
|||
configureRATE(200); // 5Hz
|
||||
#ifdef GPS_PROTO_UBLOX_NEO7PLUS
|
||||
}
|
||||
else if(gpsState.gpsConfig->provider == GPS_UBLOX7PLUS) {
|
||||
else if (gpsState.gpsConfig->provider == GPS_UBLOX7PLUS) {
|
||||
configureRATE(100); // 10Hz
|
||||
}
|
||||
#endif
|
||||
|
@ -751,7 +751,7 @@ bool gpsHandleUBLOX(void)
|
|||
bool hasNewData = gpsReceiveData();
|
||||
|
||||
// Process state
|
||||
switch(gpsState.state) {
|
||||
switch (gpsState.state) {
|
||||
default:
|
||||
return false;
|
||||
|
||||
|
|
|
@ -864,7 +864,7 @@ static void applyLedAnimationLayer(bool updateNow, timeUs_t *timer)
|
|||
{
|
||||
static uint8_t frameCounter = 0;
|
||||
const int animationFrames = ledGridHeight;
|
||||
if(updateNow) {
|
||||
if (updateNow) {
|
||||
frameCounter = (frameCounter + 1 < animationFrames) ? frameCounter + 1 : 0;
|
||||
*timer += LED_STRIP_HZ(20);
|
||||
}
|
||||
|
@ -993,7 +993,7 @@ bool parseColor(int index, const char *colorConfig)
|
|||
};
|
||||
for (int componentIndex = 0; result && componentIndex < HSV_COLOR_COMPONENT_COUNT; componentIndex++) {
|
||||
int val = atoi(remainingCharacters);
|
||||
if(val > hsv_limit[componentIndex]) {
|
||||
if (val > hsv_limit[componentIndex]) {
|
||||
result = false;
|
||||
break;
|
||||
}
|
||||
|
@ -1034,7 +1034,7 @@ bool setModeColor(ledModeIndex_e modeIndex, int modeColorIndex, int colorIndex)
|
|||
if (colorIndex < 0 || colorIndex >= LED_CONFIGURABLE_COLOR_COUNT)
|
||||
return false;
|
||||
if (modeIndex < LED_MODE_COUNT) { // modeIndex_e is unsigned, so one-sided test is enough
|
||||
if(modeColorIndex < 0 || modeColorIndex >= LED_DIRECTION_COUNT)
|
||||
if (modeColorIndex < 0 || modeColorIndex >= LED_DIRECTION_COUNT)
|
||||
return false;
|
||||
ledStripConfigMutable()->modeColors[modeIndex].color[modeColorIndex] = colorIndex;
|
||||
} else if (modeIndex == LED_SPECIAL) {
|
||||
|
|
|
@ -638,7 +638,7 @@ void pgResetFn_osdConfig(osdConfig_t *osdConfig)
|
|||
osdConfig->item_pos[OSD_HOME_DIST] = OSD_POS(1, 1);
|
||||
osdConfig->item_pos[OSD_HEADING] = OSD_POS(12, 1);
|
||||
osdConfig->item_pos[OSD_GPS_SPEED] = OSD_POS(23, 1);
|
||||
|
||||
|
||||
osdConfig->item_pos[OSD_THROTTLE_POS] = OSD_POS(1, 2) | VISIBLE_FLAG;
|
||||
osdConfig->item_pos[OSD_CURRENT_DRAW] = OSD_POS(1, 3) | VISIBLE_FLAG;
|
||||
osdConfig->item_pos[OSD_MAH_DRAWN] = OSD_POS(1, 4) | VISIBLE_FLAG;
|
||||
|
@ -648,18 +648,18 @@ void pgResetFn_osdConfig(osdConfig_t *osdConfig)
|
|||
osdConfig->item_pos[OSD_HOME_DIR] = OSD_POS(14, 11);
|
||||
osdConfig->item_pos[OSD_ARTIFICIAL_HORIZON] = OSD_POS(8, 6) | VISIBLE_FLAG;
|
||||
osdConfig->item_pos[OSD_HORIZON_SIDEBARS] = OSD_POS(8, 6) | VISIBLE_FLAG;
|
||||
|
||||
|
||||
osdConfig->item_pos[OSD_CRAFT_NAME] = OSD_POS(20, 2);
|
||||
osdConfig->item_pos[OSD_VTX_CHANNEL] = OSD_POS(8, 6);
|
||||
|
||||
osdConfig->item_pos[OSD_ONTIME] = OSD_POS(23, 10) | VISIBLE_FLAG;
|
||||
osdConfig->item_pos[OSD_FLYTIME] = OSD_POS(23, 11) | VISIBLE_FLAG;
|
||||
osdConfig->item_pos[OSD_GPS_SATS] = OSD_POS(0, 11) | VISIBLE_FLAG;
|
||||
|
||||
|
||||
osdConfig->item_pos[OSD_GPS_LAT] = OSD_POS(0, 12);
|
||||
osdConfig->item_pos[OSD_FLYMODE] = OSD_POS(12, 12) | VISIBLE_FLAG;
|
||||
osdConfig->item_pos[OSD_GPS_LON] = OSD_POS(18, 12);
|
||||
|
||||
|
||||
osdConfig->item_pos[OSD_ROLL_PIDS] = OSD_POS(2, 10);
|
||||
osdConfig->item_pos[OSD_PITCH_PIDS] = OSD_POS(2, 11);
|
||||
osdConfig->item_pos[OSD_YAW_PIDS] = OSD_POS(2, 12);
|
||||
|
@ -785,7 +785,7 @@ static void osdUpdateStats(void)
|
|||
value = gpsSol.groundSpeed;
|
||||
if (stats.max_speed < value)
|
||||
stats.max_speed = value;
|
||||
|
||||
|
||||
if (stats.max_distance < GPS_distanceToHome)
|
||||
stats.max_distance = GPS_distanceToHome;
|
||||
}
|
||||
|
@ -821,7 +821,7 @@ static void osdShowStats(void)
|
|||
max7456Write(2, top, "MAX SPEED :");
|
||||
osdFormatVelocityStr(buff, stats.max_speed);
|
||||
max7456Write(22, top++, buff);
|
||||
|
||||
|
||||
max7456Write(2, top, "MAX DISTANCE :");
|
||||
osdFormatDistanceStr(buff, stats.max_distance*100);
|
||||
max7456Write(22, top++, buff);
|
||||
|
|
|
@ -319,7 +319,7 @@ serialPort_t *openSerialPort(
|
|||
|
||||
serialPort_t *serialPort = NULL;
|
||||
|
||||
switch(identifier) {
|
||||
switch (identifier) {
|
||||
#ifdef USE_VCP
|
||||
case SERIAL_PORT_USB_VCP:
|
||||
serialPort = usbVcpOpen();
|
||||
|
@ -526,7 +526,7 @@ void serialPassthrough(serialPort_t *left, serialPort_t *right, serialConsumer
|
|||
// Either port might be open in a mode other than MODE_RXTX. We rely on
|
||||
// serialRxBytesWaiting() to do the right thing for a TX only port. No
|
||||
// special handling is necessary OR performed.
|
||||
while(1) {
|
||||
while (1) {
|
||||
// TODO: maintain a timestamp of last data received. Use this to
|
||||
// implement a guard interval and check for `+++` as an escape sequence
|
||||
// to return to CLI command mode.
|
||||
|
|
|
@ -139,7 +139,7 @@ uint8_t esc4wayInit(void)
|
|||
pwmIOConfiguration_t *pwmIOConfiguration = pwmGetOutputConfiguration();
|
||||
for (volatile uint8_t i = 0; i < pwmIOConfiguration->ioCount; i++) {
|
||||
if ((pwmIOConfiguration->ioConfigurations[i].flags & PWM_PF_MOTOR) == PWM_PF_MOTOR) {
|
||||
if(motor[pwmIOConfiguration->ioConfigurations[i].index] > 0) {
|
||||
if (motor[pwmIOConfiguration->ioConfigurations[i].index] > 0) {
|
||||
escHardware[escCount].io = IOGetByTag(pwmIOConfiguration->ioConfigurations[i].timerHardware->tag);
|
||||
setEscInput(escCount);
|
||||
setEscHi(escCount);
|
||||
|
@ -418,7 +418,7 @@ void esc4wayProcess(serialPort_t *mspPort)
|
|||
#endif
|
||||
bool isExitScheduled = false;
|
||||
|
||||
while(1) {
|
||||
while (1) {
|
||||
// restart looking for new sequence from host
|
||||
do {
|
||||
CRC_in.word = 0;
|
||||
|
@ -446,7 +446,7 @@ void esc4wayProcess(serialPort_t *mspPort)
|
|||
CRC_check.bytes[1] = ReadByte();
|
||||
CRC_check.bytes[0] = ReadByte();
|
||||
|
||||
if(CRC_check.word == CRC_in.word) {
|
||||
if (CRC_check.word == CRC_in.word) {
|
||||
ACK_OUT = ACK_OK;
|
||||
} else {
|
||||
ACK_OUT = ACK_I_INVALID_CRC;
|
||||
|
@ -461,12 +461,12 @@ void esc4wayProcess(serialPort_t *mspPort)
|
|||
ioMem.D_PTR_I = ParamBuf;
|
||||
|
||||
|
||||
switch(CMD) {
|
||||
switch (CMD) {
|
||||
// ******* Interface related stuff *******
|
||||
case cmd_InterfaceTestAlive:
|
||||
{
|
||||
if (isMcuConnected()){
|
||||
switch(CurrentInterfaceMode)
|
||||
switch (CurrentInterfaceMode)
|
||||
{
|
||||
#ifdef USE_SERIAL_4WAY_BLHELI_BOOTLOADER
|
||||
case imATM_BLB:
|
||||
|
@ -583,7 +583,7 @@ void esc4wayProcess(serialPort_t *mspPort)
|
|||
}
|
||||
O_PARAM_LEN = DeviceInfoSize; //4
|
||||
O_PARAM = (uint8_t *)&DeviceInfo;
|
||||
if(Connect(&DeviceInfo)) {
|
||||
if (Connect(&DeviceInfo)) {
|
||||
DeviceInfo.bytes[INTF_MODE_IDX] = CurrentInterfaceMode;
|
||||
} else {
|
||||
SET_DISCONNECTED;
|
||||
|
@ -595,7 +595,7 @@ void esc4wayProcess(serialPort_t *mspPort)
|
|||
#ifdef USE_SERIAL_4WAY_SK_BOOTLOADER
|
||||
case cmd_DeviceEraseAll:
|
||||
{
|
||||
switch(CurrentInterfaceMode)
|
||||
switch (CurrentInterfaceMode)
|
||||
{
|
||||
case imSK:
|
||||
{
|
||||
|
@ -639,13 +639,13 @@ void esc4wayProcess(serialPort_t *mspPort)
|
|||
wtf.D_FLASH_ADDR_L=Adress_L;
|
||||
wtf.D_PTR_I = BUF_I;
|
||||
*/
|
||||
switch(CurrentInterfaceMode)
|
||||
switch (CurrentInterfaceMode)
|
||||
{
|
||||
#ifdef USE_SERIAL_4WAY_BLHELI_BOOTLOADER
|
||||
case imSIL_BLB:
|
||||
case imATM_BLB:
|
||||
{
|
||||
if(!BL_ReadFlash(CurrentInterfaceMode, &ioMem))
|
||||
if (!BL_ReadFlash(CurrentInterfaceMode, &ioMem))
|
||||
{
|
||||
ACK_OUT = ACK_D_GENERAL_ERROR;
|
||||
}
|
||||
|
@ -655,7 +655,7 @@ void esc4wayProcess(serialPort_t *mspPort)
|
|||
#ifdef USE_SERIAL_4WAY_SK_BOOTLOADER
|
||||
case imSK:
|
||||
{
|
||||
if(!Stk_ReadFlash(&ioMem))
|
||||
if (!Stk_ReadFlash(&ioMem))
|
||||
{
|
||||
ACK_OUT = ACK_D_GENERAL_ERROR;
|
||||
}
|
||||
|
@ -706,7 +706,7 @@ void esc4wayProcess(serialPort_t *mspPort)
|
|||
default:
|
||||
ACK_OUT = ACK_I_INVALID_CMD;
|
||||
}
|
||||
if(ACK_OUT == ACK_OK)
|
||||
if (ACK_OUT == ACK_OK)
|
||||
{
|
||||
O_PARAM_LEN = ioMem.D_NUM_BYTES;
|
||||
O_PARAM = (uint8_t *)&ParamBuf;
|
||||
|
|
|
@ -94,7 +94,7 @@ static uint8_t suart_getc_(uint8_t *bt)
|
|||
uint16_t bitmask = 0;
|
||||
uint8_t bit = 0;
|
||||
while (micros() < btime);
|
||||
while(1) {
|
||||
while (1) {
|
||||
if (ESC_IS_HI)
|
||||
{
|
||||
bitmask |= (1 << bit);
|
||||
|
@ -117,8 +117,8 @@ static void suart_putc_(uint8_t *tx_b)
|
|||
// shift out stopbit first
|
||||
uint16_t bitmask = (*tx_b << 2) | 1 | (1 << 10);
|
||||
uint32_t btime = micros();
|
||||
while(1) {
|
||||
if(bitmask & 1) {
|
||||
while (1) {
|
||||
if (bitmask & 1) {
|
||||
ESC_SET_HI; // 1
|
||||
}
|
||||
else {
|
||||
|
@ -156,22 +156,22 @@ static uint8_t BL_ReadBuf(uint8_t *pstring, uint8_t len)
|
|||
LastCRC_16.word = 0;
|
||||
uint8_t LastACK = brNONE;
|
||||
do {
|
||||
if(!suart_getc_(pstring)) goto timeout;
|
||||
if (!suart_getc_(pstring)) goto timeout;
|
||||
ByteCrc(pstring);
|
||||
pstring++;
|
||||
len--;
|
||||
} while(len > 0);
|
||||
} while (len > 0);
|
||||
|
||||
if(isMcuConnected()) {
|
||||
if (isMcuConnected()) {
|
||||
//With CRC read 3 more
|
||||
if(!suart_getc_(&LastCRC_16.bytes[0])) goto timeout;
|
||||
if(!suart_getc_(&LastCRC_16.bytes[1])) goto timeout;
|
||||
if(!suart_getc_(&LastACK)) goto timeout;
|
||||
if (!suart_getc_(&LastCRC_16.bytes[0])) goto timeout;
|
||||
if (!suart_getc_(&LastCRC_16.bytes[1])) goto timeout;
|
||||
if (!suart_getc_(&LastACK)) goto timeout;
|
||||
if (CRC_16.word != LastCRC_16.word) {
|
||||
LastACK = brERRORCRC;
|
||||
}
|
||||
} else {
|
||||
if(!suart_getc_(&LastACK)) goto timeout;
|
||||
if (!suart_getc_(&LastACK)) goto timeout;
|
||||
}
|
||||
timeout:
|
||||
return (LastACK == brSUCCESS);
|
||||
|
@ -260,7 +260,7 @@ void BL_SendCMDRunRestartBootloader(uint8_32_u *pDeviceInfo)
|
|||
static uint8_t BL_SendCMDSetAddress(ioMem_t *pMem) //supports only 16 bit Adr
|
||||
{
|
||||
// skip if adr == 0xFFFF
|
||||
if((pMem->D_FLASH_ADDR_H == 0xFF) && (pMem->D_FLASH_ADDR_L == 0xFF)) return 1;
|
||||
if ((pMem->D_FLASH_ADDR_H == 0xFF) && (pMem->D_FLASH_ADDR_L == 0xFF)) return 1;
|
||||
uint8_t sCMD[] = {CMD_SET_ADDRESS, 0, pMem->D_FLASH_ADDR_H, pMem->D_FLASH_ADDR_L };
|
||||
BL_SendBuf(sCMD, 4);
|
||||
return (BL_GetACK(2) == brSUCCESS);
|
||||
|
@ -302,7 +302,7 @@ static uint8_t BL_WriteA(uint8_t cmd, ioMem_t *pMem, uint32_t timeout)
|
|||
|
||||
uint8_t BL_ReadFlash(uint8_t interface_mode, ioMem_t *pMem)
|
||||
{
|
||||
if(interface_mode == imATM_BLB) {
|
||||
if (interface_mode == imATM_BLB) {
|
||||
return BL_ReadA(CMD_READ_FLASH_ATM, pMem);
|
||||
} else {
|
||||
return BL_ReadA(CMD_READ_FLASH_SIL, pMem);
|
||||
|
|
|
@ -177,9 +177,9 @@ static uint8_t StkReadLeader(void)
|
|||
// Wait for the first bit
|
||||
uint32_t waitcycl; //250uS each
|
||||
|
||||
if((StkCmd == CMD_PROGRAM_EEPROM_ISP) || (StkCmd == CMD_CHIP_ERASE_ISP)) {
|
||||
if ((StkCmd == CMD_PROGRAM_EEPROM_ISP) || (StkCmd == CMD_CHIP_ERASE_ISP)) {
|
||||
waitcycl = STK_WAITCYLCES_EXT;
|
||||
} else if(StkCmd == CMD_SIGN_ON) {
|
||||
} else if (StkCmd == CMD_SIGN_ON) {
|
||||
waitcycl = STK_WAITCYLCES_START;
|
||||
} else {
|
||||
waitcycl= STK_WAITCYLCES;
|
||||
|
@ -272,7 +272,7 @@ static uint8_t _CMD_LOAD_ADDRESS(ioMem_t *pMem)
|
|||
{
|
||||
// ignore 0xFFFF
|
||||
// assume address is set before and we read or write the immediately following package
|
||||
if((pMem->D_FLASH_ADDR_H == 0xFF) && (pMem->D_FLASH_ADDR_L == 0xFF)) return 1;
|
||||
if ((pMem->D_FLASH_ADDR_H == 0xFF) && (pMem->D_FLASH_ADDR_L == 0xFF)) return 1;
|
||||
StkCmd = CMD_LOAD_ADDRESS;
|
||||
StkSendPacketHeader();
|
||||
StkSendByte(0); // hi byte Msg len
|
||||
|
|
|
@ -136,7 +136,7 @@ static int mspSerialEncode(mspPort_t *msp, mspPacket_t *packet)
|
|||
hdr[6] = (len >> 8) & 0xff;
|
||||
}
|
||||
|
||||
// We are allowed to send out the response if
|
||||
// We are allowed to send out the response if
|
||||
// a) TX buffer is completely empty (we are talking to well-behaving party that follows request-response scheduling;
|
||||
// this allows us to transmit jumbo frames bigger than TX buffer (serialWriteBuf will block, but for jumbo frames we don't care)
|
||||
// b) Response fits into TX buffer
|
||||
|
|
|
@ -120,7 +120,7 @@ PG_RESET_TEMPLATE(navConfig_t, navConfig,
|
|||
|
||||
//Fixed wing landing
|
||||
.land_dive_angle = 2, // 2 degrees dive by default
|
||||
|
||||
|
||||
// Fixed wing launch
|
||||
.launch_velocity_thresh = 300, // 3 m/s
|
||||
.launch_accel_thresh = 1.9f * 981, // cm/s/s (1.9*G)
|
||||
|
@ -2100,7 +2100,7 @@ bool loadNonVolatileWaypointList(void)
|
|||
resetWaypointList();
|
||||
|
||||
for (int i = 0; i < NAV_MAX_WAYPOINTS; i++) {
|
||||
// Load waypoint
|
||||
// Load waypoint
|
||||
setWaypoint(i + 1, nonVolatileWaypointList(i));
|
||||
|
||||
// Check if this is the last waypoint
|
||||
|
|
|
@ -461,7 +461,7 @@ void applyFixedWingPitchRollThrottleController(navigationFSMStateFlags_t navStat
|
|||
|
||||
/*
|
||||
* Stabilize ROLL axis on 0 degress banking regardless of loiter radius and position
|
||||
*/
|
||||
*/
|
||||
rcCommand[ROLL] = 0;
|
||||
|
||||
/*
|
||||
|
|
|
@ -266,11 +266,11 @@ bool crsfRxInit(const rxConfig_t *rxConfig, rxRuntimeConfig_t *rxRuntimeConfig)
|
|||
return false;
|
||||
}
|
||||
|
||||
serialPort = openSerialPort(portConfig->identifier,
|
||||
FUNCTION_RX_SERIAL,
|
||||
crsfDataReceive,
|
||||
CRSF_BAUDRATE,
|
||||
CRSF_PORT_MODE,
|
||||
serialPort = openSerialPort(portConfig->identifier,
|
||||
FUNCTION_RX_SERIAL,
|
||||
crsfDataReceive,
|
||||
CRSF_BAUDRATE,
|
||||
CRSF_PORT_MODE,
|
||||
CRSF_PORT_OPTIONS | (rxConfig->halfDuplex ? SERIAL_BIDIR : 0)
|
||||
);
|
||||
|
||||
|
|
|
@ -168,17 +168,17 @@ static void frequencyConfigurator(uint32_t frequency)
|
|||
{
|
||||
uint8_t band;
|
||||
|
||||
if(frequency<48000) {
|
||||
if (frequency<48000) {
|
||||
frequency -= 24000;
|
||||
band = frequency/1000;
|
||||
if(band>23) band = 23;
|
||||
if (band>23) band = 23;
|
||||
frequency -= (1000*(uint32_t)band);
|
||||
frequency *= 64;
|
||||
band |= 0x40;
|
||||
} else {
|
||||
frequency -= 48000;
|
||||
band = frequency/2000;
|
||||
if(band>22) band = 22;
|
||||
if (band>22) band = 22;
|
||||
frequency -= (2000*(uint32_t)band);
|
||||
frequency *= 32;
|
||||
band |= 0x60;
|
||||
|
@ -199,7 +199,7 @@ static void rfm22bInitParameter(void)
|
|||
static uint8_t cf3[8] = {0x0f,0x42,0x07,0x20,0x2d,0xd4,0x00,0x00};
|
||||
rfmSpiRead(0x03);
|
||||
rfmSpiRead(0x04);
|
||||
for(i = 0; i < 8; i++)
|
||||
for (i = 0; i < 8; i++)
|
||||
rfmSpiWrite(0x06+i, cf1[i]);
|
||||
if (first_init) {
|
||||
first_init = 0;
|
||||
|
@ -210,20 +210,20 @@ static void rfm22bInitParameter(void)
|
|||
rfmSpiWrite(0x6f, 0xD5);
|
||||
rfmSpiWrite(0x1c, 0x02);
|
||||
rfmSpiWrite(0x70, 0x00);
|
||||
for(i=0; i<6; i++) rfmSpiWrite(0x20+i, cf2[i]);
|
||||
for (i=0; i<6; i++) rfmSpiWrite(0x20+i, cf2[i]);
|
||||
rfmSpiWrite(0x2a, 0x1e);
|
||||
rfmSpiWrite(0x72, 0x1F);
|
||||
rfmSpiWrite(0x30, 0x8c);
|
||||
rfmSpiWrite(0x3e, 22);
|
||||
for(i=0; i<8; i++) rfmSpiWrite(0x32+i, cf3[i]);
|
||||
for(i=0; i<4; i++) rfmSpiWrite(0x43+i, 0xff);
|
||||
for (i=0; i<8; i++) rfmSpiWrite(0x32+i, cf3[i]);
|
||||
for (i=0; i<4; i++) rfmSpiWrite(0x43+i, 0xff);
|
||||
rfmSpiWrite(0x6d, eleresConfig()->eleresTelemetryPower | 0x18);
|
||||
rfmSpiWrite(0x79, 0x00);
|
||||
rfmSpiWrite(0x7a, 0x04);
|
||||
rfmSpiWrite(0x71, 0x23);
|
||||
rfmSpiWrite(0x73, 0x00);
|
||||
rfmSpiWrite(0x74, 0x00);
|
||||
for(i=0; i<4; i++) {
|
||||
for (i=0; i<4; i++) {
|
||||
rfmSpiWrite(0x3a+i, eleresSignaturePtr[i]);
|
||||
rfmSpiWrite(0x3f+i, eleresSignaturePtr[i]);
|
||||
}
|
||||
|
@ -236,15 +236,15 @@ static void rfm22bInitParameter(void)
|
|||
static void channelHopping(uint8_t hops)
|
||||
{
|
||||
hoppingChannel += hops;
|
||||
while(hoppingChannel >= 16) hoppingChannel -= 16;
|
||||
while (hoppingChannel >= 16) hoppingChannel -= 16;
|
||||
|
||||
if (eleresConfig()->eleresTelemetryEn && eleresConfig()->eleresLocEn) {
|
||||
if(bkgLocEnable && (hoppingChannel==bkgLocChlist || hoppingChannel==(bkgLocChlist+1)%16)) {
|
||||
if (bkgLocEnable && (hoppingChannel==bkgLocChlist || hoppingChannel==(bkgLocChlist+1)%16)) {
|
||||
rfmSpiWrite(0x79,0);
|
||||
bkgLocEnable = 2;
|
||||
return;
|
||||
}
|
||||
if(bkgLocEnable == 2) bkgLocEnable = 1;
|
||||
if (bkgLocEnable == 2) bkgLocEnable = 1;
|
||||
}
|
||||
|
||||
rfmSpiWrite(0x79, holList[hoppingChannel]);
|
||||
|
@ -275,20 +275,20 @@ static void telemetryRX(void)
|
|||
switch (telem_state++) {
|
||||
case 0:
|
||||
|
||||
if(presfil>200000) pres = presfil/4 - 50000;
|
||||
if (presfil>200000) pres = presfil/4 - 50000;
|
||||
else pres = 1;
|
||||
|
||||
themp = (uint8_t)(thempfil/80 + 86);
|
||||
|
||||
if (FLIGHT_MODE(FAILSAFE_MODE)) wii_flymode = 7;
|
||||
else if(FLIGHT_MODE(PASSTHRU_MODE)) wii_flymode = 8;
|
||||
else if(FLIGHT_MODE(NAV_RTH_MODE)) wii_flymode = 6;
|
||||
else if(FLIGHT_MODE(NAV_POSHOLD_MODE)) wii_flymode = 5;
|
||||
else if(FLIGHT_MODE(HEADFREE_MODE)) wii_flymode = 4;
|
||||
else if(FLIGHT_MODE(NAV_ALTHOLD_MODE)) wii_flymode = 3;
|
||||
else if(FLIGHT_MODE(ANGLE_MODE) || FLIGHT_MODE(HORIZON_MODE)) wii_flymode = 2;
|
||||
else if (FLIGHT_MODE(PASSTHRU_MODE)) wii_flymode = 8;
|
||||
else if (FLIGHT_MODE(NAV_RTH_MODE)) wii_flymode = 6;
|
||||
else if (FLIGHT_MODE(NAV_POSHOLD_MODE)) wii_flymode = 5;
|
||||
else if (FLIGHT_MODE(HEADFREE_MODE)) wii_flymode = 4;
|
||||
else if (FLIGHT_MODE(NAV_ALTHOLD_MODE)) wii_flymode = 3;
|
||||
else if (FLIGHT_MODE(ANGLE_MODE) || FLIGHT_MODE(HORIZON_MODE)) wii_flymode = 2;
|
||||
else wii_flymode = 1;
|
||||
if(ARMING_FLAG(ARMED)) wii_flymode |= 0x10;
|
||||
if (ARMING_FLAG(ARMED)) wii_flymode |= 0x10;
|
||||
rfTxBuffer[0] = 0x54;
|
||||
rfTxBuffer[1] = localRssi;
|
||||
rfTxBuffer[2] = quality;
|
||||
|
@ -307,9 +307,9 @@ static void telemetryRX(void)
|
|||
|
||||
rfTxBuffer[0] = 0x50;
|
||||
cnv.val = gpsSol.llh.lat/10;
|
||||
for(i=0; i<4; i++) rfTxBuffer[i+1] = cnv.b[i];
|
||||
for (i=0; i<4; i++) rfTxBuffer[i+1] = cnv.b[i];
|
||||
cnv.val = gpsSol.llh.lon/10;
|
||||
for(i=0; i<4; i++) rfTxBuffer[i+5] = cnv.b[i];
|
||||
for (i=0; i<4; i++) rfTxBuffer[i+5] = cnv.b[i];
|
||||
|
||||
rfTxBuffer[4] &= 0x0F;
|
||||
rfTxBuffer[4] |= (hdop << 4);
|
||||
|
@ -331,7 +331,7 @@ static void telemetryRX(void)
|
|||
|
||||
rfTxBuffer[0] = 0x47;
|
||||
rfTxBuffer[1] = (STATE(GPS_FIX)<<4) | (gpsSol.numSat & 0x0F);
|
||||
if(gpsSol.numSat > 15) rfTxBuffer[1] |= 0x80;
|
||||
if (gpsSol.numSat > 15) rfTxBuffer[1] |= 0x80;
|
||||
rfTxBuffer[2] = ((course>>8) & 0x0F) | ((gpsspeed>>4) & 0xF0);
|
||||
rfTxBuffer[3] = course & 0xFF;
|
||||
rfTxBuffer[4] = gpsspeed & 0xFF;
|
||||
|
@ -382,15 +382,15 @@ static void parseStatusRegister(const uint8_t *payload)
|
|||
static uint16_t rssifil;
|
||||
const timeMs_t irq_time = millis();
|
||||
|
||||
if((rfMode & RECEIVE) && (statusRegisters[0] & RF22B_RX_PACKET_RECEIVED_INTERRUPT))
|
||||
if ((rfMode & RECEIVE) && (statusRegisters[0] & RF22B_RX_PACKET_RECEIVED_INTERRUPT))
|
||||
rfMode |= RECEIVED;
|
||||
if((rfMode & TRANSMIT) && (statusRegisters[0] & RF22B_PACKET_SENT_INTERRUPT))
|
||||
if ((rfMode & TRANSMIT) && (statusRegisters[0] & RF22B_PACKET_SENT_INTERRUPT))
|
||||
rfMode |= TRANSMITTED;
|
||||
if((rfMode & RECEIVE) && (statusRegisters[1] & RF22B_VALID_SYNCWORD_INTERRUPT))
|
||||
if ((rfMode & RECEIVE) && (statusRegisters[1] & RF22B_VALID_SYNCWORD_INTERRUPT))
|
||||
rfMode |= PREAMBLE;
|
||||
|
||||
if(rfMode & RECEIVED) {
|
||||
if(bkgLocEnable < 2) {
|
||||
if (rfMode & RECEIVED) {
|
||||
if (bkgLocEnable < 2) {
|
||||
lastPackTime = irq_time;
|
||||
nextPackTime = irq_time + channelHoppingTime;
|
||||
}
|
||||
|
@ -407,9 +407,9 @@ static void parseStatusRegister(const uint8_t *payload)
|
|||
channelHoppingTime = (rfRxBuffer[20] & 0x0F)+18;
|
||||
dataReady |= DATA_FLAG;
|
||||
} else if (eleresConfig()->eleresLocEn && eleresConfig()->eleresTelemetryEn && bkgLocEnable==2) {
|
||||
if((rfRxBuffer[0] == 'H' && rfRxBuffer[2] == 'L') ||
|
||||
if ((rfRxBuffer[0] == 'H' && rfRxBuffer[2] == 'L') ||
|
||||
rfRxBuffer[0]=='T' || rfRxBuffer[0]=='P' || rfRxBuffer[0]=='G') {
|
||||
if(bkgLocCnt==0) bkgLocCnt = 200;
|
||||
if (bkgLocCnt==0) bkgLocCnt = 200;
|
||||
toReadyMode();
|
||||
bkgLocEnable = 0;
|
||||
channelHopping(0);
|
||||
|
@ -424,7 +424,7 @@ static void parseStatusRegister(const uint8_t *payload)
|
|||
}
|
||||
}
|
||||
|
||||
if((dataReady & LOCALIZER_FLAG)==0) {
|
||||
if ((dataReady & LOCALIZER_FLAG)==0) {
|
||||
if (eleresConfig()->eleresTelemetryEn)
|
||||
toTxMode(9);
|
||||
else
|
||||
|
@ -432,27 +432,27 @@ static void parseStatusRegister(const uint8_t *payload)
|
|||
}
|
||||
}
|
||||
|
||||
if(rfMode & TRANSMITTED) {
|
||||
if (rfMode & TRANSMITTED) {
|
||||
toReadyMode();
|
||||
if(dataReady & LOCALIZER_FLAG) {
|
||||
if (dataReady & LOCALIZER_FLAG) {
|
||||
rfmSpiWrite(0x79, holList[0]);
|
||||
} else if(irq_time-lastPackTime <= 1500 && bkgLocEnable<2)
|
||||
} else if (irq_time-lastPackTime <= 1500 && bkgLocEnable<2)
|
||||
channelHopping(1);
|
||||
toRxMode();
|
||||
}
|
||||
|
||||
if(rfMode & PREAMBLE) {
|
||||
if (rfMode & PREAMBLE) {
|
||||
uint8_t rssitmp = rfmSpiRead(0x26);
|
||||
if (eleresConfig()->eleresLocEn && eleresConfig()->eleresTelemetryEn && bkgLocEnable==2) {
|
||||
if(rssitmp>124) rssitmp = 124;
|
||||
if(rssitmp<18) rssitmp = 18;
|
||||
if (rssitmp>124) rssitmp = 124;
|
||||
if (rssitmp<18) rssitmp = 18;
|
||||
bkgLocBuf[0][1] = rssitmp + 128;
|
||||
} else {
|
||||
rssifil -= rssifil/8;
|
||||
rssifil += rssitmp;
|
||||
localRssi = (rssifil/8 * quality / 100)+10;
|
||||
if(localRssi>124) localRssi = 124;
|
||||
if(localRssi<18) localRssi = 18;
|
||||
if (localRssi>124) localRssi = 124;
|
||||
if (localRssi<18) localRssi = 18;
|
||||
}
|
||||
rfMode &= ~PREAMBLE;
|
||||
}
|
||||
|
@ -480,8 +480,8 @@ void eleresSetRcDataFromPayload(uint16_t *rcData, const uint8_t *payload)
|
|||
else
|
||||
led_time = cr_time;
|
||||
|
||||
if((dataReady & LOCALIZER_FLAG) == 0) {
|
||||
if(cr_time > nextPackTime+2) {
|
||||
if ((dataReady & LOCALIZER_FLAG) == 0) {
|
||||
if (cr_time > nextPackTime+2) {
|
||||
if ((cr_time-lastPackTime > 1500) || firstRun) {
|
||||
localRssi = 18;
|
||||
rfm22bInitParameter();
|
||||
|
@ -495,7 +495,7 @@ void eleresSetRcDataFromPayload(uint16_t *rcData, const uint8_t *payload)
|
|||
// res = RX_FRAME_FAILSAFE;
|
||||
} else {
|
||||
|
||||
if(cr_time-lastPackTime > 3*channelHoppingTime) {
|
||||
if (cr_time-lastPackTime > 3*channelHoppingTime) {
|
||||
red_led_local=1;
|
||||
if (localRssi > 0x18)
|
||||
localRssi--;
|
||||
|
@ -505,37 +505,37 @@ void eleresSetRcDataFromPayload(uint16_t *rcData, const uint8_t *payload)
|
|||
nextPackTime += channelHoppingTime;
|
||||
}
|
||||
}
|
||||
if(cr_time > qtest_time) {
|
||||
if (cr_time > qtest_time) {
|
||||
qtest_time = cr_time + 500;
|
||||
quality = goodFrames * 100 / (500/channelHoppingTime);
|
||||
if(quality > 100) quality = 100;
|
||||
if (quality > 100) quality = 100;
|
||||
goodFrames = 0;
|
||||
}
|
||||
}
|
||||
|
||||
if((dataReady & 0x03) == DATA_FLAG && rcData != NULL) {
|
||||
if((dataReady & RELAY_FLAG)==0) {
|
||||
if ((dataReady & 0x03) == DATA_FLAG && rcData != NULL) {
|
||||
if ((dataReady & RELAY_FLAG)==0) {
|
||||
channel_count = rfRxBuffer[20] >> 4;
|
||||
if(channel_count < 4) channel_count = 4;
|
||||
if(channel_count > RC_CHANS) channel_count = 12;
|
||||
for(i = 0; i<channel_count; i++) {
|
||||
if (channel_count < 4) channel_count = 4;
|
||||
if (channel_count > RC_CHANS) channel_count = 12;
|
||||
for (i = 0; i<channel_count; i++) {
|
||||
temp_int = rfRxBuffer[i+1];
|
||||
if(i%2 == 0)
|
||||
if (i%2 == 0)
|
||||
temp_int |= ((unsigned int)rfRxBuffer[i/2 + 13] << 4) & 0x0F00;
|
||||
else
|
||||
temp_int |= ((unsigned int)rfRxBuffer[i/2 + 13] << 8) & 0x0F00;
|
||||
if ((temp_int>799) && (temp_int<2201)) rcData4Values[i] = temp_int;
|
||||
}
|
||||
n = rfRxBuffer[19];
|
||||
for(i=channel_count; i < channel_count+5; i++) {
|
||||
if(i > 11) break;
|
||||
if(n & 0x01) temp_int = BIN_ON_VALUE;
|
||||
for (i=channel_count; i < channel_count+5; i++) {
|
||||
if (i > 11) break;
|
||||
if (n & 0x01) temp_int = BIN_ON_VALUE;
|
||||
else temp_int = BIN_OFF_VALUE;
|
||||
rcData4Values[i] = temp_int;
|
||||
n >>= 1;
|
||||
}
|
||||
for(; i<RC_CHANS; i++) rcData4Values[i]=1500;
|
||||
for(i=0; i<RC_CHANS; i++) {
|
||||
for (; i<RC_CHANS; i++) rcData4Values[i]=1500;
|
||||
for (i=0; i<RC_CHANS; i++) {
|
||||
temp_int = rcData4Values[i];
|
||||
if (temp_int < rcData[i] -3) rcData[i] = temp_int+2;
|
||||
if (temp_int > rcData[i] +3) rcData[i] = temp_int-2;
|
||||
|
@ -545,10 +545,10 @@ void eleresSetRcDataFromPayload(uint16_t *rcData, const uint8_t *payload)
|
|||
|
||||
if (eleresConfig()->eleresTelemetryEn) {
|
||||
if (eleresConfig()->eleresLocEn) {
|
||||
if(bkgLocEnable == 0) bkgLocCnt=0;
|
||||
if(bkgLocCnt) bkgLocCnt--;
|
||||
if (bkgLocEnable == 0) bkgLocCnt=0;
|
||||
if (bkgLocCnt) bkgLocCnt--;
|
||||
|
||||
if(bkgLocCnt<128)
|
||||
if (bkgLocCnt<128)
|
||||
telemetryRX();
|
||||
else
|
||||
memcpy(rfTxBuffer, bkgLocBuf[bkgLocCnt%3], 9);
|
||||
|
@ -565,24 +565,24 @@ void eleresSetRcDataFromPayload(uint16_t *rcData, const uint8_t *payload)
|
|||
}
|
||||
|
||||
if (eleresConfig()->eleresLocEn) {
|
||||
if((dataReady & 0x03)==(DATA_FLAG | LOCALIZER_FLAG) && rfRxBuffer[19]<128) {
|
||||
if(rx_frames == 0) guard_time = lastPackTime;
|
||||
if(rx_frames < 250) {
|
||||
if ((dataReady & 0x03)==(DATA_FLAG | LOCALIZER_FLAG) && rfRxBuffer[19]<128) {
|
||||
if (rx_frames == 0) guard_time = lastPackTime;
|
||||
if (rx_frames < 250) {
|
||||
rx_frames++;
|
||||
}
|
||||
if(rx_frames > 20 && cr_time-guard_time > (locForce?5000:20000)) {
|
||||
if (rx_frames > 20 && cr_time-guard_time > (locForce?5000:20000)) {
|
||||
dataReady = 0;
|
||||
localizerTime = cr_time + (1000L*eleresConfig()->eleresLocDelay);
|
||||
rfm22bInitParameter();
|
||||
channelHopping(1);
|
||||
rx_frames = 0;
|
||||
|
||||
if(locForce && eleresConfig()->eleresTelemetryEn) {
|
||||
if (locForce && eleresConfig()->eleresTelemetryEn) {
|
||||
bkgLocEnable = 1;
|
||||
temp_int = 0;
|
||||
for(i=0; i<16; i++) {
|
||||
for (i=0; i<16; i++) {
|
||||
uint16_t mult = holList[i] * holList[(i+1)%16];
|
||||
if(mult > temp_int) {
|
||||
if (mult > temp_int) {
|
||||
temp_int = mult;
|
||||
bkgLocChlist = i;
|
||||
}
|
||||
|
@ -591,11 +591,11 @@ void eleresSetRcDataFromPayload(uint16_t *rcData, const uint8_t *payload)
|
|||
}
|
||||
}
|
||||
|
||||
if(cr_time-lastPackTime > 8000) {
|
||||
if (cr_time-lastPackTime > 8000) {
|
||||
rx_frames = 0;
|
||||
}
|
||||
if(!ARMING_FLAG(ARMED) && cr_time > localizerTime) {
|
||||
if((dataReady & LOCALIZER_FLAG)==0) {
|
||||
if (!ARMING_FLAG(ARMED) && cr_time > localizerTime) {
|
||||
if ((dataReady & LOCALIZER_FLAG)==0) {
|
||||
rfm22bInitParameter();
|
||||
rfmSpiWrite(0x6d, eleresConfig()->eleresLocPower);
|
||||
}
|
||||
|
@ -607,7 +607,7 @@ void eleresSetRcDataFromPayload(uint16_t *rcData, const uint8_t *payload)
|
|||
led_time = cr_time;
|
||||
|
||||
bkgLocEnable = 0;
|
||||
if(!(++loc_cnt & 1) && eleresConfig()->eleresTelemetryEn) {
|
||||
if (!(++loc_cnt & 1) && eleresConfig()->eleresTelemetryEn) {
|
||||
telemetryRX();
|
||||
toTxMode(9);
|
||||
} else {
|
||||
|
@ -620,18 +620,18 @@ void eleresSetRcDataFromPayload(uint16_t *rcData, const uint8_t *payload)
|
|||
}
|
||||
}
|
||||
|
||||
if((ARMING_FLAG(ARMED) || firstRun) && (dataReady & LOCALIZER_FLAG)==0)
|
||||
if ((ARMING_FLAG(ARMED) || firstRun) && (dataReady & LOCALIZER_FLAG)==0)
|
||||
localizerTime = cr_time + (1000L*eleresConfig()->eleresLocDelay);
|
||||
|
||||
if (eleresConfig()->eleresTelemetryEn)
|
||||
if(dataReady & RELAY_FLAG) {
|
||||
if(rfRxBuffer[0]=='H') bkgLocBuf[0][0]='T';
|
||||
if(rfRxBuffer[0]=='T') {
|
||||
if (dataReady & RELAY_FLAG) {
|
||||
if (rfRxBuffer[0]=='H') bkgLocBuf[0][0]='T';
|
||||
if (rfRxBuffer[0]=='T') {
|
||||
bkgLocBuf[0][0]='T';
|
||||
memcpy(bkgLocBuf[0]+2, rfRxBuffer+2, 7);
|
||||
}
|
||||
if(rfRxBuffer[0]=='P') memcpy(bkgLocBuf[1], rfRxBuffer, 9);
|
||||
if(rfRxBuffer[0]=='G') memcpy(bkgLocBuf[2], rfRxBuffer, 9);
|
||||
if (rfRxBuffer[0]=='P') memcpy(bkgLocBuf[1], rfRxBuffer, 9);
|
||||
if (rfRxBuffer[0]=='G') memcpy(bkgLocBuf[2], rfRxBuffer, 9);
|
||||
dataReady = 0;
|
||||
}
|
||||
}
|
||||
|
@ -665,7 +665,7 @@ static void bindChannels(const uint8_t* RF_HEAD, uint8_t* hop_lst)
|
|||
for (int j=0; j<4; j++) {
|
||||
for (int i=0; i<4; i++) {
|
||||
n = RF_HEAD[i]%128;
|
||||
if(j==3) n /= 5;
|
||||
if (j==3) n /= 5;
|
||||
else n /= j+1;
|
||||
hop_lst[4*j+i] = checkChannel(n,hop_lst);
|
||||
}
|
||||
|
@ -710,17 +710,17 @@ uint8_t eleresBind(void)
|
|||
bindChannels(eleresSignaturePtr,holList);
|
||||
channelHoppingTime = 33;
|
||||
RED_LED_OFF;
|
||||
while(timeout--) {
|
||||
while (timeout--) {
|
||||
eleresDataReceived(NULL);
|
||||
eleresSetRcDataFromPayload(NULL,NULL);
|
||||
if (rfRxBuffer[0]==0x42) {
|
||||
for(i=0; i<4; i++) {
|
||||
for (i=0; i<4; i++) {
|
||||
if (rfRxBuffer[i+1]==eleres_signature_old[i]) eleres_signature_OK_count++;
|
||||
else eleres_signature_OK_count = 0;
|
||||
}
|
||||
for(i=0; i<4; i++) eleres_signature_old[i] = rfRxBuffer[i+1];
|
||||
for (i=0; i<4; i++) eleres_signature_old[i] = rfRxBuffer[i+1];
|
||||
if (eleres_signature_OK_count>200) {
|
||||
for(i=0; i<4; i++)
|
||||
for (i=0; i<4; i++)
|
||||
eleresSignaturePtr[i] = eleres_signature_old[i];
|
||||
RED_LED_OFF;
|
||||
saveConfigAndNotify();
|
||||
|
|
|
@ -225,18 +225,18 @@ bool ibusInit(const rxConfig_t *rxConfig, rxRuntimeConfig_t *rxRuntimeConfig)
|
|||
#endif
|
||||
|
||||
rxBytesToIgnore = 0;
|
||||
serialPort_t *ibusPort = openSerialPort(portConfig->identifier,
|
||||
FUNCTION_RX_SERIAL,
|
||||
ibusDataReceive,
|
||||
IBUS_BAUDRATE,
|
||||
portShared ? MODE_RXTX : MODE_RX,
|
||||
serialPort_t *ibusPort = openSerialPort(portConfig->identifier,
|
||||
FUNCTION_RX_SERIAL,
|
||||
ibusDataReceive,
|
||||
IBUS_BAUDRATE,
|
||||
portShared ? MODE_RXTX : MODE_RX,
|
||||
SERIAL_NOT_INVERTED | (rxConfig->halfDuplex || portShared ? SERIAL_BIDIR : 0)
|
||||
);
|
||||
|
||||
#if defined(TELEMETRY) && defined(TELEMETRY_IBUS)
|
||||
if (portShared) {
|
||||
initSharedIbusTelemetry(ibusPort);
|
||||
}
|
||||
}
|
||||
#endif
|
||||
|
||||
return ibusPort != NULL;
|
||||
|
|
|
@ -316,7 +316,7 @@ static void jetiExBusDataReceive(uint16_t c)
|
|||
|
||||
// Check if we shall start a frame?
|
||||
if (jetiExBusFramePosition == 0) {
|
||||
switch(c){
|
||||
switch (c){
|
||||
case EXBUS_START_CHANNEL_FRAME:
|
||||
jetiExBusFrameState = EXBUS_STATE_IN_PROGRESS;
|
||||
jetiExBusFrame = jetiExBusChannelFrame;
|
||||
|
@ -339,12 +339,12 @@ static void jetiExBusDataReceive(uint16_t c)
|
|||
// Check the header for the message length
|
||||
if (jetiExBusFramePosition == EXBUS_HEADER_LEN) {
|
||||
|
||||
if((jetiExBusFrameState == EXBUS_STATE_IN_PROGRESS) && (jetiExBusFrame[EXBUS_HEADER_MSG_LEN] <= EXBUS_MAX_CHANNEL_FRAME_SIZE)) {
|
||||
if ((jetiExBusFrameState == EXBUS_STATE_IN_PROGRESS) && (jetiExBusFrame[EXBUS_HEADER_MSG_LEN] <= EXBUS_MAX_CHANNEL_FRAME_SIZE)) {
|
||||
jetiExBusFrameLength = jetiExBusFrame[EXBUS_HEADER_MSG_LEN];
|
||||
return;
|
||||
}
|
||||
|
||||
if((jetiExBusRequestState == EXBUS_STATE_IN_PROGRESS) && (jetiExBusFrame[EXBUS_HEADER_MSG_LEN] <= EXBUS_MAX_REQUEST_FRAME_SIZE)) {
|
||||
if ((jetiExBusRequestState == EXBUS_STATE_IN_PROGRESS) && (jetiExBusFrame[EXBUS_HEADER_MSG_LEN] <= EXBUS_MAX_REQUEST_FRAME_SIZE)) {
|
||||
jetiExBusFrameLength = jetiExBusFrame[EXBUS_HEADER_MSG_LEN];
|
||||
return;
|
||||
}
|
||||
|
@ -375,7 +375,7 @@ uint8_t jetiExBusFrameStatus()
|
|||
if (jetiExBusFrameState != EXBUS_STATE_RECEIVED)
|
||||
return RX_FRAME_PENDING;
|
||||
|
||||
if(calcCRC16(jetiExBusChannelFrame, jetiExBusChannelFrame[EXBUS_HEADER_MSG_LEN]) == 0) {
|
||||
if (calcCRC16(jetiExBusChannelFrame, jetiExBusChannelFrame[EXBUS_HEADER_MSG_LEN]) == 0) {
|
||||
jetiExBusDecodeChannelFrame(jetiExBusChannelFrame);
|
||||
jetiExBusFrameState = EXBUS_STATE_ZERO;
|
||||
return RX_FRAME_COMPLETE;
|
||||
|
@ -448,18 +448,18 @@ uint8_t createExTelemetrieValueMessage(uint8_t *exMessage, uint8_t itemStart)
|
|||
if ((item & 0x0F) == 0)
|
||||
item++;
|
||||
|
||||
if(item >= JETI_EX_SENSOR_COUNT)
|
||||
if (item >= JETI_EX_SENSOR_COUNT)
|
||||
item = 1;
|
||||
|
||||
exMessage[EXTEL_HEADER_LSN_LB] = item & 0xF0; // Device ID
|
||||
uint8_t *p = &exMessage[EXTEL_HEADER_ID];
|
||||
|
||||
while(item <= (itemStart | 0x0F)) {
|
||||
while (item <= (itemStart | 0x0F)) {
|
||||
*p++ = ((item & 0x0F) << 4) | jetiExSensors[item].exDataType; // Sensor ID (%16) | EX Data Type
|
||||
|
||||
sensorValue = jetiExSensors[item].value;
|
||||
iCount = exDataTypeLen[jetiExSensors[item].exDataType];
|
||||
while(iCount > 1) {
|
||||
while (iCount > 1) {
|
||||
*p++ = sensorValue;
|
||||
sensorValue = sensorValue >> 8;
|
||||
iCount--;
|
||||
|
@ -467,9 +467,9 @@ uint8_t createExTelemetrieValueMessage(uint8_t *exMessage, uint8_t itemStart)
|
|||
*p++ = (sensorValue & 0x9F) | jetiExSensors[item].decimals;
|
||||
|
||||
item++;
|
||||
if(item >= JETI_EX_SENSOR_COUNT)
|
||||
if (item >= JETI_EX_SENSOR_COUNT)
|
||||
break;
|
||||
if(EXTEL_MAX_PAYLOAD <= ((p-&exMessage[EXTEL_HEADER_ID]) + exDataTypeLen[jetiExSensors[item].exDataType]) + 1)
|
||||
if (EXTEL_MAX_PAYLOAD <= ((p-&exMessage[EXTEL_HEADER_ID]) + exDataTypeLen[jetiExSensors[item].exDataType]) + 1)
|
||||
break;
|
||||
}
|
||||
|
||||
|
@ -512,13 +512,13 @@ void handleJetiExBusTelemetry(void)
|
|||
// to prevent timing issues from request to answer - max. 4ms
|
||||
timeDiff = micros() - jetiTimeStampRequest;
|
||||
|
||||
if(timeDiff > 3000) { // include reserved time
|
||||
if (timeDiff > 3000) { // include reserved time
|
||||
jetiExBusRequestState = EXBUS_STATE_ZERO;
|
||||
framesLost++;
|
||||
return;
|
||||
}
|
||||
|
||||
if((jetiExBusRequestFrame[EXBUS_HEADER_DATA_ID] == EXBUS_EX_REQUEST) && (calcCRC16(jetiExBusRequestFrame, jetiExBusRequestFrame[EXBUS_HEADER_MSG_LEN]) == 0)) {
|
||||
if ((jetiExBusRequestFrame[EXBUS_HEADER_DATA_ID] == EXBUS_EX_REQUEST) && (calcCRC16(jetiExBusRequestFrame, jetiExBusRequestFrame[EXBUS_HEADER_MSG_LEN]) == 0)) {
|
||||
jetiExSensors[EX_VOLTAGE].value = vbat;
|
||||
jetiExSensors[EX_CURRENT].value = amperage;
|
||||
jetiExSensors[EX_ALTITUDE].value = baro.BaroAlt;
|
||||
|
@ -597,12 +597,12 @@ bool jetiExBusInit(const rxConfig_t *rxConfig, rxRuntimeConfig_t *rxRuntimeConfi
|
|||
return false;
|
||||
}
|
||||
|
||||
jetiExBusPort = openSerialPort(portConfig->identifier,
|
||||
FUNCTION_RX_SERIAL,
|
||||
jetiExBusDataReceive,
|
||||
JETIEXBUS_BAUDRATE,
|
||||
MODE_RXTX,
|
||||
JETIEXBUS_OPTIONS | (rxConfig->halfDuplex ? SERIAL_BIDIR : 0)
|
||||
jetiExBusPort = openSerialPort(portConfig->identifier,
|
||||
FUNCTION_RX_SERIAL,
|
||||
jetiExBusDataReceive,
|
||||
JETIEXBUS_BAUDRATE,
|
||||
MODE_RXTX,
|
||||
JETIEXBUS_OPTIONS | (rxConfig->halfDuplex ? SERIAL_BIDIR : 0)
|
||||
);
|
||||
|
||||
serialSetMode(jetiExBusPort, MODE_RX);
|
||||
|
|
|
@ -152,7 +152,7 @@ static void decode_bind_packet(uint8_t *packet)
|
|||
// Returns whether the data was successfully decoded
|
||||
static rx_spi_received_e decode_packet(uint8_t *packet)
|
||||
{
|
||||
if(bind_phase != PHASE_BOUND) {
|
||||
if (bind_phase != PHASE_BOUND) {
|
||||
decode_bind_packet(packet);
|
||||
return RX_SPI_RECEIVED_BIND;
|
||||
}
|
||||
|
|
|
@ -246,11 +246,11 @@ bool sbusInit(const rxConfig_t *rxConfig, rxRuntimeConfig_t *rxRuntimeConfig)
|
|||
bool portShared = false;
|
||||
#endif
|
||||
|
||||
serialPort_t *sBusPort = openSerialPort(portConfig->identifier,
|
||||
FUNCTION_RX_SERIAL,
|
||||
sbusDataReceive,
|
||||
SBUS_BAUDRATE,
|
||||
portShared ? MODE_RXTX : MODE_RX,
|
||||
serialPort_t *sBusPort = openSerialPort(portConfig->identifier,
|
||||
FUNCTION_RX_SERIAL,
|
||||
sbusDataReceive,
|
||||
SBUS_BAUDRATE,
|
||||
portShared ? MODE_RXTX : MODE_RX,
|
||||
SBUS_PORT_OPTIONS | (rxConfig->sbus_inversion ? SERIAL_INVERTED : 0) | (rxConfig->halfDuplex ? SERIAL_BIDIR : 0)
|
||||
);
|
||||
|
||||
|
|
|
@ -126,11 +126,11 @@ uint8_t spektrumFrameStatus(void)
|
|||
// This is the first frame status received.
|
||||
spek_fade_last_sec_count = fade;
|
||||
spek_fade_last_sec = current_secs;
|
||||
} else if(spek_fade_last_sec != current_secs) {
|
||||
} else if (spek_fade_last_sec != current_secs) {
|
||||
// If the difference is > 1, then we missed several seconds worth of frames and
|
||||
// should just throw out the fade calc (as it's likely a full signal loss).
|
||||
if((current_secs - spek_fade_last_sec) == 1) {
|
||||
if(rssi_channel != 0) {
|
||||
if ((current_secs - spek_fade_last_sec) == 1) {
|
||||
if (rssi_channel != 0) {
|
||||
if (spekHiRes)
|
||||
spekChannelData[rssi_channel] = 2048 - ((fade - spek_fade_last_sec_count) * 2048 / (SPEKTRUM_MAX_FADE_PER_SEC / SPEKTRUM_FADE_REPORTS_PER_SEC));
|
||||
else
|
||||
|
@ -145,7 +145,7 @@ uint8_t spektrumFrameStatus(void)
|
|||
for (int b = 3; b < SPEK_FRAME_SIZE; b += 2) {
|
||||
const uint8_t spekChannel = 0x0F & (spekFrame[b - 1] >> spek_chan_shift);
|
||||
if (spekChannel < rxRuntimeConfigPtr->channelCount && spekChannel < SPEKTRUM_MAX_SUPPORTED_CHANNEL_COUNT) {
|
||||
if(rssi_channel == 0 || spekChannel != rssi_channel) {
|
||||
if (rssi_channel == 0 || spekChannel != rssi_channel) {
|
||||
spekChannelData[spekChannel] = ((uint32_t)(spekFrame[b - 1] & spek_chan_mask) << 8) + spekFrame[b];
|
||||
}
|
||||
}
|
||||
|
|
|
@ -179,11 +179,11 @@ bool sumdInit(const rxConfig_t *rxConfig, rxRuntimeConfig_t *rxRuntimeConfig)
|
|||
bool portShared = false;
|
||||
#endif
|
||||
|
||||
serialPort_t *sumdPort = openSerialPort(portConfig->identifier,
|
||||
FUNCTION_RX_SERIAL,
|
||||
sumdDataReceive,
|
||||
SUMD_BAUDRATE,
|
||||
portShared ? MODE_RXTX : MODE_RX,
|
||||
serialPort_t *sumdPort = openSerialPort(portConfig->identifier,
|
||||
FUNCTION_RX_SERIAL,
|
||||
sumdDataReceive,
|
||||
SUMD_BAUDRATE,
|
||||
portShared ? MODE_RXTX : MODE_RX,
|
||||
SERIAL_NOT_INVERTED | (rxConfig->halfDuplex ? SERIAL_BIDIR : 0)
|
||||
);
|
||||
|
||||
|
|
|
@ -322,11 +322,11 @@ bool xBusInit(const rxConfig_t *rxConfig, rxRuntimeConfig_t *rxRuntimeConfig)
|
|||
bool portShared = false;
|
||||
#endif
|
||||
|
||||
serialPort_t *xBusPort = openSerialPort(portConfig->identifier,
|
||||
FUNCTION_RX_SERIAL,
|
||||
xBusDataReceive,
|
||||
baudRate,
|
||||
portShared ? MODE_RXTX : MODE_RX,
|
||||
serialPort_t *xBusPort = openSerialPort(portConfig->identifier,
|
||||
FUNCTION_RX_SERIAL,
|
||||
xBusDataReceive,
|
||||
baudRate,
|
||||
portShared ? MODE_RXTX : MODE_RX,
|
||||
SERIAL_NOT_INVERTED | (rxConfig->halfDuplex ? SERIAL_BIDIR : 0)
|
||||
);
|
||||
|
||||
|
|
|
@ -130,7 +130,7 @@ void batteryUpdate(uint32_t vbatTimeDelta)
|
|||
batteryCriticalVoltage = 0;
|
||||
}
|
||||
|
||||
switch(batteryState)
|
||||
switch (batteryState)
|
||||
{
|
||||
case BATTERY_OK:
|
||||
if (vbat <= (batteryWarningVoltage - VBATT_HYSTERESIS)) {
|
||||
|
@ -192,7 +192,7 @@ void currentMeterUpdate(int32_t lastUpdateAt)
|
|||
int32_t throttleFactor = 0;
|
||||
int32_t throttleOffset = (int32_t)rcCommand[THROTTLE] - 1000;
|
||||
|
||||
switch(batteryConfig()->currentMeterType) {
|
||||
switch (batteryConfig()->currentMeterType) {
|
||||
case CURRENT_SENSOR_ADC:
|
||||
amperageRaw -= amperageRaw / 8;
|
||||
amperageRaw += (amperageLatestADC = adcGetChannel(ADC_CURRENT));
|
||||
|
|
|
@ -109,7 +109,7 @@ bool compassDetect(magDev_t *dev, magSensor_e magHardwareToUse)
|
|||
|
||||
dev->magAlign = ALIGN_DEFAULT;
|
||||
|
||||
switch(magHardwareToUse) {
|
||||
switch (magHardwareToUse) {
|
||||
case MAG_AUTODETECT:
|
||||
case MAG_HMC5883:
|
||||
#ifdef USE_MAG_HMC5883
|
||||
|
|
|
@ -153,7 +153,7 @@ STATIC_UNIT_TESTED gyroSensor_e gyroDetect(gyroDev_t *dev, gyroSensor_e gyroHard
|
|||
{
|
||||
dev->gyroAlign = ALIGN_DEFAULT;
|
||||
|
||||
switch(gyroHardware) {
|
||||
switch (gyroHardware) {
|
||||
case GYRO_AUTODETECT:
|
||||
// fallthrough
|
||||
|
||||
|
|
|
@ -101,7 +101,7 @@ static bool rangefinderDetect(rangefinderDev_t * dev, uint8_t rangefinderHardwar
|
|||
rescheduleTask(TASK_RANGEFINDER, TASK_PERIOD_MS(RANGEFINDER_HCSR04_TASK_PERIOD_MS));
|
||||
}
|
||||
}
|
||||
#endif
|
||||
#endif
|
||||
break;
|
||||
|
||||
case RANGEFINDER_SRF10:
|
||||
|
|
|
@ -23,7 +23,7 @@ const timerHardware_t timerHardware[USABLE_TIMER_CHANNEL_COUNT] = {
|
|||
{ TIM1, IO_TAG(PE11), TIM_Channel_2, 1, IOCFG_AF_PP, GPIO_AF_TIM1, TIM_USE_MC_MOTOR | TIM_USE_FW_SERVO}, // S6_OUT
|
||||
{ TIM1, IO_TAG(PE13), TIM_Channel_3, 1, IOCFG_AF_PP, GPIO_AF_TIM1, TIM_USE_MC_MOTOR | TIM_USE_FW_SERVO}, // S7_OUT
|
||||
{ TIM1, IO_TAG(PE14), TIM_Channel_4, 1, IOCFG_AF_PP, GPIO_AF_TIM1, TIM_USE_MC_MOTOR | TIM_USE_FW_SERVO}, // S8_OUT
|
||||
|
||||
|
||||
{ TIM9, IO_TAG(PE6), TIM_Channel_2, 0, IOCFG_AF_PP, GPIO_AF_TIM9, TIM_USE_ANY }, // HC-SR04 echo if needed
|
||||
};
|
||||
|
||||
|
|
|
@ -28,7 +28,7 @@ void initialisePreBootHardware(void)
|
|||
IOInit(DEFIO_IO(OSD_CH_SWITCH), OWNER_SYSTEM, RESOURCE_OUTPUT, 0);
|
||||
IOConfigGPIO(DEFIO_IO(OSD_CH_SWITCH), IOCFG_OUT_PP);
|
||||
IOLo(DEFIO_IO(OSD_CH_SWITCH));
|
||||
|
||||
|
||||
// Inverting the UART1 port by default
|
||||
IOInit(DEFIO_IO(PB13), OWNER_SYSTEM, RESOURCE_OUTPUT, 0);
|
||||
IOConfigGPIO(DEFIO_IO(PB13), IOCFG_OUT_PP);
|
||||
|
|
|
@ -197,7 +197,7 @@
|
|||
|
||||
#ifdef OMNIBUSF4PRO
|
||||
#define USED_TIMERS ( TIM_N(1) | TIM_N(2) | TIM_N(3) | TIM_N(5) | TIM_N(4) | TIM_N(8) | TIM_N(9) )
|
||||
#else
|
||||
#else
|
||||
#define USED_TIMERS ( TIM_N(1) | TIM_N(2) | TIM_N(3) | TIM_N(5) | TIM_N(12) | TIM_N(8) | TIM_N(9) )
|
||||
#endif
|
||||
|
||||
|
|
|
@ -31,7 +31,7 @@ const timerHardware_t timerHardware[USABLE_TIMER_CHANNEL_COUNT] = {
|
|||
{ TIM4, IO_TAG(PB9), TIM_Channel_4, 1, IOCFG_AF_PP, GPIO_AF_2, TIM_USE_MC_MOTOR | TIM_USE_FW_SERVO }, // PWM6 - PB9
|
||||
{ TIM15, IO_TAG(PA2), TIM_Channel_1, 1, IOCFG_AF_PP, GPIO_AF_9, TIM_USE_MC_MOTOR | TIM_USE_MC_SERVO | TIM_USE_FW_SERVO }, // PWM7 - PA2
|
||||
{ TIM15, IO_TAG(PA3), TIM_Channel_2, 1, IOCFG_AF_PP, GPIO_AF_9, TIM_USE_MC_MOTOR | TIM_USE_MC_SERVO | TIM_USE_FW_SERVO }, // PWM8 - PA3
|
||||
|
||||
|
||||
{ TIM1, IO_TAG(PA8), TIM_Channel_1, 1, IOCFG_AF_PP, GPIO_AF_6, TIM_USE_LED }, // GPIO_TIMER / LED_STRIP
|
||||
|
||||
{ TIM2, IO_TAG(PA0), TIM_Channel_1, 0, IOCFG_AF_PP, GPIO_AF_1, TIM_USE_PWM | TIM_USE_PPM }, // RC_CH1 - PA0 - *TIM2_CH1
|
||||
|
|
|
@ -30,13 +30,13 @@ const timerHardware_t timerHardware[USABLE_TIMER_CHANNEL_COUNT] = {
|
|||
{ TIM3, IO_TAG(PB0), TIM_Channel_3, 0, IOCFG_AF_PP, GPIO_AF_2, TIM_USE_MC_MOTOR | TIM_USE_FW_SERVO }, // PWM4 - PB0 - *TIM3_CH3, TIM1_CH2N, TIM8_CH2N
|
||||
{ TIM16, IO_TAG(PA6), TIM_Channel_1, 0, IOCFG_AF_PP, GPIO_AF_1, TIM_USE_MC_MOTOR | TIM_USE_FW_SERVO | TIM_USE_LED }, // PWM5 - PA6 - *TIM3_CH1, TIM8_BKIN, TIM1_BKIN, TIM16_CH1
|
||||
{ TIM2, IO_TAG(PA2), TIM_Channel_3, 0, IOCFG_AF_PP, GPIO_AF_1, TIM_USE_MC_MOTOR | TIM_USE_FW_SERVO }, // PWM6 - PA2 - *TIM2_CH3, !TIM15_CH1
|
||||
|
||||
|
||||
// PWM7 - PMW10
|
||||
{ TIM3, IO_TAG(PB1), TIM_Channel_4, 0, IOCFG_AF_PP, GPIO_AF_2, TIM_USE_MC_MOTOR | TIM_USE_FW_SERVO }, // PWM7 - PB1 - *TIM3_CH4, TIM1_CH3N, TIM8_CH3N
|
||||
{ TIM17, IO_TAG(PA7), TIM_Channel_1, 1, IOCFG_AF_PP, GPIO_AF_1, TIM_USE_MC_MOTOR | TIM_USE_FW_SERVO }, // PWM8 - PA7 - !TIM3_CH2, *TIM17_CH1, TIM1_CH1N, TIM8_CH1
|
||||
{ TIM3, IO_TAG(PA4), TIM_Channel_2, 0, IOCFG_AF_PP, GPIO_AF_2, TIM_USE_MC_MOTOR | TIM_USE_FW_SERVO }, // PWM9 - PA4 - *TIM3_CH2
|
||||
{ TIM2, IO_TAG(PA1), TIM_Channel_2, 0, IOCFG_AF_PP, GPIO_AF_1, TIM_USE_MC_MOTOR | TIM_USE_FW_SERVO }, // PWM10 - PA1 - *TIM2_CH2, TIM15_CH1N
|
||||
|
||||
|
||||
// PPM PORT - Also USART2 RX (AF5)
|
||||
{ TIM2, IO_TAG(PA3), TIM_Channel_4, 0, IOCFG_AF_PP_PD, GPIO_AF_1, TIM_USE_PPM } // PPM - PA3 - TIM2_CH4, TIM15_CH2 - PWM13
|
||||
};
|
||||
|
|
|
@ -33,7 +33,7 @@ const timerHardware_t timerHardware[USABLE_TIMER_CHANNEL_COUNT] = {
|
|||
{ TIM15, IO_TAG(PA3), TIM_Channel_2, 1, IOCFG_AF_PP, GPIO_AF_9, TIM_USE_MC_MOTOR | TIM_USE_MC_SERVO | TIM_USE_FW_SERVO }, // PWM8
|
||||
|
||||
{ TIM1, IO_TAG(PA8), TIM_Channel_1, 1, IOCFG_AF_PP, GPIO_AF_6, TIM_USE_LED }, // GPIO_TIMER / LED_STRIP
|
||||
|
||||
|
||||
{ TIM2, IO_TAG(PA0), TIM_Channel_1, 0, IOCFG_AF_PP, GPIO_AF_1, TIM_USE_PPM | TIM_USE_PWM }, // RC_CH1
|
||||
{ TIM2, IO_TAG(PA1), TIM_Channel_2, 0, IOCFG_AF_PP, GPIO_AF_1, TIM_USE_PWM}, // RC_CH2
|
||||
{ TIM2, IO_TAG(PB11), TIM_Channel_4, 0, IOCFG_AF_PP, GPIO_AF_1, TIM_USE_PWM }, // RC_CH3
|
||||
|
|
|
@ -32,7 +32,7 @@ const timerHardware_t timerHardware[USABLE_TIMER_CHANNEL_COUNT] = {
|
|||
{ TIM15, IO_TAG(PA3), TIM_Channel_2, 1, IOCFG_AF_PP, GPIO_AF_9, TIM_USE_MC_MOTOR | TIM_USE_FW_SERVO }, // PWM4
|
||||
#ifdef SPRACINGF3EVO_1SS
|
||||
{ TIM16, IO_TAG(PA6), TIM_Channel_1, 1, IOCFG_AF_PP, GPIO_AF_1, TIM_USE_MC_MOTOR | TIM_USE_FW_SERVO }, // PWM5 - PA6 - TIM3_CH1, TIM8_BKIN, TIM1_BKIN, *TIM16_CH1
|
||||
{ TIM17, IO_TAG(PA7), TIM_Channel_1, 1, IOCFG_AF_PP, GPIO_AF_1, TIM_USE_MC_MOTOR | TIM_USE_FW_SERVO }, // PWM6 - PA7 - TIM3_CH2, *TIM17_CH1, TIM1_CH1N, TIM8_CH1
|
||||
{ TIM17, IO_TAG(PA7), TIM_Channel_1, 1, IOCFG_AF_PP, GPIO_AF_1, TIM_USE_MC_MOTOR | TIM_USE_FW_SERVO }, // PWM6 - PA7 - TIM3_CH2, *TIM17_CH1, TIM1_CH1N, TIM8_CH1
|
||||
#else
|
||||
{ TIM3, IO_TAG(PA6), TIM_Channel_1, 1, IOCFG_AF_PP, GPIO_AF_2, TIM_USE_MC_MOTOR | TIM_USE_MC_CHNFW | TIM_USE_FW_SERVO }, // PWM5
|
||||
{ TIM3, IO_TAG(PA7), TIM_Channel_2, 1, IOCFG_AF_PP, GPIO_AF_2, TIM_USE_MC_MOTOR | TIM_USE_MC_CHNFW | TIM_USE_FW_SERVO }, // PWM6
|
||||
|
|
|
@ -304,7 +304,7 @@ void SetSysClock(void)
|
|||
{
|
||||
HSEStatus = RCC->CR & RCC_CR_HSERDY;
|
||||
StartUpCounter++;
|
||||
} while((HSEStatus == 0) && (StartUpCounter != HSE_STARTUP_TIMEOUT));
|
||||
} while ((HSEStatus == 0) && (StartUpCounter != HSE_STARTUP_TIMEOUT));
|
||||
|
||||
if ((RCC->CR & RCC_CR_HSERDY) != RESET)
|
||||
{
|
||||
|
@ -343,7 +343,7 @@ void SetSysClock(void)
|
|||
RCC->CR |= RCC_CR_PLLON;
|
||||
|
||||
/* Wait till PLL is ready */
|
||||
while((RCC->CR & RCC_CR_PLLRDY) == 0)
|
||||
while ((RCC->CR & RCC_CR_PLLRDY) == 0)
|
||||
{
|
||||
}
|
||||
|
||||
|
|
|
@ -167,16 +167,16 @@
|
|||
RCC_OscInitStruct.PLL.PLLQ = PLL_Q;
|
||||
|
||||
ret = HAL_RCC_OscConfig(&RCC_OscInitStruct);
|
||||
if(ret != HAL_OK)
|
||||
if (ret != HAL_OK)
|
||||
{
|
||||
while(1) { ; }
|
||||
while (1) { ; }
|
||||
}
|
||||
|
||||
/* Activate the OverDrive to reach the 216 MHz Frequency */
|
||||
ret = HAL_PWREx_EnableOverDrive();
|
||||
if(ret != HAL_OK)
|
||||
if (ret != HAL_OK)
|
||||
{
|
||||
while(1) { ; }
|
||||
while (1) { ; }
|
||||
}
|
||||
/* Select PLLSAI output as USB clock source */
|
||||
PeriphClkInitStruct.PeriphClockSelection = RCC_PERIPHCLK_CLK48;
|
||||
|
@ -184,9 +184,9 @@
|
|||
PeriphClkInitStruct.PLLSAI.PLLSAIN = PLL_SAIN;
|
||||
PeriphClkInitStruct.PLLSAI.PLLSAIQ = PLL_SAIQ;
|
||||
PeriphClkInitStruct.PLLSAI.PLLSAIP = PLL_SAIP;
|
||||
if(HAL_RCCEx_PeriphCLKConfig(&PeriphClkInitStruct) != HAL_OK)
|
||||
if (HAL_RCCEx_PeriphCLKConfig(&PeriphClkInitStruct) != HAL_OK)
|
||||
{
|
||||
while(1) {};
|
||||
while (1) {};
|
||||
}
|
||||
|
||||
/* Select PLL as system clock source and configure the HCLK, PCLK1 and PCLK2 clocks dividers */
|
||||
|
@ -197,9 +197,9 @@
|
|||
RCC_ClkInitStruct.APB2CLKDivider = RCC_HCLK_DIV2;
|
||||
|
||||
ret = HAL_RCC_ClockConfig(&RCC_ClkInitStruct, FLASH_LATENCY_7);
|
||||
if(ret != HAL_OK)
|
||||
if (ret != HAL_OK)
|
||||
{
|
||||
while(1) { ; }
|
||||
while (1) { ; }
|
||||
}
|
||||
|
||||
PeriphClkInitStruct.PeriphClockSelection = RCC_PERIPHCLK_USART1|RCC_PERIPHCLK_USART2
|
||||
|
@ -223,7 +223,7 @@
|
|||
ret = HAL_RCCEx_PeriphCLKConfig(&PeriphClkInitStruct);
|
||||
if (ret != HAL_OK)
|
||||
{
|
||||
while(1) { ; }
|
||||
while (1) { ; }
|
||||
}
|
||||
|
||||
// Activating the timerprescalers while the APBx prescalers are 1/2/4 will connect the TIMxCLK to HCLK which has been configured to 216MHz
|
||||
|
@ -288,9 +288,9 @@ void SystemInit(void)
|
|||
/* Configure the system clock to 216 MHz */
|
||||
SystemClock_Config();
|
||||
|
||||
if(SystemCoreClock != 216000000)
|
||||
if (SystemCoreClock != 216000000)
|
||||
{
|
||||
while(1)
|
||||
while (1)
|
||||
{
|
||||
// There is a mismatch between the configured clock and the expected clock in portable.h
|
||||
}
|
||||
|
|
|
@ -222,7 +222,7 @@ bool checkIbusTelemetryState(void) {
|
|||
} else {
|
||||
freeIbusTelemetryPort();
|
||||
}
|
||||
|
||||
|
||||
return true;
|
||||
}
|
||||
|
||||
|
|
|
@ -125,7 +125,7 @@ static uint8_t dispatchMeasurementRequest(ibusAddress_t address) {
|
|||
if (address == 1) { //2. VBAT
|
||||
return sendIbusMeasurement(address, vbat * 10);
|
||||
} else if (address == 2) { //3. BARO_TEMP\GYRO_TEMP
|
||||
if (sensors(SENSOR_BARO)) return sendIbusMeasurement(address, (uint16_t) ((baro.baroTemperature + 50) / 10 + IBUS_TEMPERATURE_OFFSET)); //int32_t
|
||||
if (sensors(SENSOR_BARO)) return sendIbusMeasurement(address, (uint16_t) ((baro.baroTemperature + 50) / 10 + IBUS_TEMPERATURE_OFFSET)); //int32_t
|
||||
else return sendIbusMeasurement(address, (uint16_t) (telemTemperature1 + IBUS_TEMPERATURE_OFFSET)); //int16_t
|
||||
} else if (address == 3) { //4. STATUS (sat num AS #0, FIX AS 0, HDOP AS 0, Mode AS 0)
|
||||
int16_t status = flightModeToIBusTelemetryMode[getFlightModeForTelemetry()];
|
||||
|
@ -145,9 +145,9 @@ static uint8_t dispatchMeasurementRequest(ibusAddress_t address) {
|
|||
return sendIbusMeasurement(address, (uint16_t) (attitude.values.yaw / 10));
|
||||
} else if (address == 5) { //6. CURR //In 10*mA, 1 = 10 mA
|
||||
if (feature(FEATURE_CURRENT_METER)) return sendIbusMeasurement(address, (uint16_t) amperage); //int32_t
|
||||
else return sendIbusMeasurement(address, 0);
|
||||
else return sendIbusMeasurement(address, 0);
|
||||
} else if (address == 6) { //7. BARO_ALT //In cm => m
|
||||
if (sensors(SENSOR_BARO)) return sendIbusMeasurement(address, (uint16_t) baro.BaroAlt); //int32_t
|
||||
if (sensors(SENSOR_BARO)) return sendIbusMeasurement(address, (uint16_t) baro.BaroAlt); //int32_t
|
||||
else return sendIbusMeasurement(address, 0);
|
||||
}
|
||||
#if defined(GPS)
|
||||
|
@ -170,7 +170,7 @@ static uint8_t dispatchMeasurementRequest(ibusAddress_t address) {
|
|||
if (sensors(SENSOR_GPS)) return sendIbusMeasurement(address, (uint16_t) ((gpsSol.llh.lon % 100000)/10));
|
||||
else return sendIbusMeasurement(address, 0);
|
||||
} else if (address == 13) { //14. GPS_LAT1 //Lattitude * 1e+7
|
||||
if (sensors(SENSOR_GPS)) return sendIbusMeasurement(address, (uint16_t) (gpsSol.llh.lat / 100000));
|
||||
if (sensors(SENSOR_GPS)) return sendIbusMeasurement(address, (uint16_t) (gpsSol.llh.lat / 100000));
|
||||
else return sendIbusMeasurement(address, 0);
|
||||
} else if (address == 14) { //15. GPS_LON1 //Longitude * 1e+7
|
||||
if (sensors(SENSOR_GPS)) return sendIbusMeasurement(address, (uint16_t) (gpsSol.llh.lon / 100000));
|
||||
|
|
|
@ -431,7 +431,7 @@ void configureLtmTelemetryPort(void)
|
|||
}
|
||||
|
||||
/* setup scheduler, default to 'normal' */
|
||||
if(telemetryConfig()->ltmUpdateRate == LTM_RATE_MEDIUM)
|
||||
if (telemetryConfig()->ltmUpdateRate == LTM_RATE_MEDIUM)
|
||||
ltm_schedule = ltm_medium_schedule;
|
||||
else if (telemetryConfig()->ltmUpdateRate == LTM_RATE_SLOW)
|
||||
ltm_schedule = ltm_slow_schedule;
|
||||
|
@ -439,9 +439,9 @@ void configureLtmTelemetryPort(void)
|
|||
ltm_schedule = ltm_normal_schedule;
|
||||
|
||||
/* Sanity check that we can support the scheduler */
|
||||
if(baudRateIndex == BAUD_2400 && telemetryConfig()->ltmUpdateRate == LTM_RATE_NORMAL)
|
||||
if (baudRateIndex == BAUD_2400 && telemetryConfig()->ltmUpdateRate == LTM_RATE_NORMAL)
|
||||
ltm_schedule = ltm_medium_schedule;
|
||||
if(baudRateIndex == BAUD_1200)
|
||||
if (baudRateIndex == BAUD_1200)
|
||||
ltm_schedule = ltm_slow_schedule;
|
||||
|
||||
ltmPort = openSerialPort(portConfig->identifier, FUNCTION_TELEMETRY_LTM, NULL, baudRates[baudRateIndex], TELEMETRY_LTM_INITIAL_PORT_MODE, SERIAL_NOT_INVERTED);
|
||||
|
|
|
@ -424,7 +424,7 @@ void mavlinkSendHUDAndHeartbeat(void)
|
|||
mavModes |= MAV_MODE_FLAG_SAFETY_ARMED;
|
||||
|
||||
uint8_t mavSystemType;
|
||||
switch(mixerConfig()->mixerMode)
|
||||
switch (mixerConfig()->mixerMode)
|
||||
{
|
||||
case MIXER_TRI:
|
||||
mavSystemType = MAV_TYPE_TRICOPTER;
|
||||
|
|
|
@ -303,7 +303,7 @@ void handleSmartPortTelemetry(void)
|
|||
|
||||
int32_t tmpi;
|
||||
|
||||
switch(id) {
|
||||
switch (id) {
|
||||
#ifdef GPS
|
||||
case FSSP_DATAID_SPEED :
|
||||
if (sensors(SENSOR_GPS) && STATE(GPS_FIX)) {
|
||||
|
|
|
@ -193,7 +193,7 @@ void USB_Istr(void)
|
|||
_SetCNTR(wCNTR);
|
||||
|
||||
/*poll for RESET flag in ISTR*/
|
||||
while((_GetISTR()&ISTR_RESET) == 0);
|
||||
while ((_GetISTR()&ISTR_RESET) == 0);
|
||||
/* clear RESET flag in ISTR */
|
||||
_SetISTR((uint16_t)CLR_RESET);
|
||||
|
||||
|
|
|
@ -123,7 +123,7 @@ static int8_t CDC_Itf_Init(void)
|
|||
|
||||
/*##-4- Start the TIM Base generation in interrupt mode ####################*/
|
||||
/* Start Channel1 */
|
||||
if(HAL_TIM_Base_Start_IT(&TimHandle) != HAL_OK)
|
||||
if (HAL_TIM_Base_Start_IT(&TimHandle) != HAL_OK)
|
||||
{
|
||||
/* Starting Error */
|
||||
Error_Handler();
|
||||
|
@ -222,14 +222,14 @@ static int8_t CDC_Itf_Control (uint8_t cmd, uint8_t* pbuf, uint16_t length)
|
|||
*/
|
||||
void HAL_TIM_PeriodElapsedCallback(TIM_HandleTypeDef *htim)
|
||||
{
|
||||
if(htim->Instance != TIMusb) return;
|
||||
if (htim->Instance != TIMusb) return;
|
||||
|
||||
uint32_t buffptr;
|
||||
uint32_t buffsize;
|
||||
|
||||
if(UserTxBufPtrOut != UserTxBufPtrIn)
|
||||
if (UserTxBufPtrOut != UserTxBufPtrIn)
|
||||
{
|
||||
if(UserTxBufPtrOut > UserTxBufPtrIn) /* Roll-back */
|
||||
if (UserTxBufPtrOut > UserTxBufPtrIn) /* Roll-back */
|
||||
{
|
||||
buffsize = APP_RX_DATA_SIZE - UserTxBufPtrOut;
|
||||
}
|
||||
|
@ -242,7 +242,7 @@ void HAL_TIM_PeriodElapsedCallback(TIM_HandleTypeDef *htim)
|
|||
|
||||
USBD_CDC_SetTxBuffer(&USBD_Device, (uint8_t*)&UserTxBuffer[buffptr], buffsize);
|
||||
|
||||
if(USBD_CDC_TransmitPacket(&USBD_Device) == USBD_OK)
|
||||
if (USBD_CDC_TransmitPacket(&USBD_Device) == USBD_OK)
|
||||
{
|
||||
UserTxBufPtrOut += buffsize;
|
||||
if (UserTxBufPtrOut == APP_TX_DATA_SIZE)
|
||||
|
@ -288,7 +288,7 @@ static void TIM_Config(void)
|
|||
TimHandle.Init.Prescaler = (SystemCoreClock / 2 / (1000000)) - 1;
|
||||
TimHandle.Init.ClockDivision = 0;
|
||||
TimHandle.Init.CounterMode = TIM_COUNTERMODE_UP;
|
||||
if(HAL_TIM_Base_Init(&TimHandle) != HAL_OK)
|
||||
if (HAL_TIM_Base_Init(&TimHandle) != HAL_OK)
|
||||
{
|
||||
/* Initialization Error */
|
||||
Error_Handler();
|
||||
|
@ -318,7 +318,7 @@ static void Error_Handler(void)
|
|||
uint32_t CDC_Receive_DATA(uint8_t* recvBuf, uint32_t len)
|
||||
{
|
||||
uint32_t count = 0;
|
||||
if( (rxBuffPtr != NULL))
|
||||
if ( (rxBuffPtr != NULL))
|
||||
{
|
||||
while ((rxAvailable > 0) && count < len)
|
||||
{
|
||||
|
@ -326,7 +326,7 @@ uint32_t CDC_Receive_DATA(uint8_t* recvBuf, uint32_t len)
|
|||
rxBuffPtr++;
|
||||
rxAvailable--;
|
||||
count++;
|
||||
if(rxAvailable < 1)
|
||||
if (rxAvailable < 1)
|
||||
USBD_CDC_ReceivePacket(&USBD_Device);
|
||||
}
|
||||
}
|
||||
|
@ -361,7 +361,7 @@ uint32_t CDC_Send_FreeBytes(void)
|
|||
uint32_t CDC_Send_DATA(const uint8_t *ptrBuffer, uint32_t sendLength)
|
||||
{
|
||||
USBD_CDC_HandleTypeDef *hcdc = (USBD_CDC_HandleTypeDef*)USBD_Device.pClassData;
|
||||
while(hcdc->TxState != 0);
|
||||
while (hcdc->TxState != 0);
|
||||
|
||||
for (uint32_t i = 0; i < sendLength; i++)
|
||||
{
|
||||
|
|
|
@ -84,7 +84,7 @@ void HAL_PCD_MspInit(PCD_HandleTypeDef *hpcd)
|
|||
{
|
||||
GPIO_InitTypeDef GPIO_InitStruct;
|
||||
|
||||
if(hpcd->Instance == USB_OTG_FS)
|
||||
if (hpcd->Instance == USB_OTG_FS)
|
||||
{
|
||||
/* Configure USB FS GPIOs */
|
||||
__HAL_RCC_GPIOA_CLK_ENABLE();
|
||||
|
@ -97,7 +97,7 @@ void HAL_PCD_MspInit(PCD_HandleTypeDef *hpcd)
|
|||
GPIO_InitStruct.Alternate = GPIO_AF10_OTG_FS;
|
||||
HAL_GPIO_Init(GPIOA, &GPIO_InitStruct);
|
||||
|
||||
if(hpcd->Init.vbus_sensing_enable == 1)
|
||||
if (hpcd->Init.vbus_sensing_enable == 1)
|
||||
{
|
||||
/* Configure VBUS Pin */
|
||||
GPIO_InitStruct.Pin = GPIO_PIN_9;
|
||||
|
@ -122,7 +122,7 @@ void HAL_PCD_MspInit(PCD_HandleTypeDef *hpcd)
|
|||
/* Enable USBFS Interrupt */
|
||||
HAL_NVIC_EnableIRQ(OTG_FS_IRQn);
|
||||
}
|
||||
else if(hpcd->Instance == USB_OTG_HS)
|
||||
else if (hpcd->Instance == USB_OTG_HS)
|
||||
{
|
||||
#ifdef USE_USB_HS_IN_FS
|
||||
|
||||
|
@ -136,7 +136,7 @@ void HAL_PCD_MspInit(PCD_HandleTypeDef *hpcd)
|
|||
GPIO_InitStruct.Alternate = GPIO_AF12_OTG_HS_FS;
|
||||
HAL_GPIO_Init(GPIOB, &GPIO_InitStruct);
|
||||
|
||||
if(hpcd->Init.vbus_sensing_enable == 1)
|
||||
if (hpcd->Init.vbus_sensing_enable == 1)
|
||||
{
|
||||
/* Configure VBUS Pin */
|
||||
GPIO_InitStruct.Pin = GPIO_PIN_13 ;
|
||||
|
@ -216,13 +216,13 @@ void HAL_PCD_MspInit(PCD_HandleTypeDef *hpcd)
|
|||
*/
|
||||
void HAL_PCD_MspDeInit(PCD_HandleTypeDef *hpcd)
|
||||
{
|
||||
if(hpcd->Instance == USB_OTG_FS)
|
||||
if (hpcd->Instance == USB_OTG_FS)
|
||||
{
|
||||
/* Disable USB FS Clock */
|
||||
__HAL_RCC_USB_OTG_FS_CLK_DISABLE();
|
||||
__HAL_RCC_SYSCFG_CLK_DISABLE();
|
||||
}
|
||||
else if(hpcd->Instance == USB_OTG_HS)
|
||||
else if (hpcd->Instance == USB_OTG_HS)
|
||||
{
|
||||
/* Disable USB HS Clocks */
|
||||
__HAL_RCC_USB_OTG_HS_CLK_DISABLE();
|
||||
|
@ -286,7 +286,7 @@ void HAL_PCD_ResetCallback(PCD_HandleTypeDef *hpcd)
|
|||
USBD_SpeedTypeDef speed = USBD_SPEED_FULL;
|
||||
|
||||
/* Set USB Current Speed */
|
||||
switch(hpcd->Init.speed)
|
||||
switch (hpcd->Init.speed)
|
||||
{
|
||||
case PCD_SPEED_HIGH:
|
||||
speed = USBD_SPEED_HIGH;
|
||||
|
@ -559,7 +559,7 @@ uint8_t USBD_LL_IsStallEP(USBD_HandleTypeDef *pdev, uint8_t ep_addr)
|
|||
{
|
||||
PCD_HandleTypeDef *hpcd = pdev->pData;
|
||||
|
||||
if((ep_addr & 0x80) == 0x80)
|
||||
if ((ep_addr & 0x80) == 0x80)
|
||||
{
|
||||
return hpcd->IN_ep[ep_addr & 0x7F].is_stall;
|
||||
}
|
||||
|
|
|
@ -174,7 +174,7 @@ uint8_t *USBD_VCP_LangIDStrDescriptor(USBD_SpeedTypeDef speed, uint16_t *length)
|
|||
*/
|
||||
uint8_t *USBD_VCP_ProductStrDescriptor(USBD_SpeedTypeDef speed, uint16_t *length)
|
||||
{
|
||||
if(speed == USBD_SPEED_HIGH)
|
||||
if (speed == USBD_SPEED_HIGH)
|
||||
{
|
||||
USBD_GetString((uint8_t *)USBD_PRODUCT_HS_STRING, USBD_StrDesc, length);
|
||||
}
|
||||
|
@ -223,7 +223,7 @@ uint8_t *USBD_VCP_SerialStrDescriptor(USBD_SpeedTypeDef speed, uint16_t *length)
|
|||
*/
|
||||
uint8_t *USBD_VCP_ConfigStrDescriptor(USBD_SpeedTypeDef speed, uint16_t *length)
|
||||
{
|
||||
if(speed == USBD_SPEED_HIGH)
|
||||
if (speed == USBD_SPEED_HIGH)
|
||||
{
|
||||
USBD_GetString((uint8_t *)USBD_CONFIGURATION_HS_STRING, USBD_StrDesc, length);
|
||||
}
|
||||
|
@ -242,7 +242,7 @@ uint8_t *USBD_VCP_ConfigStrDescriptor(USBD_SpeedTypeDef speed, uint16_t *length)
|
|||
*/
|
||||
uint8_t *USBD_VCP_InterfaceStrDescriptor(USBD_SpeedTypeDef speed, uint16_t *length)
|
||||
{
|
||||
if(speed == USBD_SPEED_HIGH)
|
||||
if (speed == USBD_SPEED_HIGH)
|
||||
{
|
||||
USBD_GetString((uint8_t *)USBD_INTERFACE_HS_STRING, USBD_StrDesc, length);
|
||||
}
|
||||
|
@ -286,9 +286,9 @@ static void IntToUnicode (uint32_t value , uint8_t *pbuf , uint8_t len)
|
|||
{
|
||||
uint8_t idx = 0;
|
||||
|
||||
for( idx = 0; idx < len; idx ++)
|
||||
for ( idx = 0; idx < len; idx ++)
|
||||
{
|
||||
if( ((value >> 28)) < 0xA )
|
||||
if ( ((value >> 28)) < 0xA )
|
||||
{
|
||||
pbuf[ 2* idx] = (value >> 28) + '0';
|
||||
}
|
||||
|
|
|
@ -59,7 +59,7 @@ void PendSV_Handler(void)
|
|||
#ifdef USE_USB_OTG_FS
|
||||
void OTG_FS_WKUP_IRQHandler(void)
|
||||
{
|
||||
if(USB_OTG_dev.cfg.low_power)
|
||||
if (USB_OTG_dev.cfg.low_power)
|
||||
{
|
||||
*(uint32_t *)(0xE000ED10) &= 0xFFFFFFF9 ;
|
||||
SystemInit();
|
||||
|
@ -77,7 +77,7 @@ void OTG_FS_WKUP_IRQHandler(void)
|
|||
#ifdef USE_USB_OTG_HS
|
||||
void OTG_HS_WKUP_IRQHandler(void)
|
||||
{
|
||||
if(USB_OTG_dev.cfg.low_power)
|
||||
if (USB_OTG_dev.cfg.low_power)
|
||||
{
|
||||
*(uint32_t *)(0xE000ED10) &= 0xFFFFFFF9 ;
|
||||
SystemInit();
|
||||
|
|
Some files were not shown because too many files have changed in this diff Show more
Loading…
Add table
Add a link
Reference in a new issue