mirror of
https://github.com/betaflight/betaflight.git
synced 2025-07-14 20:10:18 +03:00
Fix function brace style
This commit is contained in:
parent
6a06f0e408
commit
9957ceb275
83 changed files with 494 additions and 251 deletions
|
@ -998,7 +998,8 @@ static void stopInTestMode(void)
|
|||
* Of course, after the 5 seconds and shutdown of the logger, the system will be re-enabled to allow the
|
||||
* test mode to trigger again; its just that the data will be in a second, third, fourth etc log file.
|
||||
*/
|
||||
static bool inMotorTestMode(void) {
|
||||
static bool inMotorTestMode(void)
|
||||
{
|
||||
static uint32_t resetTime = 0;
|
||||
|
||||
if (!ARMING_FLAG(ARMED) && areMotorsRunning()) {
|
||||
|
@ -1959,11 +1960,13 @@ uint8_t blackboxGetRateDenom(void)
|
|||
|
||||
}
|
||||
|
||||
uint16_t blackboxGetPRatio(void) {
|
||||
uint16_t blackboxGetPRatio(void)
|
||||
{
|
||||
return blackboxIInterval / blackboxPInterval;
|
||||
}
|
||||
|
||||
uint8_t blackboxCalculateSampleRate(uint16_t pRatio) {
|
||||
uint8_t blackboxCalculateSampleRate(uint16_t pRatio)
|
||||
{
|
||||
return LOG2(32000 / (targetPidLooptime * pRatio));
|
||||
}
|
||||
|
||||
|
|
|
@ -3640,7 +3640,8 @@ static void cliDumpGyroRegisters(const char *cmdName, char *cmdline)
|
|||
#endif
|
||||
|
||||
|
||||
static int parseOutputIndex(const char *cmdName, char *pch, bool allowAllEscs) {
|
||||
static int parseOutputIndex(const char *cmdName, char *pch, bool allowAllEscs)
|
||||
{
|
||||
int outputIndex = atoi(pch);
|
||||
if ((outputIndex >= 0) && (outputIndex < getMotorCount())) {
|
||||
cliPrintLinef("Using output %d.", outputIndex);
|
||||
|
|
|
@ -39,7 +39,8 @@ float exp_cst2 = 0.f;
|
|||
/* Relative error bounded by 1e-5 for normalized outputs
|
||||
Returns invalid outputs for nan inputs
|
||||
Continuous error */
|
||||
float exp_approx(float val) {
|
||||
float exp_approx(float val)
|
||||
{
|
||||
union { int32_t i; float f; } xu, xu2;
|
||||
float val2, val3, val4, b;
|
||||
int32_t val4i;
|
||||
|
@ -70,7 +71,8 @@ float exp_approx(float val) {
|
|||
Returns a finite number for +inf input
|
||||
Returns -inf for nan and <= 0 inputs.
|
||||
Continuous error. */
|
||||
float log_approx(float val) {
|
||||
float log_approx(float val)
|
||||
{
|
||||
union { float f; int32_t i; } valu;
|
||||
float exp, addcst, x;
|
||||
valu.f = val;
|
||||
|
|
|
@ -167,13 +167,15 @@ float degreesToRadians(int16_t degrees)
|
|||
return degrees * RAD;
|
||||
}
|
||||
|
||||
int scaleRange(int x, int srcFrom, int srcTo, int destFrom, int destTo) {
|
||||
int scaleRange(int x, int srcFrom, int srcTo, int destFrom, int destTo)
|
||||
{
|
||||
long int a = ((long int) destTo - (long int) destFrom) * ((long int) x - (long int) srcFrom);
|
||||
long int b = (long int) srcTo - (long int) srcFrom;
|
||||
return (a / b) + destFrom;
|
||||
}
|
||||
|
||||
float scaleRangef(float x, float srcFrom, float srcTo, float destFrom, float destTo) {
|
||||
float scaleRangef(float x, float srcFrom, float srcTo, float destFrom, float destTo)
|
||||
{
|
||||
float a = (destTo - destFrom) * (x - srcFrom);
|
||||
float b = srcTo - srcFrom;
|
||||
return (a / b) + destFrom;
|
||||
|
@ -329,14 +331,17 @@ void arraySubInt32(int32_t *dest, int32_t *array1, int32_t *array2, int count)
|
|||
}
|
||||
}
|
||||
|
||||
int16_t qPercent(fix12_t q) {
|
||||
int16_t qPercent(fix12_t q)
|
||||
{
|
||||
return (100 * q) >> 12;
|
||||
}
|
||||
|
||||
int16_t qMultiply(fix12_t q, int16_t input) {
|
||||
int16_t qMultiply(fix12_t q, int16_t input)
|
||||
{
|
||||
return (input * q) >> 12;
|
||||
}
|
||||
|
||||
fix12_t qConstruct(int16_t num, int16_t den) {
|
||||
fix12_t qConstruct(int16_t num, int16_t den)
|
||||
{
|
||||
return (num << 12) / den;
|
||||
}
|
||||
|
|
|
@ -237,7 +237,8 @@ bool loadEEPROMFromSDCard(void)
|
|||
#endif
|
||||
|
||||
#ifdef CONFIG_IN_FILE
|
||||
void loadEEPROMFromFile(void) {
|
||||
void loadEEPROMFromFile(void)
|
||||
{
|
||||
FLASH_Unlock(); // load existing config file into eepromData
|
||||
}
|
||||
#endif
|
||||
|
|
|
@ -129,28 +129,34 @@ i2cDevice_t i2cDevice[I2CDEV_COUNT];
|
|||
|
||||
static volatile uint16_t i2cErrorCount = 0;
|
||||
|
||||
void I2C1_ER_IRQHandler(void) {
|
||||
void I2C1_ER_IRQHandler(void)
|
||||
{
|
||||
i2c_er_handler(I2CDEV_1);
|
||||
}
|
||||
|
||||
void I2C1_EV_IRQHandler(void) {
|
||||
void I2C1_EV_IRQHandler(void)
|
||||
{
|
||||
i2c_ev_handler(I2CDEV_1);
|
||||
}
|
||||
|
||||
void I2C2_ER_IRQHandler(void) {
|
||||
void I2C2_ER_IRQHandler(void)
|
||||
{
|
||||
i2c_er_handler(I2CDEV_2);
|
||||
}
|
||||
|
||||
void I2C2_EV_IRQHandler(void) {
|
||||
void I2C2_EV_IRQHandler(void)
|
||||
{
|
||||
i2c_ev_handler(I2CDEV_2);
|
||||
}
|
||||
|
||||
#ifdef STM32F4
|
||||
void I2C3_ER_IRQHandler(void) {
|
||||
void I2C3_ER_IRQHandler(void)
|
||||
{
|
||||
i2c_er_handler(I2CDEV_3);
|
||||
}
|
||||
|
||||
void I2C3_EV_IRQHandler(void) {
|
||||
void I2C3_EV_IRQHandler(void)
|
||||
{
|
||||
i2c_ev_handler(I2CDEV_3);
|
||||
}
|
||||
#endif
|
||||
|
@ -284,8 +290,8 @@ bool i2cRead(I2CDevice device, uint8_t addr_, uint8_t reg_, uint8_t len, uint8_t
|
|||
return i2cReadBuffer(device, addr_, reg_, len, buf) && i2cWait(device);
|
||||
}
|
||||
|
||||
static void i2c_er_handler(I2CDevice device) {
|
||||
|
||||
static void i2c_er_handler(I2CDevice device)
|
||||
{
|
||||
I2C_TypeDef *I2Cx = i2cDevice[device].hardware->reg;
|
||||
|
||||
i2cState_t *state = &i2cDevice[device].state;
|
||||
|
@ -317,8 +323,8 @@ static void i2c_er_handler(I2CDevice device) {
|
|||
state->busy = 0;
|
||||
}
|
||||
|
||||
void i2c_ev_handler(I2CDevice device) {
|
||||
|
||||
void i2c_ev_handler(I2CDevice device)
|
||||
{
|
||||
I2C_TypeDef *I2Cx = i2cDevice[device].hardware->reg;
|
||||
|
||||
i2cState_t *state = &i2cDevice[device].state;
|
||||
|
|
|
@ -295,7 +295,8 @@ static bool ak8963DirectReadData(const extDevice_t *dev, uint8_t *buf)
|
|||
return ak8963ReadRegisterBuffer(dev, AK8963_MAG_REG_HXL, buf, 7);
|
||||
}
|
||||
|
||||
static int16_t parseMag(uint8_t *raw, int16_t gain) {
|
||||
static int16_t parseMag(uint8_t *raw, int16_t gain)
|
||||
{
|
||||
int ret = (int16_t)(raw[1] << 8 | raw[0]) * gain / 256;
|
||||
return constrain(ret, INT16_MIN, INT16_MAX);
|
||||
}
|
||||
|
|
|
@ -111,7 +111,8 @@ static bool ak8975Init(magDev_t *mag)
|
|||
return true;
|
||||
}
|
||||
|
||||
static int16_t parseMag(uint8_t *raw, int16_t gain) {
|
||||
static int16_t parseMag(uint8_t *raw, int16_t gain)
|
||||
{
|
||||
int ret = (int16_t)(raw[1] << 8 | raw[0]) * gain / 256;
|
||||
return constrain(ret, INT16_MIN, INT16_MAX);
|
||||
}
|
||||
|
|
|
@ -46,8 +46,8 @@
|
|||
#include "rx/rx.h"
|
||||
#include "dshot.h"
|
||||
|
||||
|
||||
void dshotInitEndpoints(const motorConfig_t *motorConfig, float outputLimit, float *outputLow, float *outputHigh, float *disarm, float *deadbandMotor3dHigh, float *deadbandMotor3dLow) {
|
||||
void dshotInitEndpoints(const motorConfig_t *motorConfig, float outputLimit, float *outputLow, float *outputHigh, float *disarm, float *deadbandMotor3dHigh, float *deadbandMotor3dLow)
|
||||
{
|
||||
float outputLimitOffset = DSHOT_RANGE * (1 - outputLimit);
|
||||
*disarm = DSHOT_CMD_MOTOR_STOP;
|
||||
if (featureIsEnabled(FEATURE_3D)) {
|
||||
|
|
|
@ -84,7 +84,8 @@ motorVTable_t motorGetVTable(void)
|
|||
}
|
||||
|
||||
// This is not motor generic anymore; should be moved to analog pwm module
|
||||
static void analogInitEndpoints(const motorConfig_t *motorConfig, float outputLimit, float *outputLow, float *outputHigh, float *disarm, float *deadbandMotor3dHigh, float *deadbandMotor3dLow) {
|
||||
static void analogInitEndpoints(const motorConfig_t *motorConfig, float outputLimit, float *outputLow, float *outputHigh, float *disarm, float *deadbandMotor3dHigh, float *deadbandMotor3dLow)
|
||||
{
|
||||
if (featureIsEnabled(FEATURE_3D)) {
|
||||
float outputLimitOffset = (flight3DConfig()->limit3d_high - flight3DConfig()->limit3d_low) * (1 - outputLimit) / 2;
|
||||
*disarm = flight3DConfig()->neutral3d;
|
||||
|
@ -256,7 +257,8 @@ bool isMotorProtocolDshot(void)
|
|||
return motorProtocolDshot;
|
||||
}
|
||||
|
||||
void motorDevInit(const motorDevConfig_t *motorDevConfig, uint16_t idlePulse, uint8_t motorCount) {
|
||||
void motorDevInit(const motorDevConfig_t *motorDevConfig, uint16_t idlePulse, uint8_t motorCount)
|
||||
{
|
||||
memset(motors, 0, sizeof(motors));
|
||||
|
||||
bool useUnsyncedPwm = motorDevConfig->useUnsyncedPwm;
|
||||
|
|
|
@ -76,7 +76,8 @@ void A7105Config(const uint8_t *regsTable, uint8_t size)
|
|||
}
|
||||
}
|
||||
|
||||
bool A7105RxTxFinished(timeUs_t *timeStamp) {
|
||||
bool A7105RxTxFinished(timeUs_t *timeStamp)
|
||||
{
|
||||
bool result = false;
|
||||
|
||||
if (consumeExti && rxSpiPollExti()) {
|
||||
|
|
|
@ -690,12 +690,14 @@ SD_Error_t SD_WriteBlocks_DMA(uint64_t WriteAddress, uint32_t *buffer, uint32_t
|
|||
return ErrorState;
|
||||
}
|
||||
|
||||
SD_Error_t SD_CheckWrite(void) {
|
||||
SD_Error_t SD_CheckWrite(void)
|
||||
{
|
||||
if (SD_Handle.TXCplt != 0) return SD_BUSY;
|
||||
return SD_OK;
|
||||
}
|
||||
|
||||
SD_Error_t SD_CheckRead(void) {
|
||||
SD_Error_t SD_CheckRead(void)
|
||||
{
|
||||
if (SD_Handle.RXCplt != 0) return SD_BUSY;
|
||||
return SD_OK;
|
||||
}
|
||||
|
@ -1724,7 +1726,8 @@ SD_Error_t SD_Init(void)
|
|||
/**
|
||||
* @brief This function handles SD card interrupt request.
|
||||
*/
|
||||
void SDIO_IRQHandler(void) {
|
||||
void SDIO_IRQHandler(void)
|
||||
{
|
||||
// Check for SDIO interrupt flags
|
||||
if ((SDIO->STA & SDIO_STA_DATAEND) != 0) {
|
||||
SDIO->ICR = SDIO_ICR_DATAENDC;
|
||||
|
|
|
@ -672,12 +672,14 @@ SD_Error_t SD_WriteBlocks_DMA(uint64_t WriteAddress, uint32_t *buffer, uint32_t
|
|||
return ErrorState;
|
||||
}
|
||||
|
||||
SD_Error_t SD_CheckWrite(void) {
|
||||
SD_Error_t SD_CheckWrite(void)
|
||||
{
|
||||
if (SD_Handle.TXCplt != 0) return SD_BUSY;
|
||||
return SD_OK;
|
||||
}
|
||||
|
||||
SD_Error_t SD_CheckRead(void) {
|
||||
SD_Error_t SD_CheckRead(void)
|
||||
{
|
||||
if (SD_Handle.RXCplt != 0) return SD_BUSY;
|
||||
return SD_OK;
|
||||
}
|
||||
|
@ -1705,7 +1707,8 @@ SD_Error_t SD_Init(void)
|
|||
/**
|
||||
* @brief This function handles SD card interrupt request.
|
||||
*/
|
||||
void SDMMC1_IRQHandler(void) {
|
||||
void SDMMC1_IRQHandler(void)
|
||||
{
|
||||
// Check for SDMMC1 interrupt flags
|
||||
if ((SDMMC1->STA & SDMMC_STA_DATAEND) != 0) {
|
||||
SDMMC1->ICR = SDMMC_ICR_DATAENDC;
|
||||
|
|
|
@ -540,12 +540,14 @@ SD_Error_t SD_Init(void)
|
|||
return result;
|
||||
}
|
||||
|
||||
SD_Error_t SD_CheckWrite(void) {
|
||||
SD_Error_t SD_CheckWrite(void)
|
||||
{
|
||||
if (SD_Handle.TXCplt != 0) return SD_BUSY;
|
||||
return SD_OK;
|
||||
}
|
||||
|
||||
SD_Error_t SD_CheckRead(void) {
|
||||
SD_Error_t SD_CheckRead(void)
|
||||
{
|
||||
if (SD_Handle.RXCplt != 0) return SD_BUSY;
|
||||
return SD_OK;
|
||||
}
|
||||
|
|
|
@ -44,14 +44,17 @@ static const struct serialPortVTable tcpVTable; // Forward
|
|||
static tcpPort_t tcpSerialPorts[SERIAL_PORT_COUNT];
|
||||
static bool tcpPortInitialized[SERIAL_PORT_COUNT];
|
||||
static bool tcpStart = false;
|
||||
bool tcpIsStart(void) {
|
||||
bool tcpIsStart(void)
|
||||
{
|
||||
return tcpStart;
|
||||
}
|
||||
static void onData(dyad_Event *e) {
|
||||
static void onData(dyad_Event *e)
|
||||
{
|
||||
tcpPort_t* s = (tcpPort_t*)(e->udata);
|
||||
tcpDataIn(s, (uint8_t*)e->data, e->size);
|
||||
}
|
||||
static void onClose(dyad_Event *e) {
|
||||
static void onClose(dyad_Event *e)
|
||||
{
|
||||
tcpPort_t* s = (tcpPort_t*)(e->udata);
|
||||
s->clientCount--;
|
||||
s->conn = NULL;
|
||||
|
@ -60,7 +63,8 @@ static void onClose(dyad_Event *e) {
|
|||
s->connected = false;
|
||||
}
|
||||
}
|
||||
static void onAccept(dyad_Event *e) {
|
||||
static void onAccept(dyad_Event *e)
|
||||
{
|
||||
tcpPort_t* s = (tcpPort_t*)(e->udata);
|
||||
fprintf(stderr, "New connection on UART%u, %d\n", s->id + 1, s->clientCount);
|
||||
|
||||
|
|
|
@ -46,7 +46,8 @@
|
|||
#include "drivers/serial_uart.h"
|
||||
#include "drivers/serial_uart_impl.h"
|
||||
|
||||
static void usartConfigurePinInversion(uartPort_t *uartPort) {
|
||||
static void usartConfigurePinInversion(uartPort_t *uartPort)
|
||||
{
|
||||
bool inverted = uartPort->port.options & SERIAL_INVERTED;
|
||||
|
||||
if (inverted)
|
||||
|
|
|
@ -48,7 +48,8 @@
|
|||
#include "drivers/serial_uart.h"
|
||||
#include "drivers/serial_uart_impl.h"
|
||||
|
||||
static void usartConfigurePinInversion(uartPort_t *uartPort) {
|
||||
static void usartConfigurePinInversion(uartPort_t *uartPort)
|
||||
{
|
||||
#if !defined(USE_INVERTER)
|
||||
UNUSED(uartPort);
|
||||
#else
|
||||
|
|
|
@ -44,14 +44,16 @@ __STATIC_INLINE uint32_t LL_EX_DMA_Stream_to_Stream(DMA_Stream_TypeDef *DMAx_Str
|
|||
|
||||
#undef DMA_STREAM_MASK
|
||||
|
||||
__STATIC_INLINE uint32_t LL_EX_DMA_Init(DMA_Stream_TypeDef *DMAx_Streamy, LL_DMA_InitTypeDef *DMA_InitStruct) {
|
||||
__STATIC_INLINE uint32_t LL_EX_DMA_Init(DMA_Stream_TypeDef *DMAx_Streamy, LL_DMA_InitTypeDef *DMA_InitStruct)
|
||||
{
|
||||
DMA_TypeDef *DMA = LL_EX_DMA_Stream_to_DMA(DMAx_Streamy);
|
||||
const uint32_t Stream = LL_EX_DMA_Stream_to_Stream(DMAx_Streamy);
|
||||
|
||||
return LL_DMA_Init(DMA, Stream, DMA_InitStruct);
|
||||
}
|
||||
|
||||
__STATIC_INLINE uint32_t LL_EX_DMA_DeInit(DMA_Stream_TypeDef *DMAx_Streamy) {
|
||||
__STATIC_INLINE uint32_t LL_EX_DMA_DeInit(DMA_Stream_TypeDef *DMAx_Streamy)
|
||||
{
|
||||
DMA_TypeDef *DMA = LL_EX_DMA_Stream_to_DMA(DMAx_Streamy);
|
||||
const uint32_t Stream = LL_EX_DMA_Stream_to_Stream(DMAx_Streamy);
|
||||
|
||||
|
|
|
@ -45,14 +45,16 @@ __STATIC_INLINE uint32_t LL_EX_DMA_Channel_to_Channel(DMA_Channel_TypeDef *DMAx_
|
|||
#undef DMA_FIRST_CHANNEL_OFFSET
|
||||
#undef DMA_CHANNEL_SIZE
|
||||
|
||||
__STATIC_INLINE uint32_t LL_EX_DMA_Init(DMA_Channel_TypeDef *DMAx_Channely, LL_DMA_InitTypeDef *DMA_InitStruct) {
|
||||
__STATIC_INLINE uint32_t LL_EX_DMA_Init(DMA_Channel_TypeDef *DMAx_Channely, LL_DMA_InitTypeDef *DMA_InitStruct)
|
||||
{
|
||||
DMA_TypeDef *DMA = LL_EX_DMA_Channel_to_DMA(DMAx_Channely);
|
||||
const uint32_t Channel = LL_EX_DMA_Channel_to_Channel(DMAx_Channely);
|
||||
|
||||
return LL_DMA_Init(DMA, Channel, DMA_InitStruct);
|
||||
}
|
||||
|
||||
__STATIC_INLINE uint32_t LL_EX_DMA_DeInit(DMA_Channel_TypeDef *DMAx_Channely) {
|
||||
__STATIC_INLINE uint32_t LL_EX_DMA_DeInit(DMA_Channel_TypeDef *DMAx_Channely)
|
||||
{
|
||||
DMA_TypeDef *DMA = LL_EX_DMA_Channel_to_DMA(DMAx_Channely);
|
||||
const uint32_t Channel = LL_EX_DMA_Channel_to_Channel(DMAx_Channely);
|
||||
|
||||
|
|
|
@ -47,14 +47,16 @@ __STATIC_INLINE uint32_t LL_EX_DMA_Stream_to_Stream(DMA_Stream_TypeDef *DMAx_Str
|
|||
|
||||
#undef DMA_STREAM_MASK
|
||||
|
||||
__STATIC_INLINE uint32_t LL_EX_DMA_Init(DMA_Stream_TypeDef *DMAx_Streamy, LL_DMA_InitTypeDef *DMA_InitStruct) {
|
||||
__STATIC_INLINE uint32_t LL_EX_DMA_Init(DMA_Stream_TypeDef *DMAx_Streamy, LL_DMA_InitTypeDef *DMA_InitStruct)
|
||||
{
|
||||
DMA_TypeDef *DMA = LL_EX_DMA_Stream_to_DMA(DMAx_Streamy);
|
||||
const uint32_t Stream = LL_EX_DMA_Stream_to_Stream(DMAx_Streamy);
|
||||
|
||||
return LL_DMA_Init(DMA, Stream, DMA_InitStruct);
|
||||
}
|
||||
|
||||
__STATIC_INLINE uint32_t LL_EX_DMA_DeInit(DMA_Stream_TypeDef *DMAx_Streamy) {
|
||||
__STATIC_INLINE uint32_t LL_EX_DMA_DeInit(DMA_Stream_TypeDef *DMAx_Streamy)
|
||||
{
|
||||
DMA_TypeDef *DMA = LL_EX_DMA_Stream_to_DMA(DMAx_Streamy);
|
||||
const uint32_t Stream = LL_EX_DMA_Stream_to_Stream(DMAx_Streamy);
|
||||
|
||||
|
|
|
@ -401,7 +401,8 @@ void timerChOvrHandlerInit(timerOvrHandlerRec_t *self, timerOvrHandlerCallback *
|
|||
|
||||
// update overflow callback list
|
||||
// some synchronization mechanism is neccesary to avoid disturbing other channels (BASEPRI used now)
|
||||
static void timerChConfig_UpdateOverflow(timerConfig_t *cfg, const TIM_TypeDef *tim) {
|
||||
static void timerChConfig_UpdateOverflow(timerConfig_t *cfg, const TIM_TypeDef *tim)
|
||||
{
|
||||
timerOvrHandlerRec_t **chain = &cfg->overflowCallbackActive;
|
||||
ATOMIC_BLOCK(NVIC_PRIO_TIMER) {
|
||||
|
||||
|
@ -489,7 +490,8 @@ void timerChConfigCallbacksDual(const timerHardware_t *timHw, timerCCHandlerRec_
|
|||
}
|
||||
|
||||
// enable/disable IRQ for low channel in dual configuration
|
||||
void timerChITConfigDualLo(const timerHardware_t *timHw, FunctionalState newState) {
|
||||
void timerChITConfigDualLo(const timerHardware_t *timHw, FunctionalState newState)
|
||||
{
|
||||
TIM_ITConfig(timHw->tim, TIM_IT_CCx(timHw->channel&~TIM_Channel_2), newState);
|
||||
}
|
||||
|
||||
|
|
|
@ -34,7 +34,8 @@
|
|||
extern const struct transponderVTable arcitimerTansponderVTable;
|
||||
static uint16_t dmaBufferOffset;
|
||||
|
||||
void transponderIrInitArcitimer(transponder_t *transponder){
|
||||
void transponderIrInitArcitimer(transponder_t *transponder)
|
||||
{
|
||||
// from drivers/transponder_ir.h
|
||||
transponder->gap_toggles = TRANSPONDER_GAP_TOGGLES_ARCITIMER;
|
||||
transponder->dma_buffer_size = TRANSPONDER_DMA_BUFFER_SIZE_ARCITIMER;
|
||||
|
|
|
@ -33,7 +33,8 @@
|
|||
static uint16_t dmaBufferOffset;
|
||||
extern const struct transponderVTable erltTansponderVTable;
|
||||
|
||||
void transponderIrInitERLT(transponder_t *transponder){
|
||||
void transponderIrInitERLT(transponder_t *transponder)
|
||||
{
|
||||
transponder->dma_buffer_size = TRANSPONDER_DMA_BUFFER_SIZE_ERLT;
|
||||
transponder->vTable = &erltTansponderVTable;
|
||||
transponder->timer_hz = TRANSPONDER_TIMER_MHZ_ERLT;
|
||||
|
|
|
@ -33,7 +33,8 @@
|
|||
static uint16_t dmaBufferOffset;
|
||||
extern const struct transponderVTable ilapTansponderVTable;
|
||||
|
||||
void transponderIrInitIlap(transponder_t *transponder){
|
||||
void transponderIrInitIlap(transponder_t *transponder)
|
||||
{
|
||||
// from drivers/transponder_ir.h
|
||||
transponder->gap_toggles = TRANSPONDER_GAP_TOGGLES_ILAP;
|
||||
transponder->dma_buffer_size = TRANSPONDER_DMA_BUFFER_SIZE_ILAP;
|
||||
|
|
|
@ -94,7 +94,8 @@ void changeControlRateProfile(uint8_t controlRateProfileIndex)
|
|||
initRcProcessing();
|
||||
}
|
||||
|
||||
void copyControlRateProfile(const uint8_t dstControlRateProfileIndex, const uint8_t srcControlRateProfileIndex) {
|
||||
void copyControlRateProfile(const uint8_t dstControlRateProfileIndex, const uint8_t srcControlRateProfileIndex)
|
||||
{
|
||||
if ((dstControlRateProfileIndex < CONTROL_RATE_PROFILE_COUNT && srcControlRateProfileIndex < CONTROL_RATE_PROFILE_COUNT)
|
||||
&& dstControlRateProfileIndex != srcControlRateProfileIndex
|
||||
) {
|
||||
|
|
|
@ -733,7 +733,8 @@ rcSmoothingFilter_t *getRcSmoothingData(void)
|
|||
return &rcSmoothingData;
|
||||
}
|
||||
|
||||
bool rcSmoothingInitializationComplete(void) {
|
||||
bool rcSmoothingInitializationComplete(void)
|
||||
{
|
||||
return rcSmoothingData.filterInitialized;
|
||||
}
|
||||
#endif // USE_RC_SMOOTHING_FILTER
|
||||
|
|
|
@ -410,7 +410,8 @@ void processRcStickPositions()
|
|||
#endif
|
||||
}
|
||||
|
||||
int32_t getRcStickDeflection(int32_t axis, uint16_t midrc) {
|
||||
int32_t getRcStickDeflection(int32_t axis, uint16_t midrc)
|
||||
{
|
||||
return MIN(ABS(rcData[axis] - midrc), 500);
|
||||
}
|
||||
|
||||
|
|
|
@ -79,11 +79,13 @@ void rcModeUpdate(boxBitmask_t *newState)
|
|||
rcModeActivationMask = *newState;
|
||||
}
|
||||
|
||||
bool airmodeIsEnabled(void) {
|
||||
bool airmodeIsEnabled(void)
|
||||
{
|
||||
return airmodeEnabled;
|
||||
}
|
||||
|
||||
bool isRangeActive(uint8_t auxChannelIndex, const channelRange_t *range) {
|
||||
bool isRangeActive(uint8_t auxChannelIndex, const channelRange_t *range)
|
||||
{
|
||||
if (!IS_RANGE_USABLE(range)) {
|
||||
return false;
|
||||
}
|
||||
|
|
|
@ -48,7 +48,8 @@ typedef struct laggedMovingAverageCombined_s {
|
|||
} laggedMovingAverageCombined_t;
|
||||
laggedMovingAverageCombined_t setpointDeltaAvg[XYZ_AXIS_COUNT];
|
||||
|
||||
void feedforwardInit(const pidProfile_t *pidProfile) {
|
||||
void feedforwardInit(const pidProfile_t *pidProfile)
|
||||
{
|
||||
const float feedforwardMaxRateScale = pidProfile->feedforward_max_rate_limit * 0.01f;
|
||||
averagingCount = pidProfile->feedforward_averaging + 1;
|
||||
for (int i = 0; i < XYZ_AXIS_COUNT; i++) {
|
||||
|
@ -58,7 +59,8 @@ void feedforwardInit(const pidProfile_t *pidProfile) {
|
|||
}
|
||||
}
|
||||
|
||||
FAST_CODE_NOINLINE float feedforwardApply(int axis, bool newRcFrame, feedforwardAveraging_t feedforwardAveraging) {
|
||||
FAST_CODE_NOINLINE float feedforwardApply(int axis, bool newRcFrame, feedforwardAveraging_t feedforwardAveraging)
|
||||
{
|
||||
|
||||
if (newRcFrame) {
|
||||
|
||||
|
@ -191,7 +193,8 @@ FAST_CODE_NOINLINE float feedforwardApply(int axis, bool newRcFrame, feedforward
|
|||
return setpointDelta[axis]; // the value used by the PID code
|
||||
}
|
||||
|
||||
FAST_CODE_NOINLINE float applyFeedforwardLimit(int axis, float value, float Kp, float currentPidSetpoint) {
|
||||
FAST_CODE_NOINLINE float applyFeedforwardLimit(int axis, float value, float Kp, float currentPidSetpoint)
|
||||
{
|
||||
switch (axis) {
|
||||
case FD_ROLL:
|
||||
DEBUG_SET(DEBUG_FEEDFORWARD_LIMIT, 0, value);
|
||||
|
|
|
@ -133,7 +133,8 @@ static void imuQuaternionComputeProducts(quaternion *quat, quaternionProducts *q
|
|||
quatProd->zz = quat->z * quat->z;
|
||||
}
|
||||
|
||||
STATIC_UNIT_TESTED void imuComputeRotationMatrix(void){
|
||||
STATIC_UNIT_TESTED void imuComputeRotationMatrix(void)
|
||||
{
|
||||
imuQuaternionComputeProducts(&q, &qP);
|
||||
|
||||
rMat[0][0] = 1.0f - 2.0f * qP.yy - 2.0f * qP.zz;
|
||||
|
|
|
@ -424,7 +424,8 @@ static void updateDynLpfCutoffs(timeUs_t currentTimeUs, float throttle)
|
|||
}
|
||||
#endif
|
||||
|
||||
static void applyMixerAdjustmentLinear(float *motorMix, const bool airmodeEnabled) {
|
||||
static void applyMixerAdjustmentLinear(float *motorMix, const bool airmodeEnabled)
|
||||
{
|
||||
float airmodeTransitionPercent = 1.0f;
|
||||
float motorDeltaScale = 0.5f;
|
||||
|
||||
|
@ -458,7 +459,8 @@ static void applyMixerAdjustmentLinear(float *motorMix, const bool airmodeEnable
|
|||
throttle = constrainf(throttle, -minMotor, 1.0f - maxMotor);
|
||||
}
|
||||
|
||||
static void applyMixerAdjustment(float *motorMix, const float motorMixMin, const float motorMixMax, const bool airmodeEnabled) {
|
||||
static void applyMixerAdjustment(float *motorMix, const float motorMixMin, const float motorMixMax, const bool airmodeEnabled)
|
||||
{
|
||||
#ifdef USE_AIRMODE_LPF
|
||||
const float unadjustedThrottle = throttle;
|
||||
throttle += pidGetAirmodeThrottleOffset();
|
||||
|
|
|
@ -427,7 +427,8 @@ STATIC_UNIT_TESTED FAST_CODE_NOINLINE float calcHorizonLevelStrength()
|
|||
// The impact is possibly slightly slower performance on F7/H7 but they have more than enough
|
||||
// processing power that it should be a non-issue.
|
||||
STATIC_UNIT_TESTED FAST_CODE_NOINLINE float pidLevel(int axis, const pidProfile_t *pidProfile, const rollAndPitchTrims_t *angleTrim,
|
||||
float currentPidSetpoint, float horizonLevelStrength) {
|
||||
float currentPidSetpoint, float horizonLevelStrength)
|
||||
{
|
||||
const float levelAngleLimit = pidProfile->levelAngleLimit;
|
||||
// calculate error angle and limit the angle to the max inclination
|
||||
// rcDeflection is in range [-1.0, 1.0]
|
||||
|
@ -1251,7 +1252,8 @@ void dynLpfDTermUpdate(float throttle)
|
|||
}
|
||||
#endif
|
||||
|
||||
float dynLpfCutoffFreq(float throttle, uint16_t dynLpfMin, uint16_t dynLpfMax, uint8_t expo) {
|
||||
float dynLpfCutoffFreq(float throttle, uint16_t dynLpfMin, uint16_t dynLpfMax, uint8_t expo)
|
||||
{
|
||||
const float expof = expo / 10.0f;
|
||||
const float curve = throttle * (1 - throttle) * expof + throttle;
|
||||
return (dynLpfMax - dynLpfMin) * curve + dynLpfMin;
|
||||
|
|
|
@ -298,7 +298,8 @@ static void shiftPacketLog(void)
|
|||
}
|
||||
}
|
||||
|
||||
static bool isConfiguratorConnected() {
|
||||
static bool isConfiguratorConnected()
|
||||
{
|
||||
return (getArmingDisableFlags() & ARMING_DISABLED_MSP);
|
||||
}
|
||||
|
||||
|
@ -473,7 +474,8 @@ static void ubloxSendPollMessage(uint8_t msg_id)
|
|||
ubloxSendMessage((const uint8_t *) &tx_buffer, 6);
|
||||
}
|
||||
|
||||
static void ubloxSendNAV5Message(bool airborne) {
|
||||
static void ubloxSendNAV5Message(bool airborne)
|
||||
{
|
||||
ubx_message tx_buffer;
|
||||
tx_buffer.payload.cfg_nav5.mask = 0xFFFF;
|
||||
if (airborne) {
|
||||
|
@ -511,7 +513,8 @@ static void ubloxSendNAV5Message(bool airborne) {
|
|||
ubloxSendConfigMessage(&tx_buffer, MSG_CFG_NAV_SETTINGS, sizeof(ubx_cfg_nav5));
|
||||
}
|
||||
|
||||
static void ubloxSetMessageRate(uint8_t messageClass, uint8_t messageID, uint8_t rate) {
|
||||
static void ubloxSetMessageRate(uint8_t messageClass, uint8_t messageID, uint8_t rate)
|
||||
{
|
||||
ubx_message tx_buffer;
|
||||
tx_buffer.payload.cfg_msg.msgClass = messageClass;
|
||||
tx_buffer.payload.cfg_msg.msgID = messageID;
|
||||
|
@ -519,7 +522,8 @@ static void ubloxSetMessageRate(uint8_t messageClass, uint8_t messageID, uint8_t
|
|||
ubloxSendConfigMessage(&tx_buffer, MSG_CFG_MSG, sizeof(ubx_cfg_msg));
|
||||
}
|
||||
|
||||
static void ubloxSetNavRate(uint16_t measRate, uint16_t navRate, uint16_t timeRef) {
|
||||
static void ubloxSetNavRate(uint16_t measRate, uint16_t navRate, uint16_t timeRef)
|
||||
{
|
||||
ubx_message tx_buffer;
|
||||
tx_buffer.payload.cfg_rate.measRate = measRate;
|
||||
tx_buffer.payload.cfg_rate.navRate = navRate;
|
||||
|
@ -527,7 +531,8 @@ static void ubloxSetNavRate(uint16_t measRate, uint16_t navRate, uint16_t timeRe
|
|||
ubloxSendConfigMessage(&tx_buffer, MSG_CFG_RATE, sizeof(ubx_cfg_rate));
|
||||
}
|
||||
|
||||
static void ubloxSetSbas() {
|
||||
static void ubloxSetSbas()
|
||||
{
|
||||
ubx_message tx_buffer;
|
||||
|
||||
//NOTE: default ublox config for sbas mode is: UBLOX_MODE_ENABLED, test is disabled
|
||||
|
|
|
@ -1047,7 +1047,8 @@ void updateRequiredOverlay(void)
|
|||
disabledTimerMask |= !isOverlayTypeUsed(LED_OVERLAY_INDICATOR) << timIndicator;
|
||||
}
|
||||
|
||||
static void applyStatusProfile(timeUs_t now) {
|
||||
static void applyStatusProfile(timeUs_t now)
|
||||
{
|
||||
|
||||
// apply all layers; triggered timed functions has to update timers
|
||||
// test all led timers, setting corresponding bits
|
||||
|
|
|
@ -205,7 +205,8 @@ serialPortUsage_t *findSerialPortUsageByIdentifier(serialPortIdentifier_e identi
|
|||
return NULL;
|
||||
}
|
||||
|
||||
serialPortUsage_t *findSerialPortUsageByPort(serialPort_t *serialPort) {
|
||||
serialPortUsage_t *findSerialPortUsageByPort(serialPort_t *serialPort)
|
||||
{
|
||||
uint8_t index;
|
||||
for (index = 0; index < SERIAL_PORT_COUNT; index++) {
|
||||
serialPortUsage_t *candidate = &serialPortUsageList[index];
|
||||
|
|
|
@ -314,7 +314,8 @@ void esc4wayRelease(void)
|
|||
CONTRACT, STRICT LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE)
|
||||
ARISING IN ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
|
||||
POSSIBILITY OF SUCH DAMAGE. */
|
||||
uint16_t _crc_xmodem_update (uint16_t crc, uint8_t data) {
|
||||
uint16_t _crc_xmodem_update (uint16_t crc, uint8_t data)
|
||||
{
|
||||
int i;
|
||||
|
||||
crc = crc ^ ((uint16_t)data << 8);
|
||||
|
|
|
@ -50,7 +50,8 @@ static uint16_t spek_fade_last_sec_count = 0; // Stores the fade count at the la
|
|||
#endif
|
||||
|
||||
// Linear mapping and interpolation function
|
||||
int32_t map(int32_t x, int32_t in_min, int32_t in_max, int32_t out_min, int32_t out_max) {
|
||||
int32_t map(int32_t x, int32_t in_min, int32_t in_max, int32_t out_min, int32_t out_max)
|
||||
{
|
||||
return (x - in_min) * (out_max - out_min) / (in_max - in_min) + out_min;
|
||||
}
|
||||
|
||||
|
@ -90,7 +91,8 @@ static const dbm_table_t dbmTable[] = {
|
|||
{SPEKTRUM_RSSI_MIN, 0}};
|
||||
|
||||
// Convert dBm to Range %
|
||||
static int8_t dBm2range (int8_t dBm) {
|
||||
static int8_t dBm2range (int8_t dBm)
|
||||
{
|
||||
int8_t retval = dbmTable[0].reportAs;
|
||||
|
||||
dBm = constrain(dBm, SPEKTRUM_RSSI_MIN, SPEKTRUM_RSSI_MAX);
|
||||
|
@ -107,7 +109,8 @@ static int8_t dBm2range (int8_t dBm) {
|
|||
}
|
||||
#endif
|
||||
|
||||
void spektrumHandleRSSI(volatile uint8_t spekFrame[]) {
|
||||
void spektrumHandleRSSI(volatile uint8_t spekFrame[])
|
||||
{
|
||||
#ifdef USE_SPEKTRUM_REAL_RSSI
|
||||
static int8_t spek_last_rssi = SPEKTRUM_RSSI_MAX;
|
||||
static uint8_t spek_fade_count = 0;
|
||||
|
|
|
@ -38,7 +38,8 @@ typedef enum {
|
|||
|
||||
static warningLedState_e warningLedState = WARNING_LED_OFF;
|
||||
|
||||
void warningLedResetTimer(void) {
|
||||
void warningLedResetTimer(void)
|
||||
{
|
||||
uint32_t now = millis();
|
||||
warningLedTimer = now + 500000;
|
||||
}
|
||||
|
|
|
@ -136,7 +136,8 @@ void transponderUpdateData(void)
|
|||
transponderIrUpdateData(transponderConfig()->data);
|
||||
}
|
||||
|
||||
void transponderTransmitOnce(void) {
|
||||
void transponderTransmitOnce(void)
|
||||
{
|
||||
|
||||
if (!transponderInitialised) {
|
||||
return;
|
||||
|
|
|
@ -106,7 +106,8 @@ mspDescriptor_t getMspSerialPortDescriptor(const uint8_t portIdentifier)
|
|||
}
|
||||
|
||||
#if defined(USE_TELEMETRY)
|
||||
void mspSerialReleaseSharedTelemetryPorts(void) {
|
||||
void mspSerialReleaseSharedTelemetryPorts(void)
|
||||
{
|
||||
for (uint8_t portIndex = 0; portIndex < MAX_MSP_PORT_COUNT; portIndex++) {
|
||||
mspPort_t *candidateMspPort = &mspPorts[portIndex];
|
||||
if (candidateMspPort->sharedWithTelemetry) {
|
||||
|
|
|
@ -1900,7 +1900,8 @@ void osdElementsInit(bool backgroundLayerFlag)
|
|||
pt1FilterInit(&batteryEfficiencyFilt, pt1FilterGain(EFFICIENCY_CUTOFF_HZ, 1.0f / osdConfig()->framerate_hz));
|
||||
}
|
||||
|
||||
void osdSyncBlink() {
|
||||
void osdSyncBlink()
|
||||
{
|
||||
static int blinkCount = 0;
|
||||
|
||||
// If the OSD blink is due a transition, do so
|
||||
|
|
|
@ -209,7 +209,8 @@ static void checkRSSI(void)
|
|||
setRssiDirect(tmp, RSSI_SOURCE_RX_PROTOCOL);
|
||||
}
|
||||
|
||||
static bool isValidPacket(const uint8_t *packet) {
|
||||
static bool isValidPacket(const uint8_t *packet)
|
||||
{
|
||||
const flySky2ARcDataPkt_t *rcPacket = (const flySky2ARcDataPkt_t*) packet;
|
||||
return (rcPacket->rxId == rxId && rcPacket->txId == txId);
|
||||
}
|
||||
|
|
|
@ -150,7 +150,8 @@ static void buildTelemetryFrame(uint8_t *packet)
|
|||
|
||||
#define FRSKY_D_CHANNEL_SCALING (2.0f / 3)
|
||||
|
||||
static void decodeChannelPair(uint16_t *channels, const uint8_t *packet, const uint8_t highNibbleOffset) {
|
||||
static void decodeChannelPair(uint16_t *channels, const uint8_t *packet, const uint8_t highNibbleOffset)
|
||||
{
|
||||
channels[0] = FRSKY_D_CHANNEL_SCALING * (uint16_t)((packet[highNibbleOffset] & 0xf) << 8 | packet[0]);
|
||||
channels[1] = FRSKY_D_CHANNEL_SCALING * (uint16_t)((packet[highNibbleOffset] & 0xf0) << 4 | packet[1]);
|
||||
}
|
||||
|
|
|
@ -154,7 +154,8 @@ const cc2500RegisterConfigElement_t cc2500FrskyXLbtV2Config[] =
|
|||
{ CC2500_08_PKTCTRL0, 0x05 },
|
||||
};
|
||||
|
||||
static void initialise() {
|
||||
static void initialise()
|
||||
{
|
||||
rxSpiStartupSpeed();
|
||||
|
||||
cc2500Reset();
|
||||
|
|
|
@ -134,14 +134,16 @@ static uint8_t remoteToProcessIndex = 0;
|
|||
static uint8_t packetLength;
|
||||
static uint16_t telemetryDelayUs;
|
||||
|
||||
static uint16_t crcTable(uint8_t val) {
|
||||
static uint16_t crcTable(uint8_t val)
|
||||
{
|
||||
uint16_t word;
|
||||
word = (*(&crcTable_Short[val & 0x0f]));
|
||||
val /= 16;
|
||||
return word ^ (0x1081 * val);
|
||||
}
|
||||
|
||||
static uint16_t calculateCrc(const uint8_t *data, uint8_t len) {
|
||||
static uint16_t calculateCrc(const uint8_t *data, uint8_t len)
|
||||
{
|
||||
uint16_t crc = 0;
|
||||
for (unsigned i = 0; i < len; i++) {
|
||||
crc = (crc << 8) ^ crcTable((uint8_t)(crc >> 8) ^ *data++);
|
||||
|
@ -244,7 +246,8 @@ static bool frSkyXReadyToSend(void)
|
|||
}
|
||||
|
||||
#if defined(USE_TELEMETRY_SMARTPORT)
|
||||
static void frSkyXTelemetrySendByte(uint8_t c) {
|
||||
static void frSkyXTelemetrySendByte(uint8_t c)
|
||||
{
|
||||
if (c == FSSP_DLE || c == FSSP_START_STOP) {
|
||||
telemetryOutBuffer[telemetryOutWriter] = FSSP_DLE;
|
||||
telemetryOutWriter = (telemetryOutWriter + 1) % TELEMETRY_OUT_BUFFER_SIZE;
|
||||
|
|
|
@ -305,7 +305,8 @@ static void handleCrsfLinkStatisticsTxFrame(const crsfLinkStatisticsTx_t* statsP
|
|||
#endif
|
||||
|
||||
#if defined(USE_CRSF_LINK_STATISTICS)
|
||||
static void crsfCheckRssi(uint32_t currentTimeUs) {
|
||||
static void crsfCheckRssi(uint32_t currentTimeUs)
|
||||
{
|
||||
|
||||
if (cmpTimeUs(currentTimeUs, lastLinkStatisticsFrameUs) > CRSF_LINK_STATUS_UPDATE_TIMEOUT_US) {
|
||||
if (rssiSource == RSSI_SOURCE_RX_PROTOCOL_CRSF) {
|
||||
|
|
|
@ -205,7 +205,8 @@ static volatile bool mspConfirm;
|
|||
STATIC_UNIT_TESTED volatile bool mspReplyPending;
|
||||
STATIC_UNIT_TESTED volatile bool deviceInfoReplyPending;
|
||||
|
||||
void mspReceiverResetState(void) {
|
||||
void mspReceiverResetState(void)
|
||||
{
|
||||
mspCurrentOffset = 0;
|
||||
mspCurrentPackage = 1;
|
||||
mspConfirm = false;
|
||||
|
|
|
@ -150,7 +150,8 @@ static serialPort_t *fportPort;
|
|||
static bool telemetryEnabled = false;
|
||||
#endif
|
||||
|
||||
static void reportFrameError(uint8_t errorReason) {
|
||||
static void reportFrameError(uint8_t errorReason)
|
||||
{
|
||||
static volatile uint16_t frameErrors = 0;
|
||||
|
||||
frameErrors++;
|
||||
|
|
|
@ -146,7 +146,8 @@ static bool isChecksumOkIa6(void)
|
|||
}
|
||||
|
||||
|
||||
static bool checksumIsOk(void) {
|
||||
static bool checksumIsOk(void)
|
||||
{
|
||||
if (ibusModel == IBUS_MODEL_IA6 ) {
|
||||
return isChecksumOkIa6();
|
||||
} else {
|
||||
|
@ -155,7 +156,8 @@ static bool checksumIsOk(void) {
|
|||
}
|
||||
|
||||
|
||||
static void updateChannelData(void) {
|
||||
static void updateChannelData(void)
|
||||
{
|
||||
uint8_t i;
|
||||
uint8_t offset;
|
||||
for (i = 0, offset = ibusChannelOffset; i < IBUS_MAX_SLOTS; i++, offset += 2) {
|
||||
|
|
|
@ -144,7 +144,8 @@ void pgResetFn_rxFailsafeChannelConfigs(rxFailsafeChannelConfig_t *rxFailsafeCha
|
|||
}
|
||||
}
|
||||
|
||||
void resetAllRxChannelRangeConfigurations(rxChannelRangeConfig_t *rxChannelRangeConfig) {
|
||||
void resetAllRxChannelRangeConfigurations(rxChannelRangeConfig_t *rxChannelRangeConfig)
|
||||
{
|
||||
// set default calibration to full range and 1:1 mapping
|
||||
for (int i = 0; i < NON_AUX_CHANNEL_COUNT; i++) {
|
||||
rxChannelRangeConfig->min = PWM_RANGE_MIN;
|
||||
|
|
|
@ -167,7 +167,8 @@ bool srxl2ProcessHandshake(const Srxl2Header* header)
|
|||
return true;
|
||||
}
|
||||
|
||||
void srxl2ProcessChannelData(const Srxl2ChannelDataHeader* channelData, rxRuntimeState_t *rxRuntimeState) {
|
||||
void srxl2ProcessChannelData(const Srxl2ChannelDataHeader* channelData, rxRuntimeState_t *rxRuntimeState)
|
||||
{
|
||||
globalResult = RX_FRAME_COMPLETE;
|
||||
|
||||
if (channelData->rssi >= 0) {
|
||||
|
|
|
@ -332,7 +332,9 @@ typedef enum {
|
|||
BARO_STATE_COUNT
|
||||
} barometerState_e;
|
||||
|
||||
bool isBaroReady(void) {
|
||||
|
||||
bool isBaroReady(void)
|
||||
{
|
||||
return baroReady;
|
||||
}
|
||||
|
||||
|
|
|
@ -548,7 +548,8 @@ bool isAmperageConfigured(void)
|
|||
return batteryConfig()->currentMeterSource != CURRENT_METER_NONE;
|
||||
}
|
||||
|
||||
int32_t getAmperage(void) {
|
||||
int32_t getAmperage(void)
|
||||
{
|
||||
return currentMeter.amperage;
|
||||
}
|
||||
|
||||
|
|
|
@ -593,7 +593,8 @@ uint16_t gyroAbsRateDps(int axis)
|
|||
|
||||
#ifdef USE_DYN_LPF
|
||||
|
||||
float dynThrottle(float throttle) {
|
||||
float dynThrottle(float throttle)
|
||||
{
|
||||
return throttle * (1 - (throttle * throttle) / 3.0f) * 1.5f;
|
||||
}
|
||||
|
||||
|
|
|
@ -274,7 +274,8 @@ void gyroInitFilters(void)
|
|||
}
|
||||
|
||||
#if defined(USE_GYRO_SLEW_LIMITER)
|
||||
void gyroInitSlewLimiter(gyroSensor_t *gyroSensor) {
|
||||
void gyroInitSlewLimiter(gyroSensor_t *gyroSensor)
|
||||
{
|
||||
|
||||
for (int axis = 0; axis < XYZ_AXIS_COUNT; axis++) {
|
||||
gyroSensor->gyroDev.gyroADCRawPrevious[axis] = 0;
|
||||
|
|
|
@ -189,7 +189,8 @@ static int32_t applyMedianFilter(int32_t newReading)
|
|||
return medianFilterReady ? quickMedianFilter5(filterSamples) : newReading;
|
||||
}
|
||||
|
||||
static int16_t computePseudoSnr(int32_t newReading) {
|
||||
static int16_t computePseudoSnr(int32_t newReading)
|
||||
{
|
||||
#define SNR_SAMPLES 5
|
||||
static int16_t snrSamples[SNR_SAMPLES];
|
||||
static uint8_t snrSampleIndex = 0;
|
||||
|
@ -229,7 +230,8 @@ void rangefinderUpdate(void)
|
|||
}
|
||||
}
|
||||
|
||||
bool isSurfaceAltitudeValid() {
|
||||
bool isSurfaceAltitudeValid()
|
||||
{
|
||||
|
||||
/*
|
||||
* Preconditions: raw and calculated altidude > 0
|
||||
|
@ -336,7 +338,8 @@ int32_t rangefinderGetLatestAltitude(void)
|
|||
return rangefinder.calculatedAltitude;
|
||||
}
|
||||
|
||||
int32_t rangefinderGetLatestRawAltitude(void) {
|
||||
int32_t rangefinderGetLatestRawAltitude(void)
|
||||
{
|
||||
return rangefinder.rawAltitude;
|
||||
}
|
||||
|
||||
|
|
|
@ -265,7 +265,8 @@ static const pllConfig_t overclockLevels[] = {
|
|||
{ 480, RCC_PLLP_DIV2, 10 }, // 240 MHz
|
||||
};
|
||||
|
||||
void SystemInitOC(void) {
|
||||
void SystemInitOC(void)
|
||||
{
|
||||
uint32_t currentOverclockLevel = persistentObjectRead(PERSISTENT_OBJECT_OVERCLOCK_LEVEL);
|
||||
|
||||
if (currentOverclockLevel >= ARRAYLEN(overclockLevels)) {
|
||||
|
|
|
@ -72,17 +72,20 @@ static pthread_mutex_t mainLoopLock;
|
|||
|
||||
int timeval_sub(struct timespec *result, struct timespec *x, struct timespec *y);
|
||||
|
||||
int lockMainPID(void) {
|
||||
int lockMainPID(void)
|
||||
{
|
||||
return pthread_mutex_trylock(&mainLoopLock);
|
||||
}
|
||||
|
||||
#define RAD2DEG (180.0 / M_PI)
|
||||
#define ACC_SCALE (256 / 9.80665)
|
||||
#define GYRO_SCALE (16.4)
|
||||
void sendMotorUpdate() {
|
||||
void sendMotorUpdate()
|
||||
{
|
||||
udpSend(&pwmLink, &pwmPkt, sizeof(servo_packet));
|
||||
}
|
||||
void updateState(const fdm_packet* pkt) {
|
||||
void updateState(const fdm_packet* pkt)
|
||||
{
|
||||
static double last_timestamp = 0; // in seconds
|
||||
static uint64_t last_realtime = 0; // in uS
|
||||
static struct timespec last_ts; // last packet
|
||||
|
@ -174,7 +177,8 @@ void updateState(const fdm_packet* pkt) {
|
|||
#endif
|
||||
}
|
||||
|
||||
static void* udpThread(void* data) {
|
||||
static void* udpThread(void* data)
|
||||
{
|
||||
UNUSED(data);
|
||||
int n = 0;
|
||||
|
||||
|
@ -190,7 +194,8 @@ static void* udpThread(void* data) {
|
|||
return NULL;
|
||||
}
|
||||
|
||||
static void* tcpThread(void* data) {
|
||||
static void* tcpThread(void* data)
|
||||
{
|
||||
UNUSED(data);
|
||||
|
||||
dyad_init();
|
||||
|
@ -207,7 +212,8 @@ static void* tcpThread(void* data) {
|
|||
}
|
||||
|
||||
// system
|
||||
void systemInit(void) {
|
||||
void systemInit(void)
|
||||
{
|
||||
int ret;
|
||||
|
||||
clock_gettime(CLOCK_MONOTONIC, &start_time);
|
||||
|
@ -245,14 +251,16 @@ void systemInit(void) {
|
|||
|
||||
}
|
||||
|
||||
void systemReset(void){
|
||||
void systemReset(void)
|
||||
{
|
||||
printf("[system]Reset!\n");
|
||||
workerRunning = false;
|
||||
pthread_join(tcpWorker, NULL);
|
||||
pthread_join(udpWorker, NULL);
|
||||
exit(0);
|
||||
}
|
||||
void systemResetToBootloader(bootloaderRequestType_e requestType) {
|
||||
void systemResetToBootloader(bootloaderRequestType_e requestType)
|
||||
{
|
||||
UNUSED(requestType);
|
||||
|
||||
printf("[system]ResetToBootloader!\n");
|
||||
|
@ -262,14 +270,17 @@ void systemResetToBootloader(bootloaderRequestType_e requestType) {
|
|||
exit(0);
|
||||
}
|
||||
|
||||
void timerInit(void) {
|
||||
void timerInit(void)
|
||||
{
|
||||
printf("[timer]Init...\n");
|
||||
}
|
||||
|
||||
void timerStart(void) {
|
||||
void timerStart(void)
|
||||
{
|
||||
}
|
||||
|
||||
void failureMode(failureMode_e mode) {
|
||||
void failureMode(failureMode_e mode)
|
||||
{
|
||||
printf("[failureMode]!!! %d\n", mode);
|
||||
while (1);
|
||||
}
|
||||
|
@ -282,25 +293,29 @@ void indicateFailure(failureMode_e mode, int repeatCount)
|
|||
|
||||
// Time part
|
||||
// Thanks ArduPilot
|
||||
uint64_t nanos64_real() {
|
||||
uint64_t nanos64_real()
|
||||
{
|
||||
struct timespec ts;
|
||||
clock_gettime(CLOCK_MONOTONIC, &ts);
|
||||
return (ts.tv_sec*1e9 + ts.tv_nsec) - (start_time.tv_sec*1e9 + start_time.tv_nsec);
|
||||
}
|
||||
|
||||
uint64_t micros64_real() {
|
||||
uint64_t micros64_real()
|
||||
{
|
||||
struct timespec ts;
|
||||
clock_gettime(CLOCK_MONOTONIC, &ts);
|
||||
return 1.0e6*((ts.tv_sec + (ts.tv_nsec*1.0e-9)) - (start_time.tv_sec + (start_time.tv_nsec*1.0e-9)));
|
||||
}
|
||||
|
||||
uint64_t millis64_real() {
|
||||
uint64_t millis64_real()
|
||||
{
|
||||
struct timespec ts;
|
||||
clock_gettime(CLOCK_MONOTONIC, &ts);
|
||||
return 1.0e3*((ts.tv_sec + (ts.tv_nsec*1.0e-9)) - (start_time.tv_sec + (start_time.tv_nsec*1.0e-9)));
|
||||
}
|
||||
|
||||
uint64_t micros64() {
|
||||
uint64_t micros64()
|
||||
{
|
||||
static uint64_t last = 0;
|
||||
static uint64_t out = 0;
|
||||
uint64_t now = nanos64_real();
|
||||
|
@ -312,7 +327,8 @@ uint64_t micros64() {
|
|||
// return micros64_real();
|
||||
}
|
||||
|
||||
uint64_t millis64() {
|
||||
uint64_t millis64()
|
||||
{
|
||||
static uint64_t last = 0;
|
||||
static uint64_t out = 0;
|
||||
uint64_t now = nanos64_real();
|
||||
|
@ -324,11 +340,13 @@ uint64_t millis64() {
|
|||
// return millis64_real();
|
||||
}
|
||||
|
||||
uint32_t micros(void) {
|
||||
uint32_t micros(void)
|
||||
{
|
||||
return micros64() & 0xFFFFFFFF;
|
||||
}
|
||||
|
||||
uint32_t millis(void) {
|
||||
uint32_t millis(void)
|
||||
{
|
||||
return millis64() & 0xFFFFFFFF;
|
||||
}
|
||||
|
||||
|
@ -351,22 +369,26 @@ uint32_t getCycleCounter(void)
|
|||
return (uint32_t) (micros64() & 0xFFFFFFFF);
|
||||
}
|
||||
|
||||
void microsleep(uint32_t usec) {
|
||||
void microsleep(uint32_t usec)
|
||||
{
|
||||
struct timespec ts;
|
||||
ts.tv_sec = 0;
|
||||
ts.tv_nsec = usec*1000UL;
|
||||
while (nanosleep(&ts, &ts) == -1 && errno == EINTR) ;
|
||||
}
|
||||
|
||||
void delayMicroseconds(uint32_t us) {
|
||||
void delayMicroseconds(uint32_t us)
|
||||
{
|
||||
microsleep(us / simRate);
|
||||
}
|
||||
|
||||
void delayMicroseconds_real(uint32_t us) {
|
||||
void delayMicroseconds_real(uint32_t us)
|
||||
{
|
||||
microsleep(us);
|
||||
}
|
||||
|
||||
void delay(uint32_t ms) {
|
||||
void delay(uint32_t ms)
|
||||
{
|
||||
uint64_t start = millis64();
|
||||
|
||||
while ((millis64() - start) < ms) {
|
||||
|
@ -378,7 +400,8 @@ void delay(uint32_t ms) {
|
|||
// Return 1 if the difference is negative, otherwise 0.
|
||||
// result = x - y
|
||||
// from: http://www.gnu.org/software/libc/manual/html_node/Elapsed-Time.html
|
||||
int timeval_sub(struct timespec *result, struct timespec *x, struct timespec *y) {
|
||||
int timeval_sub(struct timespec *result, struct timespec *x, struct timespec *y)
|
||||
{
|
||||
unsigned int s_carry = 0;
|
||||
unsigned int ns_carry = 0;
|
||||
// Perform the carry for the later subtraction by updating y.
|
||||
|
@ -406,7 +429,8 @@ static int16_t motorsPwm[MAX_SUPPORTED_MOTORS];
|
|||
static int16_t servosPwm[MAX_SUPPORTED_SERVOS];
|
||||
static int16_t idlePulse;
|
||||
|
||||
void servoDevInit(const servoDevConfig_t *servoConfig) {
|
||||
void servoDevInit(const servoDevConfig_t *servoConfig)
|
||||
{
|
||||
UNUSED(servoConfig);
|
||||
for (uint8_t servoIndex = 0; servoIndex < MAX_SUPPORTED_SERVOS; servoIndex++) {
|
||||
servos[servoIndex].enabled = true;
|
||||
|
@ -415,7 +439,8 @@ void servoDevInit(const servoDevConfig_t *servoConfig) {
|
|||
|
||||
static motorDevice_t motorPwmDevice; // Forward
|
||||
|
||||
pwmOutputPort_t *pwmGetMotors(void) {
|
||||
pwmOutputPort_t *pwmGetMotors(void)
|
||||
{
|
||||
return motors;
|
||||
}
|
||||
|
||||
|
@ -456,7 +481,8 @@ static void pwmShutdownPulsesForAllMotors(void)
|
|||
motorPwmDevice.enabled = false;
|
||||
}
|
||||
|
||||
bool pwmIsMotorEnabled(uint8_t index) {
|
||||
bool pwmIsMotorEnabled(uint8_t index)
|
||||
{
|
||||
return motors[index].enabled;
|
||||
}
|
||||
|
||||
|
@ -481,7 +507,8 @@ static void pwmCompleteMotorUpdate(void)
|
|||
// printf("[pwm]%u:%u,%u,%u,%u\n", idlePulse, motorsPwm[0], motorsPwm[1], motorsPwm[2], motorsPwm[3]);
|
||||
}
|
||||
|
||||
void pwmWriteServo(uint8_t index, float value) {
|
||||
void pwmWriteServo(uint8_t index, float value)
|
||||
{
|
||||
servosPwm[index] = value;
|
||||
}
|
||||
|
||||
|
@ -523,7 +550,8 @@ motorDevice_t *motorPwmDevInit(const motorDevConfig_t *motorConfig, uint16_t _id
|
|||
}
|
||||
|
||||
// ADC part
|
||||
uint16_t adcGetChannel(uint8_t channel) {
|
||||
uint16_t adcGetChannel(uint8_t channel)
|
||||
{
|
||||
UNUSED(channel);
|
||||
return 0;
|
||||
}
|
||||
|
@ -535,7 +563,8 @@ char _Min_Stack_Size;
|
|||
// fake EEPROM
|
||||
static FILE *eepromFd = NULL;
|
||||
|
||||
void FLASH_Unlock(void) {
|
||||
void FLASH_Unlock(void)
|
||||
{
|
||||
if (eepromFd != NULL) {
|
||||
fprintf(stderr, "[FLASH_Unlock] eepromFd != NULL\n");
|
||||
return;
|
||||
|
@ -568,7 +597,8 @@ void FLASH_Unlock(void) {
|
|||
}
|
||||
}
|
||||
|
||||
void FLASH_Lock(void) {
|
||||
void FLASH_Lock(void)
|
||||
{
|
||||
// flush & close
|
||||
if (eepromFd != NULL) {
|
||||
fseek(eepromFd, 0, SEEK_SET);
|
||||
|
@ -581,13 +611,15 @@ void FLASH_Lock(void) {
|
|||
}
|
||||
}
|
||||
|
||||
FLASH_Status FLASH_ErasePage(uintptr_t Page_Address) {
|
||||
FLASH_Status FLASH_ErasePage(uintptr_t Page_Address)
|
||||
{
|
||||
UNUSED(Page_Address);
|
||||
// printf("[FLASH_ErasePage]%x\n", Page_Address);
|
||||
return FLASH_COMPLETE;
|
||||
}
|
||||
|
||||
FLASH_Status FLASH_ProgramWord(uintptr_t addr, uint32_t value) {
|
||||
FLASH_Status FLASH_ProgramWord(uintptr_t addr, uint32_t value)
|
||||
{
|
||||
if ((addr >= (uintptr_t)eepromData) && (addr < (uintptr_t)ARRAYEND(eepromData))) {
|
||||
*((uint32_t*)addr) = value;
|
||||
printf("[FLASH_ProgramWord]%p = %08x\n", (void*)addr, *((uint32_t*)addr));
|
||||
|
|
|
@ -13,7 +13,8 @@
|
|||
|
||||
#include "udplink.h"
|
||||
|
||||
int udpInit(udpLink_t* link, const char* addr, int port, bool isServer) {
|
||||
int udpInit(udpLink_t* link, const char* addr, int port, bool isServer)
|
||||
{
|
||||
int one = 1;
|
||||
|
||||
if ((link->fd = socket(AF_INET, SOCK_DGRAM, IPPROTO_UDP)) == -1) {
|
||||
|
@ -43,11 +44,13 @@ int udpInit(udpLink_t* link, const char* addr, int port, bool isServer) {
|
|||
return 0;
|
||||
}
|
||||
|
||||
int udpSend(udpLink_t* link, const void* data, size_t size) {
|
||||
int udpSend(udpLink_t* link, const void* data, size_t size)
|
||||
{
|
||||
return sendto(link->fd, data, size, 0, (struct sockaddr *)&link->si, sizeof(link->si));
|
||||
}
|
||||
|
||||
int udpRecv(udpLink_t* link, void* data, size_t size, uint32_t timeout_ms) {
|
||||
int udpRecv(udpLink_t* link, void* data, size_t size, uint32_t timeout_ms)
|
||||
{
|
||||
fd_set fds;
|
||||
struct timeval tv;
|
||||
|
||||
|
|
|
@ -72,5 +72,6 @@ void detectHardwareRevision(void)
|
|||
}
|
||||
}
|
||||
|
||||
void updateHardwareRevision(void) {
|
||||
void updateHardwareRevision(void)
|
||||
{
|
||||
}
|
||||
|
|
|
@ -453,7 +453,8 @@ static inline void hottSendEAMResponse(void)
|
|||
hottSendResponse((uint8_t *)&hottEAMMessage, sizeof(hottEAMMessage));
|
||||
}
|
||||
|
||||
static void hottPrepareMessages(void) {
|
||||
static void hottPrepareMessages(void)
|
||||
{
|
||||
hottPrepareEAMResponse(&hottEAMMessage);
|
||||
#ifdef USE_GPS
|
||||
hottPrepareGPSResponse(&hottGPSMessage);
|
||||
|
@ -630,7 +631,8 @@ static void hottCheckSerialData(uint32_t currentMicros)
|
|||
#endif
|
||||
}
|
||||
|
||||
static void hottSendTelemetryData(void) {
|
||||
static void hottSendTelemetryData(void)
|
||||
{
|
||||
|
||||
if (!hottIsSending) {
|
||||
hottConfigurePortForTX();
|
||||
|
|
|
@ -139,7 +139,8 @@ static uint8_t getSensorID(ibusAddress_t address)
|
|||
}
|
||||
|
||||
#if defined(USE_TELEMETRY_IBUS_EXTENDED)
|
||||
static const uint8_t* getSensorStruct(uint8_t sensorType, uint8_t* itemCount){
|
||||
static const uint8_t* getSensorStruct(uint8_t sensorType, uint8_t* itemCount)
|
||||
{
|
||||
const uint8_t* structure = 0;
|
||||
if (sensorType == IBUS_SENSOR_TYPE_GPS_FULL) {
|
||||
structure = FULL_GPS_IDS;
|
||||
|
|
|
@ -507,7 +507,8 @@ void checkSmartPortTelemetryState(void)
|
|||
}
|
||||
|
||||
#if defined(USE_MSP_OVER_TELEMETRY)
|
||||
static void smartPortSendMspResponse(uint8_t *data, const uint8_t dataSize) {
|
||||
static void smartPortSendMspResponse(uint8_t *data, const uint8_t dataSize)
|
||||
{
|
||||
smartPortPayload_t payload;
|
||||
payload.frameId = FSSP_MSPS_FRAME;
|
||||
memcpy(&payload.valueId, data, MIN(dataSize,SMARTPORT_MSP_PAYLOAD_SIZE));
|
||||
|
|
|
@ -30,11 +30,13 @@
|
|||
#include "../drivers/nvic.h"
|
||||
#include "../drivers/io.h"
|
||||
|
||||
void USB_OTG_BSP_ConfigVBUS(USB_OTG_CORE_HANDLE *pdev) {
|
||||
void USB_OTG_BSP_ConfigVBUS(USB_OTG_CORE_HANDLE *pdev)
|
||||
{
|
||||
(void)pdev;
|
||||
}
|
||||
|
||||
void USB_OTG_BSP_DriveVBUS(USB_OTG_CORE_HANDLE *pdev,uint8_t state) {
|
||||
void USB_OTG_BSP_DriveVBUS(USB_OTG_CORE_HANDLE *pdev,uint8_t state)
|
||||
{
|
||||
(void)pdev;
|
||||
(void)state;
|
||||
}
|
||||
|
|
|
@ -154,26 +154,33 @@ bool busWriteRegister(const extDevice_t*, uint8_t, uint8_t) {return true;}
|
|||
bool busWriteRegisterStart(const extDevice_t*, uint8_t, uint8_t) {return true;}
|
||||
void busDeviceRegister(const extDevice_t*) {}
|
||||
|
||||
uint16_t spiCalculateDivider() {
|
||||
uint16_t spiCalculateDivider()
|
||||
{
|
||||
return 2;
|
||||
}
|
||||
|
||||
void spiSetClkDivisor() {
|
||||
void spiSetClkDivisor()
|
||||
{
|
||||
}
|
||||
|
||||
void spiPreinitByIO() {
|
||||
void spiPreinitByIO()
|
||||
{
|
||||
}
|
||||
|
||||
void IOConfigGPIO() {
|
||||
void IOConfigGPIO()
|
||||
{
|
||||
}
|
||||
|
||||
void IOHi() {
|
||||
void IOHi()
|
||||
{
|
||||
}
|
||||
|
||||
void IOInit() {
|
||||
void IOInit()
|
||||
{
|
||||
}
|
||||
|
||||
void IORelease() {
|
||||
void IORelease()
|
||||
{
|
||||
}
|
||||
|
||||
|
||||
|
|
|
@ -151,39 +151,49 @@ bool busWriteRegister(const extDevice_t*, uint8_t, uint8_t) {return true;}
|
|||
bool busWriteRegisterStart(const extDevice_t*, uint8_t, uint8_t) {return true;}
|
||||
void busDeviceRegister(const extDevice_t*) {}
|
||||
|
||||
uint16_t spiCalculateDivider() {
|
||||
uint16_t spiCalculateDivider()
|
||||
{
|
||||
return 2;
|
||||
}
|
||||
|
||||
void spiSetClkDivisor() {
|
||||
void spiSetClkDivisor()
|
||||
{
|
||||
}
|
||||
|
||||
void spiPreinitByIO(IO_t) {
|
||||
void spiPreinitByIO(IO_t)
|
||||
{
|
||||
}
|
||||
|
||||
void IOConfigGPIO() {
|
||||
void IOConfigGPIO()
|
||||
{
|
||||
}
|
||||
|
||||
void IOHi() {
|
||||
void IOHi()
|
||||
{
|
||||
}
|
||||
|
||||
IO_t IOGetByTag(ioTag_t) {
|
||||
IO_t IOGetByTag(ioTag_t)
|
||||
{
|
||||
return IO_NONE;
|
||||
}
|
||||
|
||||
void IOInit() {
|
||||
void IOInit()
|
||||
{
|
||||
}
|
||||
|
||||
void EXTIHandlerInit(extiCallbackRec_t *, extiHandlerCallback *) {
|
||||
void EXTIHandlerInit(extiCallbackRec_t *, extiHandlerCallback *)
|
||||
{
|
||||
}
|
||||
|
||||
void EXTIConfig(IO_t, extiCallbackRec_t *, int, ioConfig_t, extiTrigger_t) {
|
||||
void EXTIConfig(IO_t, extiCallbackRec_t *, int, ioConfig_t, extiTrigger_t)
|
||||
{
|
||||
}
|
||||
|
||||
void EXTIEnable(IO_t) {
|
||||
}
|
||||
void EXTIDisable(IO_t) {
|
||||
}
|
||||
void EXTIEnable(IO_t)
|
||||
{}
|
||||
|
||||
void EXTIDisable(IO_t)
|
||||
{}
|
||||
|
||||
|
||||
} // extern "C"
|
||||
|
|
|
@ -153,26 +153,33 @@ bool busRawWriteRegister(const extDevice_t*, uint8_t, uint8_t) {return true;}
|
|||
bool busRawWriteRegisterStart(const extDevice_t*, uint8_t, uint8_t) {return true;}
|
||||
void busDeviceRegister(const extDevice_t*) {}
|
||||
|
||||
uint16_t spiCalculateDivider() {
|
||||
uint16_t spiCalculateDivider()
|
||||
{
|
||||
return 2;
|
||||
}
|
||||
|
||||
void spiSetClkDivisor() {
|
||||
void spiSetClkDivisor()
|
||||
{
|
||||
}
|
||||
|
||||
void spiPreinitByIO() {
|
||||
void spiPreinitByIO()
|
||||
{
|
||||
}
|
||||
|
||||
void IOConfigGPIO() {
|
||||
void IOConfigGPIO()
|
||||
{
|
||||
}
|
||||
|
||||
void IOHi() {
|
||||
void IOHi()
|
||||
{
|
||||
}
|
||||
|
||||
void IOInit() {
|
||||
void IOInit()
|
||||
{
|
||||
}
|
||||
|
||||
void IORelease() {
|
||||
void IORelease()
|
||||
{
|
||||
}
|
||||
|
||||
}
|
||||
|
|
|
@ -208,27 +208,33 @@ int32_t taskGuardCycles;
|
|||
|
||||
uint32_t micros(void) {return 0;}
|
||||
|
||||
int32_t getAmperage(void) {
|
||||
int32_t getAmperage(void)
|
||||
{
|
||||
return 100;
|
||||
}
|
||||
|
||||
uint16_t getBatteryVoltage(void) {
|
||||
uint16_t getBatteryVoltage(void)
|
||||
{
|
||||
return 42;
|
||||
}
|
||||
|
||||
batteryState_e getBatteryState(void) {
|
||||
batteryState_e getBatteryState(void)
|
||||
{
|
||||
return BATTERY_OK;
|
||||
}
|
||||
|
||||
uint8_t calculateBatteryPercentageRemaining(void) {
|
||||
uint8_t calculateBatteryPercentageRemaining(void)
|
||||
{
|
||||
return 67;
|
||||
}
|
||||
|
||||
uint8_t getMotorCount() {
|
||||
uint8_t getMotorCount()
|
||||
{
|
||||
return 4;
|
||||
}
|
||||
|
||||
size_t getEEPROMStorageSize() {
|
||||
size_t getEEPROMStorageSize()
|
||||
{
|
||||
return 0;
|
||||
}
|
||||
|
||||
|
@ -241,7 +247,8 @@ const box_t *findBoxByBoxId(boxId_e) { return &boxes[0]; }
|
|||
|
||||
int8_t unitTestDataArray[3];
|
||||
|
||||
void pgResetFn_unitTestData(int8_t *) {}
|
||||
void pgResetFn_unitTestData(int8_t *)
|
||||
{}
|
||||
|
||||
uint32_t getBeeperOffMask(void) { return 0; }
|
||||
uint32_t getPreferredBeeperOffMask(void) { return 0; }
|
||||
|
|
|
@ -63,7 +63,8 @@ static int callCounts[CALL_COUNT_ITEM_COUNT];
|
|||
|
||||
#define CALL_COUNTER(item) (callCounts[item])
|
||||
|
||||
void resetCallCounters(void) {
|
||||
void resetCallCounters(void)
|
||||
{
|
||||
memset(&callCounts, 0, sizeof(callCounts));
|
||||
}
|
||||
|
||||
|
@ -739,15 +740,18 @@ throttleStatus_e calculateThrottleStatus()
|
|||
|
||||
void delay(uint32_t) {}
|
||||
|
||||
bool featureIsEnabled(uint32_t mask) {
|
||||
bool featureIsEnabled(uint32_t mask)
|
||||
{
|
||||
return (mask & testFeatureMask);
|
||||
}
|
||||
|
||||
void disarm(flightLogDisarmReason_e) {
|
||||
void disarm(flightLogDisarmReason_e)
|
||||
{
|
||||
callCounts[COUNTER_MW_DISARM]++;
|
||||
}
|
||||
|
||||
void beeper(beeperMode_e mode) {
|
||||
void beeper(beeperMode_e mode)
|
||||
{
|
||||
UNUSED(mode);
|
||||
}
|
||||
|
||||
|
@ -761,7 +765,8 @@ bool isUsingSticksForArming(void)
|
|||
return isUsingSticksToArm;
|
||||
}
|
||||
|
||||
bool areSticksActive(uint8_t stickPercentLimit) {
|
||||
bool areSticksActive(uint8_t stickPercentLimit)
|
||||
{
|
||||
UNUSED(stickPercentLimit);
|
||||
return false;
|
||||
}
|
||||
|
|
|
@ -303,42 +303,50 @@ float rcData[MAX_SUPPORTED_RC_CHANNEL_COUNT];
|
|||
boxBitmask_t rcModeActivationMask;
|
||||
gpsSolutionData_t gpsSol;
|
||||
|
||||
batteryState_e getBatteryState(void) {
|
||||
batteryState_e getBatteryState(void)
|
||||
{
|
||||
return BATTERY_OK;
|
||||
}
|
||||
|
||||
void ws2811LedStripInit(ioTag_t ioTag) {
|
||||
void ws2811LedStripInit(ioTag_t ioTag)
|
||||
{
|
||||
UNUSED(ioTag);
|
||||
}
|
||||
|
||||
void ws2811UpdateStrip(ledStripFormatRGB_e, uint8_t) {}
|
||||
|
||||
void setLedValue(uint16_t index, const uint8_t value) {
|
||||
void setLedValue(uint16_t index, const uint8_t value)
|
||||
{
|
||||
UNUSED(index);
|
||||
UNUSED(value);
|
||||
}
|
||||
|
||||
void setLedHsv(uint16_t index, const hsvColor_t *color) {
|
||||
void setLedHsv(uint16_t index, const hsvColor_t *color)
|
||||
{
|
||||
UNUSED(index);
|
||||
UNUSED(color);
|
||||
}
|
||||
|
||||
void getLedHsv(uint16_t index, hsvColor_t *color) {
|
||||
void getLedHsv(uint16_t index, hsvColor_t *color)
|
||||
{
|
||||
UNUSED(index);
|
||||
UNUSED(color);
|
||||
}
|
||||
|
||||
|
||||
void scaleLedValue(uint16_t index, const uint8_t scalePercent) {
|
||||
void scaleLedValue(uint16_t index, const uint8_t scalePercent)
|
||||
{
|
||||
UNUSED(index);
|
||||
UNUSED(scalePercent);
|
||||
}
|
||||
|
||||
void setStripColor(const hsvColor_t *color) {
|
||||
void setStripColor(const hsvColor_t *color)
|
||||
{
|
||||
UNUSED(color);
|
||||
}
|
||||
|
||||
void setStripColors(const hsvColor_t *colors) {
|
||||
void setStripColors(const hsvColor_t *colors)
|
||||
{
|
||||
UNUSED(colors);
|
||||
}
|
||||
|
||||
|
@ -355,14 +363,16 @@ uint32_t micros(void) { return 0; }
|
|||
uint32_t millis(void) { return 0; }
|
||||
|
||||
bool shouldSoundBatteryAlarm(void) { return false; }
|
||||
bool featureIsEnabled(uint32_t mask) {
|
||||
bool featureIsEnabled(uint32_t mask)
|
||||
{
|
||||
UNUSED(mask);
|
||||
return false;
|
||||
}
|
||||
|
||||
void tfp_sprintf(char *, char*, ...) { }
|
||||
|
||||
int scaleRange(int x, int srcMin, int srcMax, int destMin, int destMax) {
|
||||
int scaleRange(int x, int srcMin, int srcMax, int destMin, int destMax)
|
||||
{
|
||||
UNUSED(x);
|
||||
UNUSED(srcMin);
|
||||
UNUSED(srcMax);
|
||||
|
|
|
@ -163,7 +163,8 @@ void doTestArm(bool testEmpty = true)
|
|||
/*
|
||||
* Auxiliary function. Test is there're stats that must be shown
|
||||
*/
|
||||
bool isSomeStatEnabled(void) {
|
||||
bool isSomeStatEnabled(void)
|
||||
{
|
||||
return (osdConfigMutable()->enabled_stats != 0);
|
||||
}
|
||||
|
||||
|
|
|
@ -190,7 +190,8 @@ void doTestArm(bool testEmpty = true)
|
|||
/*
|
||||
* Auxiliary function. Test is there're stats that must be shown
|
||||
*/
|
||||
bool isSomeStatEnabled(void) {
|
||||
bool isSomeStatEnabled(void)
|
||||
{
|
||||
return (osdConfigMutable()->enabled_stats != 0);
|
||||
}
|
||||
|
||||
|
|
|
@ -118,7 +118,8 @@ pidProfile_t *pidProfile;
|
|||
int loopIter = 0;
|
||||
|
||||
// Always use same defaults for testing in future releases even when defaults change
|
||||
void setDefaultTestSettings(void) {
|
||||
void setDefaultTestSettings(void)
|
||||
{
|
||||
pgResetAll();
|
||||
pidProfile = pidProfilesMutable(1);
|
||||
pidProfile->pid[PID_ROLL] = { 40, 40, 30, 65 };
|
||||
|
@ -170,11 +171,13 @@ void setDefaultTestSettings(void) {
|
|||
gyro.targetLooptime = 8000;
|
||||
}
|
||||
|
||||
timeUs_t currentTestTime(void) {
|
||||
timeUs_t currentTestTime(void)
|
||||
{
|
||||
return targetPidLooptime * loopIter++;
|
||||
}
|
||||
|
||||
void resetTest(void) {
|
||||
void resetTest(void)
|
||||
{
|
||||
loopIter = 0;
|
||||
pidRuntime.tpaFactor = 1.0f;
|
||||
simulatedMotorMixRange = 0.0f;
|
||||
|
@ -212,14 +215,16 @@ void resetTest(void) {
|
|||
}
|
||||
}
|
||||
|
||||
void setStickPosition(int axis, float stickRatio) {
|
||||
void setStickPosition(int axis, float stickRatio)
|
||||
{
|
||||
simulatedPrevSetpointRate[axis] = simulatedSetpointRate[axis];
|
||||
simulatedSetpointRate[axis] = 1998.0f * stickRatio;
|
||||
simulatedRcDeflection[axis] = stickRatio;
|
||||
}
|
||||
|
||||
// All calculations will have 10% tolerance
|
||||
float calculateTolerance(float input) {
|
||||
float calculateTolerance(float input)
|
||||
{
|
||||
return fabsf(input * 0.1f);
|
||||
}
|
||||
|
||||
|
@ -235,7 +240,8 @@ TEST(pidControllerTest, testInitialisation)
|
|||
}
|
||||
}
|
||||
|
||||
TEST(pidControllerTest, testStabilisationDisabled) {
|
||||
TEST(pidControllerTest, testStabilisationDisabled)
|
||||
{
|
||||
ENABLE_ARMING_FLAG(ARMED);
|
||||
// Run few loops to make sure there is no error building up when stabilisation disabled
|
||||
|
||||
|
@ -255,7 +261,8 @@ TEST(pidControllerTest, testStabilisationDisabled) {
|
|||
}
|
||||
}
|
||||
|
||||
TEST(pidControllerTest, testPidLoop) {
|
||||
TEST(pidControllerTest, testPidLoop)
|
||||
{
|
||||
// Make sure to start with fresh values
|
||||
resetTest();
|
||||
ENABLE_ARMING_FLAG(ARMED);
|
||||
|
@ -362,7 +369,8 @@ TEST(pidControllerTest, testPidLoop) {
|
|||
EXPECT_FLOAT_EQ(0, pidData[FD_YAW].D);
|
||||
}
|
||||
|
||||
TEST(pidControllerTest, testPidLevel) {
|
||||
TEST(pidControllerTest, testPidLevel)
|
||||
{
|
||||
// Make sure to start with fresh values
|
||||
resetTest();
|
||||
ENABLE_ARMING_FLAG(ARMED);
|
||||
|
@ -422,7 +430,8 @@ TEST(pidControllerTest, testPidLevel) {
|
|||
}
|
||||
|
||||
|
||||
TEST(pidControllerTest, testPidHorizon) {
|
||||
TEST(pidControllerTest, testPidHorizon)
|
||||
{
|
||||
resetTest();
|
||||
ENABLE_ARMING_FLAG(ARMED);
|
||||
pidStabilisationState(PID_STABILISATION_ON);
|
||||
|
@ -445,7 +454,8 @@ TEST(pidControllerTest, testPidHorizon) {
|
|||
EXPECT_NEAR(0.811f, calcHorizonLevelStrength(), calculateTolerance(0.82));
|
||||
}
|
||||
|
||||
TEST(pidControllerTest, testMixerSaturation) {
|
||||
TEST(pidControllerTest, testMixerSaturation)
|
||||
{
|
||||
resetTest();
|
||||
ENABLE_ARMING_FLAG(ARMED);
|
||||
pidStabilisationState(PID_STABILISATION_ON);
|
||||
|
@ -491,7 +501,8 @@ TEST(pidControllerTest, testMixerSaturation) {
|
|||
}
|
||||
|
||||
// TODO - Add more scenarios
|
||||
TEST(pidControllerTest, testCrashRecoveryMode) {
|
||||
TEST(pidControllerTest, testCrashRecoveryMode)
|
||||
{
|
||||
resetTest();
|
||||
pidProfile->crash_recovery = PID_CRASH_RECOVERY_ON;
|
||||
pidInit(pidProfile);
|
||||
|
@ -516,7 +527,8 @@ TEST(pidControllerTest, testCrashRecoveryMode) {
|
|||
// Add additional verifications
|
||||
}
|
||||
|
||||
TEST(pidControllerTest, testFeedForward) {
|
||||
TEST(pidControllerTest, testFeedForward)
|
||||
{
|
||||
resetTest();
|
||||
ENABLE_ARMING_FLAG(ARMED);
|
||||
pidStabilisationState(PID_STABILISATION_ON);
|
||||
|
@ -561,7 +573,8 @@ TEST(pidControllerTest, testFeedForward) {
|
|||
EXPECT_FLOAT_EQ(0, pidData[FD_YAW].F);
|
||||
}
|
||||
|
||||
TEST(pidControllerTest, testItermRelax) {
|
||||
TEST(pidControllerTest, testItermRelax)
|
||||
{
|
||||
resetTest();
|
||||
pidProfile->iterm_relax = ITERM_RELAX_RP;
|
||||
ENABLE_ARMING_FLAG(ARMED);
|
||||
|
@ -635,7 +648,8 @@ TEST(pidControllerTest, testItermRelax) {
|
|||
}
|
||||
|
||||
// TODO - Add more tests
|
||||
TEST(pidControllerTest, testAbsoluteControl) {
|
||||
TEST(pidControllerTest, testAbsoluteControl)
|
||||
{
|
||||
resetTest();
|
||||
pidProfile->abs_control_gain = 10;
|
||||
pidInit(pidProfile);
|
||||
|
@ -663,11 +677,13 @@ TEST(pidControllerTest, testAbsoluteControl) {
|
|||
EXPECT_NEAR(-79.2, currentPidSetpoint, calculateTolerance(-79.2));
|
||||
}
|
||||
|
||||
TEST(pidControllerTest, testDtermFiltering) {
|
||||
TEST(pidControllerTest, testDtermFiltering)
|
||||
{
|
||||
// TODO
|
||||
}
|
||||
|
||||
TEST(pidControllerTest, testItermRotationHandling) {
|
||||
TEST(pidControllerTest, testItermRotationHandling)
|
||||
{
|
||||
resetTest();
|
||||
pidInit(pidProfile);
|
||||
|
||||
|
@ -709,7 +725,8 @@ TEST(pidControllerTest, testItermRotationHandling) {
|
|||
EXPECT_NEAR(1139.6, pidData[FD_YAW].I, calculateTolerance(1139.6));
|
||||
}
|
||||
|
||||
TEST(pidControllerTest, testLaunchControl) {
|
||||
TEST(pidControllerTest, testLaunchControl)
|
||||
{
|
||||
// The launchControlGain is indirectly tested since when launch control is active the
|
||||
// the gain overrides the PID settings. If the logic to use launchControlGain wasn't
|
||||
// working then any I calculations would be incorrect.
|
||||
|
|
|
@ -60,7 +60,8 @@ extern "C" {
|
|||
#include "unittest_macros.h"
|
||||
#include "gtest/gtest.h"
|
||||
|
||||
void unsetArmingDisabled(armingDisableFlags_e flag) {
|
||||
void unsetArmingDisabled(armingDisableFlags_e flag)
|
||||
{
|
||||
UNUSED(flag);
|
||||
}
|
||||
|
||||
|
@ -202,37 +203,44 @@ static int callCounts[CALL_COUNT_ITEM_COUNT];
|
|||
#define CALL_COUNTER(item) (callCounts[item])
|
||||
|
||||
extern "C" {
|
||||
void beeperConfirmationBeeps(uint8_t) {
|
||||
void beeperConfirmationBeeps(uint8_t)
|
||||
{
|
||||
callCounts[COUNTER_QUEUE_CONFIRMATION_BEEP]++;
|
||||
}
|
||||
|
||||
void beeper(beeperMode_e mode) {
|
||||
void beeper(beeperMode_e mode)
|
||||
{
|
||||
UNUSED(mode);
|
||||
}
|
||||
|
||||
void changeControlRateProfile(uint8_t) {
|
||||
void changeControlRateProfile(uint8_t)
|
||||
{
|
||||
callCounts[COUNTER_CHANGE_CONTROL_RATE_PROFILE]++;
|
||||
}
|
||||
|
||||
}
|
||||
|
||||
void resetCallCounters(void) {
|
||||
void resetCallCounters(void)
|
||||
{
|
||||
memset(&callCounts, 0, sizeof(callCounts));
|
||||
}
|
||||
|
||||
uint32_t fixedMillis;
|
||||
|
||||
extern "C" {
|
||||
uint32_t millis(void) {
|
||||
uint32_t millis(void)
|
||||
{
|
||||
return fixedMillis;
|
||||
}
|
||||
|
||||
uint32_t micros(void) {
|
||||
uint32_t micros(void)
|
||||
{
|
||||
return fixedMillis * 1000;
|
||||
}
|
||||
}
|
||||
|
||||
void resetMillis(void) {
|
||||
void resetMillis(void)
|
||||
{
|
||||
fixedMillis = 0;
|
||||
}
|
||||
|
||||
|
@ -628,7 +636,8 @@ bool failsafeIsActive() { return false; }
|
|||
bool rxIsReceivingSignal() { return true; }
|
||||
bool failsafeIsReceivingRxData() { return true; }
|
||||
|
||||
uint8_t getCurrentControlRateProfileIndex(void) {
|
||||
uint8_t getCurrentControlRateProfileIndex(void)
|
||||
{
|
||||
return 0;
|
||||
}
|
||||
void GPS_reset_home_position(void) {}
|
||||
|
@ -648,7 +657,8 @@ PG_REGISTER(blackboxConfig_t, blackboxConfig, PG_BLACKBOX_CONFIG, 0);
|
|||
PG_REGISTER(systemConfig_t, systemConfig, PG_SYSTEM_CONFIG, 2);
|
||||
void resetArmingDisabled(void) {}
|
||||
timeDelta_t getTaskDeltaTimeUs(taskId_e) { return 20000; }
|
||||
armingDisableFlags_e getArmingDisableFlags(void) {
|
||||
armingDisableFlags_e getArmingDisableFlags(void)
|
||||
{
|
||||
return (armingDisableFlags_e) 0;
|
||||
}
|
||||
bool isTryingToArm(void) { return false; }
|
||||
|
|
|
@ -175,7 +175,8 @@ static bool stubTelemetryCalled = false;
|
|||
static uint8_t stubTelemetryPacket[100];
|
||||
static uint8_t stubTelemetryIgnoreRxChars = 0;
|
||||
|
||||
uint8_t respondToIbusRequest(uint8_t const * const ibusPacket) {
|
||||
uint8_t respondToIbusRequest(uint8_t const * const ibusPacket)
|
||||
{
|
||||
uint8_t len = ibusPacket[0];
|
||||
EXPECT_LT(len, sizeof(stubTelemetryPacket));
|
||||
memcpy(stubTelemetryPacket, ibusPacket, len);
|
||||
|
|
|
@ -199,11 +199,13 @@ bool rxMspInit(rxConfig_t *rxConfig, rxRuntimeState_t *rxRuntimeState, rcReadRaw
|
|||
return true;
|
||||
}
|
||||
|
||||
bool featureIsEnabled(uint32_t) {
|
||||
bool featureIsEnabled(uint32_t)
|
||||
{
|
||||
return false;
|
||||
}
|
||||
|
||||
void featureDisableImmediate(uint32_t) {
|
||||
void featureDisableImmediate(uint32_t)
|
||||
{
|
||||
}
|
||||
|
||||
bool rxMspFrameComplete(void)
|
||||
|
|
|
@ -224,13 +224,15 @@ TEST(CrossFireMSPTest, WriteResponseTest)
|
|||
|
||||
}
|
||||
|
||||
void testSendMspResponse(uint8_t *payload, const uint8_t ) {
|
||||
void testSendMspResponse(uint8_t *payload, const uint8_t )
|
||||
{
|
||||
sbuf_t *plOut = sbufInit(&payloadOutputBuf, payloadOutput, payloadOutput + 64);
|
||||
sbufWriteData(plOut, payload, *payload + 64);
|
||||
sbufSwitchToReader(&payloadOutputBuf, payloadOutput);
|
||||
}
|
||||
|
||||
TEST(CrossFireMSPTest, SendMspReply) {
|
||||
TEST(CrossFireMSPTest, SendMspReply)
|
||||
{
|
||||
initSharedMsp();
|
||||
const crsfMspFrame_t *framePtr = (const crsfMspFrame_t*)crsfPidRequest;
|
||||
crsfFrame = *(const crsfFrame_t*)framePtr;
|
||||
|
|
|
@ -342,35 +342,43 @@ portSharing_e determinePortSharing(const serialPortConfig_t *, serialPortFunctio
|
|||
|
||||
bool airmodeIsEnabled(void) {return airMode;}
|
||||
|
||||
int32_t getAmperage(void) {
|
||||
int32_t getAmperage(void)
|
||||
{
|
||||
return testAmperage;
|
||||
}
|
||||
|
||||
uint16_t getBatteryVoltage(void) {
|
||||
uint16_t getBatteryVoltage(void)
|
||||
{
|
||||
return testBatteryVoltage;
|
||||
}
|
||||
|
||||
uint16_t getLegacyBatteryVoltage(void) {
|
||||
uint16_t getLegacyBatteryVoltage(void)
|
||||
{
|
||||
return (testBatteryVoltage + 5) / 10;
|
||||
}
|
||||
|
||||
uint16_t getBatteryAverageCellVoltage(void) {
|
||||
uint16_t getBatteryAverageCellVoltage(void)
|
||||
{
|
||||
return 0;
|
||||
}
|
||||
|
||||
batteryState_e getBatteryState(void) {
|
||||
batteryState_e getBatteryState(void)
|
||||
{
|
||||
return BATTERY_OK;
|
||||
}
|
||||
|
||||
uint8_t calculateBatteryPercentageRemaining(void) {
|
||||
uint8_t calculateBatteryPercentageRemaining(void)
|
||||
{
|
||||
return 67;
|
||||
}
|
||||
|
||||
int32_t getEstimatedAltitudeCm(void) {
|
||||
int32_t getEstimatedAltitudeCm(void)
|
||||
{
|
||||
return gpsSol.llh.altCm; // function returns cm not m.
|
||||
}
|
||||
|
||||
int32_t getMAhDrawn(void){
|
||||
int32_t getMAhDrawn(void)
|
||||
{
|
||||
return testmAhDrawn;
|
||||
}
|
||||
|
||||
|
|
|
@ -184,7 +184,8 @@ baro_t baro;
|
|||
int32_t getEstimatedAltitudeCm() { return 0; }
|
||||
int16_t getEstimatedVario() { return 0; }
|
||||
|
||||
uint32_t millis(void) {
|
||||
uint32_t millis(void)
|
||||
{
|
||||
return fixedMillis;
|
||||
}
|
||||
|
||||
|
@ -256,7 +257,8 @@ bool telemetryDetermineEnabledState(portSharing_e)
|
|||
return true;
|
||||
}
|
||||
|
||||
bool telemetryIsSensorEnabled(sensor_e sensor) {
|
||||
bool telemetryIsSensorEnabled(sensor_e sensor)
|
||||
{
|
||||
UNUSED(sensor);
|
||||
return true;
|
||||
}
|
||||
|
@ -291,11 +293,13 @@ uint16_t getLegacyBatteryVoltage(void)
|
|||
return (testBatteryVoltage + 5) / 10;
|
||||
}
|
||||
|
||||
int32_t getAmperage(void) {
|
||||
int32_t getAmperage(void)
|
||||
{
|
||||
return testAmperage;
|
||||
}
|
||||
|
||||
int32_t getMAhDrawn(void) {
|
||||
int32_t getMAhDrawn(void)
|
||||
{
|
||||
return testMAhDrawn;
|
||||
}
|
||||
|
||||
|
|
|
@ -61,7 +61,8 @@ extern "C" {
|
|||
}
|
||||
|
||||
static int16_t gyroTemperature;
|
||||
int16_t gyroGetTemperature(void) {
|
||||
int16_t gyroGetTemperature(void)
|
||||
{
|
||||
return gyroTemperature;
|
||||
}
|
||||
|
||||
|
@ -135,7 +136,8 @@ uint16_t getBatteryVoltage(void)
|
|||
return testBatteryVoltage;
|
||||
}
|
||||
|
||||
uint8_t getBatteryCellCount(void) {
|
||||
uint8_t getBatteryCellCount(void)
|
||||
{
|
||||
return testBatteryCellCount;
|
||||
}
|
||||
|
||||
|
@ -185,7 +187,8 @@ bool telemetryDetermineEnabledState(portSharing_e portSharing)
|
|||
}
|
||||
|
||||
|
||||
bool telemetryIsSensorEnabled(sensor_e sensor) {
|
||||
bool telemetryIsSensorEnabled(sensor_e sensor)
|
||||
{
|
||||
UNUSED(sensor);
|
||||
return true;
|
||||
}
|
||||
|
|
|
@ -32,7 +32,8 @@ extern "C" {
|
|||
extern const timerHardware_t timerHardware[USABLE_TIMER_CHANNEL_COUNT];
|
||||
}
|
||||
|
||||
TEST(TimerDefinitionTest, Test_counterMismatch) {
|
||||
TEST(TimerDefinitionTest, Test_counterMismatch)
|
||||
{
|
||||
for (const timerHardware_t &t : timerHardware)
|
||||
EXPECT_EQ(&t - timerHardware, t.def_tim_counter)
|
||||
<< "Counter mismatch in timerHardware (in target.c) at position "
|
||||
|
@ -43,7 +44,8 @@ TEST(TimerDefinitionTest, Test_counterMismatch) {
|
|||
<< " array element appears to be " << &t - timerHardware - 1 << '.';
|
||||
}
|
||||
|
||||
TEST(TimerDefinitionTest, Test_duplicatePin) {
|
||||
TEST(TimerDefinitionTest, Test_duplicatePin)
|
||||
{
|
||||
std::set<TestPinEnum> usedPins;
|
||||
for (const timerHardware_t &t : timerHardware)
|
||||
EXPECT_TRUE(usedPins.emplace(t.pin).second)
|
||||
|
@ -56,7 +58,8 @@ TEST(TimerDefinitionTest, Test_duplicatePin) {
|
|||
|
||||
#if !defined(USE_TIMER_MGMT)
|
||||
namespace {
|
||||
std::string writeUsedTimers(const std::bitset<TEST_TIMER_SIZE> &tset) {
|
||||
std::string writeUsedTimers(const std::bitset<TEST_TIMER_SIZE> &tset)
|
||||
{
|
||||
std::stringstream used_timers;
|
||||
if (tset.any()) {
|
||||
unsigned int timer{0};
|
||||
|
|
|
@ -37,7 +37,8 @@ extern "C" {
|
|||
STATIC_UNIT_TESTED void updateTransponderDMABufferArcitimer(transponder_t *transponder, const uint8_t* transponderData);
|
||||
}
|
||||
|
||||
TEST(transponderTest, updateTransponderDMABufferArcitimer) {
|
||||
TEST(transponderTest, updateTransponderDMABufferArcitimer)
|
||||
{
|
||||
//input
|
||||
uint8_t data[9] = {0x1F, 0xFC, 0x8F, 0x3, 0xF0, 0x1, 0xF8, 0x1F, 0x0};
|
||||
//excepted
|
||||
|
@ -69,7 +70,8 @@ TEST(transponderTest, updateTransponderDMABufferArcitimer) {
|
|||
}
|
||||
}
|
||||
|
||||
TEST(transponderTest, updateTransponderDMABufferIlap) {
|
||||
TEST(transponderTest, updateTransponderDMABufferIlap)
|
||||
{
|
||||
uint8_t data[9] = {0x1F, 0xFC, 0x8F, 0x3, 0xF0, 0x1, 0x0, 0x0, 0x0};
|
||||
|
||||
uint8_t excepted[TRANSPONDER_DMA_BUFFER_SIZE_ILAP] = {
|
||||
|
|
|
@ -36,7 +36,8 @@ extern "C" {
|
|||
void schedulerIgnoreTaskStateTime(void) {}
|
||||
}
|
||||
|
||||
TEST(WS2812, updateDMABuffer) {
|
||||
TEST(WS2812, updateDMABuffer)
|
||||
{
|
||||
// given
|
||||
rgbColor24bpp_t color1 = { .raw = {0xFF,0xAA,0x55} };
|
||||
|
||||
|
@ -78,12 +79,14 @@ TEST(WS2812, updateDMABuffer) {
|
|||
}
|
||||
|
||||
extern "C" {
|
||||
rgbColor24bpp_t* hsvToRgb24(const hsvColor_t *c) {
|
||||
rgbColor24bpp_t* hsvToRgb24(const hsvColor_t *c)
|
||||
{
|
||||
UNUSED(c);
|
||||
return NULL;
|
||||
}
|
||||
|
||||
bool ws2811LedStripHardwareInit(ioTag_t ioTag) {
|
||||
bool ws2811LedStripHardwareInit(ioTag_t ioTag)
|
||||
{
|
||||
UNUSED(ioTag);
|
||||
|
||||
return true;
|
||||
|
|
Loading…
Add table
Add a link
Reference in a new issue