Merge pull request #11128 from SteveCEvans/sizeof

This commit is contained in:
J Blackman 2021-12-15 13:08:41 +11:00 committed by GitHub
commit ade559731c
No known key found for this signature in database
GPG Key ID: 4AEE18F83AFDEB23
18 changed files with 65 additions and 65 deletions

View File

@ -56,7 +56,7 @@ static void mpu9250AccAndGyroInit(gyroDev_t *gyro);
bool mpu9250SpiWriteRegister(const extDevice_t *dev, uint8_t reg, uint8_t data)
{
delayMicroseconds(1);
spiWriteRegBuf(dev, reg, &data, sizeof (data));
spiWriteRegBuf(dev, reg, &data, sizeof(data));
delayMicroseconds(1);
return true;

View File

@ -43,7 +43,7 @@ bool i2cBusWriteRegisterStart(const extDevice_t *dev, uint8_t reg, uint8_t data)
byte = data;
return i2cWriteBuffer(dev->bus->busType_u.i2c.device, dev->busType_u.i2c.address, reg, sizeof (byte), &byte);
return i2cWriteBuffer(dev->bus->busType_u.i2c.device, dev->busType_u.i2c.address, reg, sizeof(byte), &byte);
}
bool i2cBusReadRegisterBuffer(const extDevice_t *dev, uint8_t reg, uint8_t *data, uint8_t length)

View File

@ -213,7 +213,7 @@ uint8_t spiReadWrite(const extDevice_t *dev, uint8_t data)
// This routine blocks so no need to use static data
busSegment_t segments[] = {
{&data, &retval, sizeof (data), true, NULL},
{&data, &retval, sizeof(data), true, NULL},
{NULL, NULL, 0, true, NULL},
};
@ -234,8 +234,8 @@ uint8_t spiReadWriteReg(const extDevice_t *dev, uint8_t reg, uint8_t data)
// This routine blocks so no need to use static data
busSegment_t segments[] = {
{&reg, NULL, sizeof (reg), false, NULL},
{&data, &retval, sizeof (data), true, NULL},
{&reg, NULL, sizeof(reg), false, NULL},
{&data, &retval, sizeof(data), true, NULL},
{NULL, NULL, 0, true, NULL},
};
@ -254,7 +254,7 @@ void spiWrite(const extDevice_t *dev, uint8_t data)
{
// This routine blocks so no need to use static data
busSegment_t segments[] = {
{&data, NULL, sizeof (data), true, NULL},
{&data, NULL, sizeof(data), true, NULL},
{NULL, NULL, 0, true, NULL},
};
@ -271,8 +271,8 @@ void spiWriteReg(const extDevice_t *dev, uint8_t reg, uint8_t data)
{
// This routine blocks so no need to use static data
busSegment_t segments[] = {
{&reg, NULL, sizeof (reg), false, NULL},
{&data, NULL, sizeof (data), true, NULL},
{&reg, NULL, sizeof(reg), false, NULL},
{&data, NULL, sizeof(data), true, NULL},
{NULL, NULL, 0, true, NULL},
};
@ -302,7 +302,7 @@ void spiReadRegBuf(const extDevice_t *dev, uint8_t reg, uint8_t *data, uint8_t l
{
// This routine blocks so no need to use static data
busSegment_t segments[] = {
{&reg, NULL, sizeof (reg), false, NULL},
{&reg, NULL, sizeof(reg), false, NULL},
{NULL, data, length, true, NULL},
{NULL, NULL, 0, true, NULL},
};
@ -339,7 +339,7 @@ void spiWriteRegBuf(const extDevice_t *dev, uint8_t reg, uint8_t *data, uint32_t
{
// This routine blocks so no need to use static data
busSegment_t segments[] = {
{&reg, NULL, sizeof (reg), false, NULL},
{&reg, NULL, sizeof(reg), false, NULL},
{data, NULL, length, true, NULL},
{NULL, NULL, 0, true, NULL},
};
@ -358,8 +358,8 @@ uint8_t spiReadReg(const extDevice_t *dev, uint8_t reg)
uint8_t data;
// This routine blocks so no need to use static data
busSegment_t segments[] = {
{&reg, NULL, sizeof (reg), false, NULL},
{NULL, &data, sizeof (data), true, NULL},
{&reg, NULL, sizeof(reg), false, NULL},
{NULL, &data, sizeof(data), true, NULL},
{NULL, NULL, 0, true, NULL},
};

View File

@ -66,11 +66,11 @@
#ifdef USE_DSHOT_CACHE_MGMT
// MOTOR_DSHOT_BUF_LENGTH is multiples of uint32_t
// Number of bytes required for buffer
#define MOTOR_DSHOT_BUF_BYTES (MOTOR_DSHOT_BUF_LENGTH * sizeof (uint32_t))
#define MOTOR_DSHOT_BUF_BYTES (MOTOR_DSHOT_BUF_LENGTH * sizeof(uint32_t))
// Number of bytes required to cache align buffer
#define MOTOR_DSHOT_BUF_CACHE_ALIGN_BYTES ((MOTOR_DSHOT_BUF_BYTES + 0x20) & ~0x1f)
// Size of array to create a cache aligned buffer
#define MOTOR_DSHOT_BUF_CACHE_ALIGN_LENGTH (MOTOR_DSHOT_BUF_CACHE_ALIGN_BYTES / sizeof (uint32_t))
#define MOTOR_DSHOT_BUF_CACHE_ALIGN_LENGTH (MOTOR_DSHOT_BUF_CACHE_ALIGN_BYTES / sizeof(uint32_t))
#else
#define MOTOR_DSHOT_BUF_CACHE_ALIGN_LENGTH MOTOR_DSHOT_BUF_LENGTH
#endif
@ -221,11 +221,11 @@ extern uint32_t bbOutputBuffer[MOTOR_DSHOT_BUF_CACHE_ALIGN_LENGTH * MAX_SUPPORTE
#ifdef USE_DSHOT_CACHE_MGMT
// Each sample is a uint16_t
// Number of bytes required for buffer
#define DSHOT_BB_PORT_IP_BUF_BYTES (DSHOT_BB_PORT_IP_BUF_LENGTH * sizeof (uint16_t))
#define DSHOT_BB_PORT_IP_BUF_BYTES (DSHOT_BB_PORT_IP_BUF_LENGTH * sizeof(uint16_t))
// Number of bytes required to cache align buffer
#define DSHOT_BB_PORT_IP_BUF_CACHE_ALIGN_BYTES ((DSHOT_BB_PORT_IP_BUF_BYTES + 0x20) & ~0x1f)
// Size of array to create a cache aligned buffer
#define DSHOT_BB_PORT_IP_BUF_CACHE_ALIGN_LENGTH (DSHOT_BB_PORT_IP_BUF_CACHE_ALIGN_BYTES / sizeof (uint16_t))
#define DSHOT_BB_PORT_IP_BUF_CACHE_ALIGN_LENGTH (DSHOT_BB_PORT_IP_BUF_CACHE_ALIGN_BYTES / sizeof(uint16_t))
#else
#define DSHOT_BB_PORT_IP_BUF_CACHE_ALIGN_LENGTH DSHOT_BB_PORT_IP_BUF_LENGTH
#endif

View File

@ -172,7 +172,7 @@ static bool flashSpiInit(const flashConfig_t *flashConfig)
*/
uint8_t readIdResponse[4] = { 0 };
spiReadRegBuf(dev, FLASH_INSTRUCTION_RDID, readIdResponse, sizeof (readIdResponse));
spiReadRegBuf(dev, FLASH_INSTRUCTION_RDID, readIdResponse, sizeof(readIdResponse));
// Manufacturer, memory type, and capacity
uint32_t chipID = (readIdResponse[0] << 16) | (readIdResponse[1] << 8) | (readIdResponse[2]);

View File

@ -130,7 +130,7 @@ static uint8_t m25p16_readStatus(flashDevice_t *fdevice)
STATIC_DMA_DATA_AUTO uint8_t readStatus[2] = { M25P16_INSTRUCTION_READ_STATUS_REG, 0 };
STATIC_DMA_DATA_AUTO uint8_t readyStatus[2];
spiReadWriteBuf(fdevice->io.handle.dev, readStatus, readyStatus, sizeof (readStatus));
spiReadWriteBuf(fdevice->io.handle.dev, readStatus, readyStatus, sizeof(readStatus));
return readyStatus[1];
}
@ -204,7 +204,7 @@ bool m25p16_detect(flashDevice_t *fdevice, uint32_t chipID)
// This routine blocks so no need to use static data
uint8_t modeSet[] = { W25Q256_INSTRUCTION_ENTER_4BYTE_ADDRESS_MODE };
spiReadWriteBuf(fdevice->io.handle.dev, modeSet, NULL, sizeof (modeSet));
spiReadWriteBuf(fdevice->io.handle.dev, modeSet, NULL, sizeof(modeSet));
}
fdevice->couldBeBusy = true; // Just for luck we'll assume the chip could be busy even though it isn't specced to be
@ -281,8 +281,8 @@ static void m25p16_eraseSector(flashDevice_t *fdevice, uint32_t address)
STATIC_DMA_DATA_AUTO uint8_t writeEnable[] = { M25P16_INSTRUCTION_WRITE_ENABLE };
busSegment_t segments[] = {
{readStatus, readyStatus, sizeof (readStatus), true, m25p16_callbackReady},
{writeEnable, NULL, sizeof (writeEnable), true, m25p16_callbackWriteEnable},
{readStatus, readyStatus, sizeof(readStatus), true, m25p16_callbackReady},
{writeEnable, NULL, sizeof(writeEnable), true, m25p16_callbackWriteEnable},
{sectorErase, NULL, fdevice->isLargeFlash ? 5 : 4, true, NULL},
{NULL, NULL, 0, true, NULL},
};
@ -306,9 +306,9 @@ static void m25p16_eraseCompletely(flashDevice_t *fdevice)
STATIC_DMA_DATA_AUTO uint8_t bulkErase[] = { M25P16_INSTRUCTION_BULK_ERASE };
busSegment_t segments[] = {
{readStatus, readyStatus, sizeof (readStatus), true, m25p16_callbackReady},
{writeEnable, NULL, sizeof (writeEnable), true, m25p16_callbackWriteEnable},
{bulkErase, NULL, sizeof (bulkErase), true, NULL},
{readStatus, readyStatus, sizeof(readStatus), true, m25p16_callbackReady},
{writeEnable, NULL, sizeof(writeEnable), true, m25p16_callbackWriteEnable},
{bulkErase, NULL, sizeof(bulkErase), true, NULL},
{NULL, NULL, 0, true, NULL},
};
@ -337,8 +337,8 @@ static uint32_t m25p16_pageProgramContinue(flashDevice_t *fdevice, uint8_t const
STATIC_DMA_DATA_AUTO uint8_t pageProgram[5] = { M25P16_INSTRUCTION_PAGE_PROGRAM };
static busSegment_t segments[] = {
{readStatus, readyStatus, sizeof (readStatus), true, m25p16_callbackReady},
{writeEnable, NULL, sizeof (writeEnable), true, m25p16_callbackWriteEnable},
{readStatus, readyStatus, sizeof(readStatus), true, m25p16_callbackReady},
{writeEnable, NULL, sizeof(writeEnable), true, m25p16_callbackWriteEnable},
{pageProgram, NULL, 0, false, NULL},
{NULL, NULL, 0, true, NULL},
{NULL, NULL, 0, true, NULL},
@ -430,7 +430,7 @@ static int m25p16_readBytes(flashDevice_t *fdevice, uint32_t address, uint8_t *b
spiWaitClaim(fdevice->io.handle.dev);
busSegment_t segments[] = {
{readStatus, readyStatus, sizeof (readStatus), true, m25p16_callbackReady},
{readStatus, readyStatus, sizeof(readStatus), true, m25p16_callbackReady},
{readBytes, NULL, fdevice->isLargeFlash ? 5 : 4, false, NULL},
{NULL, buffer, length, true, NULL},
{NULL, NULL, 0, true, NULL},

View File

@ -73,7 +73,7 @@ static void w25m_dieSelect(const extDevice_t *dev, int die)
uint8_t command[2] = { W25M_INSTRUCTION_SOFTWARE_DIE_SELECT, die };
busSegment_t segments[] = {
{command, NULL, sizeof (command), true, NULL},
{command, NULL, sizeof(command), true, NULL},
{NULL, NULL, 0, true, NULL},
};

View File

@ -150,7 +150,7 @@ static void w25n01g_performOneByteCommand(flashDeviceIO_t *io, uint8_t command)
extDevice_t *dev = io->handle.dev;
busSegment_t segments[] = {
{&command, NULL, sizeof (command), true, NULL},
{&command, NULL, sizeof(command), true, NULL},
{NULL, NULL, 0, true, NULL},
};
@ -178,7 +178,7 @@ static void w25n01g_performCommandWithPageAddress(flashDeviceIO_t *io, uint8_t c
uint8_t cmd[] = { command, 0, (pageAddress >> 8) & 0xff, (pageAddress >> 0) & 0xff};
busSegment_t segments[] = {
{cmd, NULL, sizeof (cmd), true, NULL},
{cmd, NULL, sizeof(cmd), true, NULL},
{NULL, NULL, 0, true, NULL},
};
@ -208,7 +208,7 @@ static uint8_t w25n01g_readRegister(flashDeviceIO_t *io, uint8_t reg)
uint8_t in[3];
busSegment_t segments[] = {
{cmd, in, sizeof (cmd), true, NULL},
{cmd, in, sizeof(cmd), true, NULL},
{NULL, NULL, 0, true, NULL},
};
@ -243,7 +243,7 @@ static void w25n01g_writeRegister(flashDeviceIO_t *io, uint8_t reg, uint8_t data
uint8_t cmd[3] = { W25N01G_INSTRUCTION_WRITE_STATUS_REG, reg, data };
busSegment_t segments[] = {
{cmd, NULL, sizeof (cmd), true, NULL},
{cmd, NULL, sizeof(cmd), true, NULL},
{NULL, NULL, 0, true, NULL},
};
@ -414,7 +414,7 @@ static void w25n01g_programDataLoad(flashDevice_t *fdevice, uint16_t columnAddre
uint8_t cmd[] = { W25N01G_INSTRUCTION_PROGRAM_DATA_LOAD, columnAddress >> 8, columnAddress & 0xff };
busSegment_t segments[] = {
{cmd, NULL, sizeof (cmd), false, NULL},
{cmd, NULL, sizeof(cmd), false, NULL},
{(uint8_t *)data, NULL, length, true, NULL},
{NULL, NULL, 0, true, NULL},
};
@ -448,7 +448,7 @@ static void w25n01g_randomProgramDataLoad(flashDevice_t *fdevice, uint16_t colum
extDevice_t *dev = fdevice->io.handle.dev;
busSegment_t segments[] = {
{cmd, NULL, sizeof (cmd), false, NULL},
{cmd, NULL, sizeof(cmd), false, NULL},
{(uint8_t *)data, NULL, length, true, NULL},
{NULL, NULL, 0, true, NULL},
};
@ -694,7 +694,7 @@ int w25n01g_readBytes(flashDevice_t *fdevice, uint32_t address, uint8_t *buffer,
cmd[3] = 0;
busSegment_t segments[] = {
{cmd, NULL, sizeof (cmd), false, NULL},
{cmd, NULL, sizeof(cmd), false, NULL},
{NULL, buffer, length, true, NULL},
{NULL, NULL, 0, true, NULL},
};
@ -762,7 +762,7 @@ int w25n01g_readExtensionBytes(flashDevice_t *fdevice, uint32_t address, uint8_t
cmd[3] = 0;
busSegment_t segments[] = {
{cmd, NULL, sizeof (cmd), false, NULL},
{cmd, NULL, sizeof(cmd), false, NULL},
{NULL, buffer, length, true, NULL},
{NULL, NULL, 0, true, NULL},
};
@ -862,8 +862,8 @@ void w25n01g_readBBLUT(flashDevice_t *fdevice, bblut_t *bblut, int lutsize)
cb_context.lutindex = 0;
busSegment_t segments[] = {
{cmd, NULL, sizeof (cmd), false, NULL},
{NULL, in, sizeof (in), true, w25n01g_readBBLUTCallback},
{cmd, NULL, sizeof(cmd), false, NULL},
{NULL, in, sizeof(in), true, w25n01g_readBBLUTCallback},
{NULL, NULL, 0, true, NULL},
};
@ -905,7 +905,7 @@ void w25n01g_writeBBLUT(flashDevice_t *fdevice, uint16_t lba, uint16_t pba)
uint8_t cmd[5] = { W25N01G_INSTRUCTION_BB_MANAGEMENT, lba >> 8, lba, pba >> 8, pba };
busSegment_t segments[] = {
{cmd, NULL, sizeof (cmd), true, NULL},
{cmd, NULL, sizeof(cmd), true, NULL},
{NULL, NULL, 0, true, NULL},
};

View File

@ -49,11 +49,11 @@
#ifdef USE_LEDSTRIP_CACHE_MGMT
// WS2811_DMA_BUFFER_SIZE is multiples of uint32_t
// Number of bytes required for buffer
#define WS2811_DMA_BUF_BYTES (WS2811_DMA_BUFFER_SIZE * sizeof (uint32_t))
#define WS2811_DMA_BUF_BYTES (WS2811_DMA_BUFFER_SIZE * sizeof(uint32_t))
// Number of bytes required to cache align buffer
#define WS2811_DMA_BUF_CACHE_ALIGN_BYTES ((WS2811_DMA_BUF_BYTES + 0x20) & ~0x1f)
// Size of array to create a cache aligned buffer
#define WS2811_DMA_BUF_CACHE_ALIGN_LENGTH (WS2811_DMA_BUF_CACHE_ALIGN_BYTES / sizeof (uint32_t))
#define WS2811_DMA_BUF_CACHE_ALIGN_LENGTH (WS2811_DMA_BUF_CACHE_ALIGN_BYTES / sizeof(uint32_t))
DMA_RW_AXI __attribute__((aligned(32))) uint32_t ledStripDMABuffer[WS2811_DMA_BUF_CACHE_ALIGN_LENGTH];
#else
#if defined(STM32F1) || defined(STM32F3)

View File

@ -44,11 +44,11 @@
#ifdef USE_LEDSTRIP_CACHE_MGMT
// WS2811_DMA_BUFFER_SIZE is multiples of uint32_t
// Number of bytes required for buffer
#define WS2811_DMA_BUF_BYTES (WS2811_DMA_BUFFER_SIZE * sizeof (uint32_t))
#define WS2811_DMA_BUF_BYTES (WS2811_DMA_BUFFER_SIZE * sizeof(uint32_t))
// Number of bytes required to cache align buffer
#define WS2811_DMA_BUF_CACHE_ALIGN_BYTES ((WS2811_DMA_BUF_BYTES + 0x20) & ~0x1f)
// Size of array to create a cache aligned buffer
#define WS2811_DMA_BUF_CACHE_ALIGN_LENGTH (WS2811_DMA_BUF_CACHE_ALIGN_BYTES / sizeof (uint32_t))
#define WS2811_DMA_BUF_CACHE_ALIGN_LENGTH (WS2811_DMA_BUF_CACHE_ALIGN_BYTES / sizeof(uint32_t))
extern uint32_t ledStripDMABuffer[WS2811_DMA_BUF_CACHE_ALIGN_LENGTH];
#else
#if defined(STM32F1) || defined(STM32F3)

View File

@ -667,7 +667,7 @@ static void max7456DrawScreenSlow(void)
dma_regs[1] = 0;
dma_regs[2] = 0;
spiWriteRegBuf(dev, MAX7456ADD_DMM, dma_regs, sizeof (dma_regs));
spiWriteRegBuf(dev, MAX7456ADD_DMM, dma_regs, sizeof(dma_regs));
// The "escape" character 0xFF must be skipped as it causes the MAX7456 to exit auto-increment mode.
for (int xx = 0; xx < maxScreenSize; xx++) {
@ -693,7 +693,7 @@ static void max7456DrawScreenSlow(void)
if (buffer[xx] == END_STRING) {
dma_regs[0] = xx >> 8;
dma_regs[1] = xx & 0xFF;
spiWriteRegBuf(dev, MAX7456ADD_DMAH, dma_regs, sizeof (dma_regs));
spiWriteRegBuf(dev, MAX7456ADD_DMAH, dma_regs, sizeof(dma_regs));
}
}
}

View File

@ -168,7 +168,7 @@ static bool sdcard_waitForIdle(int maxBytesToWait)
// Note that this does not release the CS at the end of the transaction
busSegment_t segments[] = {
{NULL, &idleByte, sizeof (idleByte), false, sdcard_callbackIdle},
{NULL, &idleByte, sizeof(idleByte), false, sdcard_callbackIdle},
{NULL, NULL, 0, false, NULL},
};
@ -196,7 +196,7 @@ static uint8_t sdcard_waitForNonIdleByte(int maxDelay)
// Note that this does not release the CS at the end of the transaction
busSegment_t segments[] = {
{NULL, &idleByte, sizeof (idleByte), false, sdcard_callbackNotIdle},
{NULL, &idleByte, sizeof(idleByte), false, sdcard_callbackNotIdle},
{NULL, NULL, 0, false, NULL},
};
@ -238,8 +238,8 @@ static uint8_t sdcard_sendCommand(uint8_t commandCode, uint32_t commandArgument)
// Note that this does not release the CS at the end of the transaction
busSegment_t segments[] = {
{command, NULL, sizeof (command), false, NULL},
{NULL, &idleByte, sizeof (idleByte), false, sdcard_callbackNotIdle},
{command, NULL, sizeof(command), false, NULL},
{NULL, &idleByte, sizeof(idleByte), false, sdcard_callbackNotIdle},
{NULL, NULL, 0, false, NULL},
};
@ -288,7 +288,7 @@ static bool sdcard_validateInterfaceCondition(void)
} else if (status == SDCARD_R1_STATUS_BIT_IDLE) {
// Note that this does not release the CS at the end of the transaction
busSegment_t segments[] = {
{NULL, ifCondReply, sizeof (ifCondReply), false, NULL},
{NULL, ifCondReply, sizeof(ifCondReply), false, NULL},
{NULL, NULL, 0, false, NULL},
};
@ -321,7 +321,7 @@ static bool sdcard_readOCRRegister(uint32_t *result)
// Note that this does not release the CS at the end of the transaction
busSegment_t segments[] = {
{NULL, response, sizeof (response), false, NULL},
{NULL, response, sizeof(response), false, NULL},
{NULL, NULL, 0, false, NULL},
};
@ -391,8 +391,8 @@ static bool sdcard_sendDataBlockFinish(void)
uint8_t dataResponseToken;
// Note that this does not release the CS at the end of the transaction
busSegment_t segments[] = {
{(uint8_t *)&dummyCRC, NULL, sizeof (dummyCRC), false, NULL},
{NULL, &dataResponseToken, sizeof (dataResponseToken), false, NULL},
{(uint8_t *)&dummyCRC, NULL, sizeof(dummyCRC), false, NULL},
{NULL, &dataResponseToken, sizeof(dataResponseToken), false, NULL},
{NULL, NULL, 0, false, NULL},
};
@ -432,7 +432,7 @@ static void sdcard_sendDataBlockBegin(uint8_t *buffer, bool multiBlockWrite)
static busSegment_t segments[] = {
// Write a single 0xff
{NULL, NULL, 1, false, NULL},
{&token, NULL, sizeof (token), false, NULL},
{&token, NULL, sizeof(token), false, NULL},
{NULL, NULL, 0, false, NULL},
{NULL, NULL, 0, false, NULL},
};

View File

@ -781,7 +781,7 @@ _TIM_IRQ_HANDLER(TIM1_TRG_COM_TIM17_IRQHandler, 17);
void timerInit(void)
{
memset(timerConfig, 0, sizeof (timerConfig));
memset(timerConfig, 0, sizeof(timerConfig));
#if defined(PARTIAL_REMAP_TIM3)
GPIO_PinRemapConfig(GPIO_PartialRemap_TIM3, ENABLE);

View File

@ -881,7 +881,7 @@ _TIM_IRQ_HANDLER(TIM20_CC_IRQHandler, 20);
void timerInit(void)
{
memset(timerConfig, 0, sizeof (timerConfig));
memset(timerConfig, 0, sizeof(timerConfig));
#if USED_TIMERS & TIM_N(1)
__HAL_RCC_TIM1_CLK_ENABLE();

View File

@ -141,7 +141,7 @@ static void rtc6705Transfer(uint32_t command)
// Perform bitwise reverse of the command.
command = reverse32(command);
spiReadWriteBuf(dev, (uint8_t *)&command, NULL, sizeof (command));
spiReadWriteBuf(dev, (uint8_t *)&command, NULL, sizeof(command));
delayMicroseconds(2);
}

View File

@ -209,7 +209,7 @@ static int8_t CDC_Itf_Control (uint8_t cmd, uint8_t* pbuf, uint16_t length)
break;
case CDC_SET_LINE_CODING:
if (pbuf && (length == sizeof (*plc))) {
if (pbuf && (length == sizeof(*plc))) {
LineCoding.bitrate = plc->bitrate;
LineCoding.format = plc->format;
LineCoding.paritytype = plc->paritytype;
@ -224,7 +224,7 @@ static int8_t CDC_Itf_Control (uint8_t cmd, uint8_t* pbuf, uint16_t length)
break;
case CDC_GET_LINE_CODING:
if (pbuf && (length == sizeof (*plc))) {
if (pbuf && (length == sizeof(*plc))) {
plc->bitrate = LineCoding.bitrate;
plc->format = LineCoding.format;
plc->paritytype = LineCoding.paritytype;
@ -234,7 +234,7 @@ static int8_t CDC_Itf_Control (uint8_t cmd, uint8_t* pbuf, uint16_t length)
case CDC_SET_CONTROL_LINE_STATE:
// If a callback is provided, tell the upper driver of changes in DTR/RTS state
if (pbuf && (length == sizeof (uint16_t))) {
if (pbuf && (length == sizeof(uint16_t))) {
if (ctrlLineStateCb) {
ctrlLineStateCb(ctrlLineStateCbContext, *((uint16_t *)pbuf));
}

View File

@ -136,7 +136,7 @@ static uint16_t VCP_Ctrl(uint32_t Cmd, uint8_t* Buf, uint32_t Len)
//Note - hw flow control on UART 1-3 and 6 only
case SET_LINE_CODING:
// If a callback is provided, tell the upper driver of changes in baud rate
if (plc && (Len == sizeof (*plc))) {
if (plc && (Len == sizeof(*plc))) {
if (baudRateCb) {
baudRateCb(baudRateCbContext, plc->bitrate);
}
@ -146,7 +146,7 @@ static uint16_t VCP_Ctrl(uint32_t Cmd, uint8_t* Buf, uint32_t Len)
case GET_LINE_CODING:
if (plc && (Len == sizeof (*plc))) {
if (plc && (Len == sizeof(*plc))) {
ust_cpy(plc, &g_lc);
}
break;
@ -154,7 +154,7 @@ static uint16_t VCP_Ctrl(uint32_t Cmd, uint8_t* Buf, uint32_t Len)
case SET_CONTROL_LINE_STATE:
// If a callback is provided, tell the upper driver of changes in DTR/RTS state
if (plc && (Len == sizeof (uint16_t))) {
if (plc && (Len == sizeof(uint16_t))) {
if (ctrlLineStateCb) {
ctrlLineStateCb(ctrlLineStateCbContext, *((uint16_t *)Buf));
}

View File

@ -543,7 +543,7 @@ TEST_F(RcControlsAdjustmentsTest, processPIDIncreasePidController0)
{
// given
pidProfile_t pidProfile;
memset(&pidProfile, 0, sizeof (pidProfile));
memset(&pidProfile, 0, sizeof(pidProfile));
pidProfile.pid[PID_PITCH].P = 0;
pidProfile.pid[PID_PITCH].I = 10;
pidProfile.pid[PID_PITCH].D = 20;
@ -555,7 +555,7 @@ TEST_F(RcControlsAdjustmentsTest, processPIDIncreasePidController0)
pidProfile.pid[PID_YAW].D = 27;
// and
controlRateConfig_t controlRateConfig;
memset(&controlRateConfig, 0, sizeof (controlRateConfig));
memset(&controlRateConfig, 0, sizeof(controlRateConfig));
const timedAdjustmentState_t *adjustmentState1 = configureStepwiseAdjustment(AUX1 - NON_AUX_CHANNEL_COUNT, ADJUSTMENT_PITCH_ROLL_P_INDEX);
const timedAdjustmentState_t *adjustmentState2 = configureStepwiseAdjustment(AUX2 - NON_AUX_CHANNEL_COUNT, ADJUSTMENT_PITCH_ROLL_I_INDEX);