Skip to content

Commit

Permalink
Make Cppcheck happier revived
Browse files Browse the repository at this point in the history
Co-authored-by: Štěpán Dalecký <daleckystepan@gmail.com>
  • Loading branch information
haslinghuis and daleckystepan committed May 10, 2024
1 parent d5af7d2 commit f6876a9
Show file tree
Hide file tree
Showing 63 changed files with 145 additions and 157 deletions.
2 changes: 0 additions & 2 deletions lib/main/MAVLink/mavlink_helpers.h
Original file line number Diff line number Diff line change
Expand Up @@ -289,7 +289,6 @@ MAVLINK_HELPER uint8_t mavlink_parse_char(uint8_t chan, uint8_t c, mavlink_messa

mavlink_message_t* rxmsg = mavlink_get_channel_buffer(chan); ///< The currently decoded message
mavlink_status_t* status = mavlink_get_channel_status(chan); ///< The current decode status
int bufferIndex = 0;

status->msg_received = 0;

Expand Down Expand Up @@ -425,7 +424,6 @@ MAVLINK_HELPER uint8_t mavlink_parse_char(uint8_t chan, uint8_t c, mavlink_messa
break;
}

bufferIndex++;
// If a message has been sucessfully decoded, check index
if (status->msg_received == 1)
{
Expand Down
30 changes: 13 additions & 17 deletions src/main/cli/cli.c
Original file line number Diff line number Diff line change
Expand Up @@ -1636,28 +1636,26 @@ static void printAdjustmentRange(dumpFlags_t dumpMask, const adjustmentRange_t *
static void cliAdjustmentRange(const char *cmdName, char *cmdline)
{
const char *format = "adjrange %u 0 %u %u %u %u %u %u %u";
int i, val = 0;
const char *ptr;

if (isEmpty(cmdline)) {
printAdjustmentRange(DUMP_MASTER, adjustmentRanges(0), NULL, NULL);
} else {
ptr = cmdline;
i = atoi(ptr++);
int i = atoi(ptr++);
if (i < MAX_ADJUSTMENT_RANGE_COUNT) {
adjustmentRange_t *ar = adjustmentRangesMutable(i);
uint8_t validArgumentCount = 0;

ptr = nextArg(ptr);
if (ptr) {
val = atoi(ptr);
// Was: slot
// Keeping the parameter to retain backwards compatibility for the command format.
validArgumentCount++;
}
ptr = nextArg(ptr);
if (ptr) {
val = atoi(ptr);
int val = atoi(ptr);
if (val >= 0 && val < MAX_AUX_CHANNEL_COUNT) {
ar->auxChannelIndex = val;
validArgumentCount++;
Expand All @@ -1668,15 +1666,15 @@ static void cliAdjustmentRange(const char *cmdName, char *cmdline)

ptr = nextArg(ptr);
if (ptr) {
val = atoi(ptr);
int val = atoi(ptr);
if (val >= 0 && val < ADJUSTMENT_FUNCTION_COUNT) {
ar->adjustmentConfig = val;
validArgumentCount++;
}
}
ptr = nextArg(ptr);
if (ptr) {
val = atoi(ptr);
int val = atoi(ptr);
if (val >= 0 && val < MAX_AUX_CHANNEL_COUNT) {
ar->auxSwitchChannelIndex = val;
validArgumentCount++;
Expand All @@ -1695,13 +1693,13 @@ static void cliAdjustmentRange(const char *cmdName, char *cmdline)

ptr = nextArg(ptr);
if (ptr) {
val = atoi(ptr);
int val = atoi(ptr);
ar->adjustmentCenter = val;
validArgumentCount++;
}
ptr = nextArg(ptr);
if (ptr) {
val = atoi(ptr);
int val = atoi(ptr);
ar->adjustmentScale = val;
validArgumentCount++;
}
Expand Down Expand Up @@ -2616,7 +2614,6 @@ static void printVtx(dumpFlags_t dumpMask, const vtxConfig_t *vtxConfig, const v
static void cliVtx(const char *cmdName, char *cmdline)
{
const char *format = "vtx %u %u %u %u %u %u %u";
int i, val = 0;
const char *ptr;

if (isEmpty(cmdline)) {
Expand All @@ -2632,37 +2629,37 @@ static void cliVtx(const char *cmdName, char *cmdline)
const uint8_t maxPowerIndex = VTX_TABLE_MAX_POWER_LEVELS;
#endif
ptr = cmdline;
i = atoi(ptr++);
int i = atoi(ptr++);
if (i < MAX_CHANNEL_ACTIVATION_CONDITION_COUNT) {
vtxChannelActivationCondition_t *cac = &vtxConfigMutable()->vtxChannelActivationConditions[i];
uint8_t validArgumentCount = 0;
ptr = nextArg(ptr);
if (ptr) {
val = atoi(ptr);
int val = atoi(ptr);
if (val >= 0 && val < MAX_AUX_CHANNEL_COUNT) {
cac->auxChannelIndex = val;
validArgumentCount++;
}
}
ptr = nextArg(ptr);
if (ptr) {
val = atoi(ptr);
int val = atoi(ptr);
if (val >= 0 && val <= maxBandIndex) {
cac->band = val;
validArgumentCount++;
}
}
ptr = nextArg(ptr);
if (ptr) {
val = atoi(ptr);
int val = atoi(ptr);
if (val >= 0 && val <= maxChannelIndex) {
cac->channel = val;
validArgumentCount++;
}
}
ptr = nextArg(ptr);
if (ptr) {
val = atoi(ptr);
int val = atoi(ptr);
if (val >= 0 && val <= maxPowerIndex) {
cac->power= val;
validArgumentCount++;
Expand Down Expand Up @@ -4377,7 +4374,7 @@ STATIC_UNIT_TESTED void cliGet(const char *cmdName, char *cmdline)
}
}

static uint8_t getWordLength(char *bufBegin, char *bufEnd)
static uint8_t getWordLength(const char *bufBegin, const char *bufEnd)
{
while (*(bufEnd - 1) == ' ') {
bufEnd--;
Expand Down Expand Up @@ -5438,9 +5435,8 @@ static void printTimerDmaoptDetails(const ioTag_t ioTag, const timerHardware_t *

if (printDetails) {
const dmaChannelSpec_t *dmaChannelSpec = dmaGetChannelSpecByTimerValue(timer->tim, timer->channel, dmaopt);
dmaCode_t dmaCode = 0;
if (dmaChannelSpec) {
dmaCode = dmaChannelSpec->code;
dmaCode_t dmaCode = dmaChannelSpec->code;
printValue(dumpMask, false,
"# pin %c%02d: " DMASPEC_FORMAT_STRING,
IO_GPIOPortIdxByTag(ioTag) + 'A', IO_GPIOPinIdxByTag(ioTag),
Expand Down
2 changes: 1 addition & 1 deletion src/main/cms/cms.c
Original file line number Diff line number Diff line change
Expand Up @@ -130,7 +130,7 @@ static displayPort_t *cmsDisplayPortSelectNext(void)
return cmsDisplayPorts[cmsCurrentDevice];
}

bool cmsDisplayPortSelect(displayPort_t *instance)
bool cmsDisplayPortSelect(const displayPort_t *instance)
{
for (unsigned i = 0; i < cmsDeviceCount; i++) {
if (cmsDisplayPortSelectNext() == instance) {
Expand Down
2 changes: 1 addition & 1 deletion src/main/cms/cms.h
Original file line number Diff line number Diff line change
Expand Up @@ -48,7 +48,7 @@ extern displayPort_t *pCurrentDisplay;
void cmsInit(void);
void cmsHandler(timeUs_t currentTimeUs);

bool cmsDisplayPortSelect(displayPort_t *instance);
bool cmsDisplayPortSelect(const displayPort_t *instance);
void cmsMenuOpen(void);
const void *cmsMenuChange(displayPort_t *pPort, const void *ptr);
const void *cmsMenuExit(displayPort_t *pPort, const void *ptr);
Expand Down
18 changes: 9 additions & 9 deletions src/main/common/maths.c
Original file line number Diff line number Diff line change
Expand Up @@ -229,7 +229,7 @@ void applyMatrixRotation(float *v, fp_rotationMatrix_t *rotationMatrix)
#define QMF_SORTF(a,b) { if ((a)>(b)) QMF_SWAPF((a),(b)); }
#define QMF_SWAPF(a,b) { float temp=(a);(a)=(b);(b)=temp; }

int32_t quickMedianFilter3(int32_t * v)
int32_t quickMedianFilter3(const int32_t * v)
{
int32_t p[3];
QMF_COPY(p, v, 3);
Expand All @@ -238,7 +238,7 @@ int32_t quickMedianFilter3(int32_t * v)
return p[1];
}

int32_t quickMedianFilter5(int32_t * v)
int32_t quickMedianFilter5(const int32_t * v)
{
int32_t p[5];
QMF_COPY(p, v, 5);
Expand All @@ -249,7 +249,7 @@ int32_t quickMedianFilter5(int32_t * v)
return p[2];
}

int32_t quickMedianFilter7(int32_t * v)
int32_t quickMedianFilter7(const int32_t * v)
{
int32_t p[7];
QMF_COPY(p, v, 7);
Expand All @@ -262,7 +262,7 @@ int32_t quickMedianFilter7(int32_t * v)
return p[3];
}

int32_t quickMedianFilter9(int32_t * v)
int32_t quickMedianFilter9(const int32_t * v)
{
int32_t p[9];
QMF_COPY(p, v, 9);
Expand All @@ -277,7 +277,7 @@ int32_t quickMedianFilter9(int32_t * v)
return p[4];
}

float quickMedianFilter3f(float * v)
float quickMedianFilter3f(const float * v)
{
float p[3];
QMF_COPY(p, v, 3);
Expand All @@ -286,7 +286,7 @@ float quickMedianFilter3f(float * v)
return p[1];
}

float quickMedianFilter5f(float * v)
float quickMedianFilter5f(const float * v)
{
float p[5];
QMF_COPY(p, v, 5);
Expand All @@ -297,7 +297,7 @@ float quickMedianFilter5f(float * v)
return p[2];
}

float quickMedianFilter7f(float * v)
float quickMedianFilter7f(const float * v)
{
float p[7];
QMF_COPY(p, v, 7);
Expand All @@ -310,7 +310,7 @@ float quickMedianFilter7f(float * v)
return p[3];
}

float quickMedianFilter9f(float * v)
float quickMedianFilter9f(const float * v)
{
float p[9];
QMF_COPY(p, v, 9);
Expand All @@ -325,7 +325,7 @@ float quickMedianFilter9f(float * v)
return p[4];
}

void arraySubInt32(int32_t *dest, int32_t *array1, int32_t *array2, int count)
void arraySubInt32(int32_t *dest, const int32_t *array1, const int32_t *array2, int count)
{
for (int i = 0; i < count; i++) {
dest[i] = array1[i] - array2[i];
Expand Down
18 changes: 9 additions & 9 deletions src/main/common/maths.h
Original file line number Diff line number Diff line change
Expand Up @@ -120,15 +120,15 @@ float scaleRangef(float x, float srcFrom, float srcTo, float destFrom, float des
void buildRotationMatrix(fp_angles_t *delta, fp_rotationMatrix_t *rotation);
void applyMatrixRotation(float *v, fp_rotationMatrix_t *rotationMatrix);

int32_t quickMedianFilter3(int32_t * v);
int32_t quickMedianFilter5(int32_t * v);
int32_t quickMedianFilter7(int32_t * v);
int32_t quickMedianFilter9(int32_t * v);
int32_t quickMedianFilter3(const int32_t * v);
int32_t quickMedianFilter5(const int32_t * v);
int32_t quickMedianFilter7(const int32_t * v);
int32_t quickMedianFilter9(const int32_t * v);

float quickMedianFilter3f(float * v);
float quickMedianFilter5f(float * v);
float quickMedianFilter7f(float * v);
float quickMedianFilter9f(float * v);
float quickMedianFilter3f(const float * v);
float quickMedianFilter5f(const float * v);
float quickMedianFilter7f(const float * v);
float quickMedianFilter9f(const float * v);

#if defined(FAST_MATH) || defined(VERY_FAST_MATH)
float sin_approx(float x);
Expand All @@ -150,7 +150,7 @@ float pow_approx(float a, float b);
#define pow_approx(a, b) powf(b, a)
#endif

void arraySubInt32(int32_t *dest, int32_t *array1, int32_t *array2, int count);
void arraySubInt32(int32_t *dest, const int32_t *array1, const int32_t *array2, int count);

int16_t qPercent(fix12_t q);
int16_t qMultiply(fix12_t q, int16_t input);
Expand Down
3 changes: 1 addition & 2 deletions src/main/common/sdft.c
Original file line number Diff line number Diff line change
Expand Up @@ -41,9 +41,8 @@ void sdftInit(sdft_t *sdft, const int startBin, const int endBin, const int numB
if (!isInitialized) {
rPowerN = powf(SDFT_R, SDFT_SAMPLE_SIZE);
const float c = 2.0f * M_PIf / (float)SDFT_SAMPLE_SIZE;
float phi = 0.0f;
for (int i = 0; i < SDFT_BIN_COUNT; i++) {
phi = c * i;
float phi = c * i;
twiddle[i] = SDFT_R * (cos_approx(phi) + _Complex_I * sin_approx(phi));
}
isInitialized = true;
Expand Down
6 changes: 3 additions & 3 deletions src/main/common/time.c
Original file line number Diff line number Diff line change
Expand Up @@ -184,12 +184,12 @@ rtcTime_t rtcTimeMake(int32_t secs, uint16_t millis)
return ((rtcTime_t)secs) * MILLIS_PER_SECOND + millis;
}

int32_t rtcTimeGetSeconds(rtcTime_t *t)
int32_t rtcTimeGetSeconds(const rtcTime_t *t)
{
return *t / MILLIS_PER_SECOND;
}

uint16_t rtcTimeGetMillis(rtcTime_t *t)
uint16_t rtcTimeGetMillis(const rtcTime_t *t)
{
return *t % MILLIS_PER_SECOND;
}
Expand Down Expand Up @@ -244,7 +244,7 @@ bool rtcGet(rtcTime_t *t)
return true;
}

bool rtcSet(rtcTime_t *t)
bool rtcSet(const rtcTime_t *t)
{
started = *t - millis();
return true;
Expand Down
6 changes: 3 additions & 3 deletions src/main/common/time.h
Original file line number Diff line number Diff line change
Expand Up @@ -62,8 +62,8 @@ PG_DECLARE(timeConfig_t, timeConfig);
typedef int64_t rtcTime_t;

rtcTime_t rtcTimeMake(int32_t secs, uint16_t millis);
int32_t rtcTimeGetSeconds(rtcTime_t *t);
uint16_t rtcTimeGetMillis(rtcTime_t *t);
int32_t rtcTimeGetSeconds(const rtcTime_t *t);
uint16_t rtcTimeGetMillis(const rtcTime_t *t);

typedef struct _dateTime_s {
// full year
Expand Down Expand Up @@ -96,7 +96,7 @@ bool dateTimeSplitFormatted(char *formatted, char **date, char **time);
bool rtcHasTime(void);

bool rtcGet(rtcTime_t *t);
bool rtcSet(rtcTime_t *t);
bool rtcSet(const rtcTime_t *t);

bool rtcGetDateTime(dateTime_t *dt);
bool rtcSetDateTime(dateTime_t *dt);
Expand Down
4 changes: 1 addition & 3 deletions src/main/drivers/accgyro/accgyro_mpu.c
Original file line number Diff line number Diff line change
Expand Up @@ -388,8 +388,6 @@ static bool detectSPISensorsAndUpdateDetectionResult(gyroDev_t *gyro, const gyro
IOConfigGPIO(gyro->dev.busType_u.spi.csnPin, SPI_IO_CS_CFG);
IOHi(gyro->dev.busType_u.spi.csnPin); // Ensure device is disabled, important when two devices are on the same bus.

uint8_t sensor = MPU_NONE;

// Allow 100ms before attempting to access gyro's SPI bus
// Do this once here rather than in each detection routine to speed boot
while (millis() < GYRO_SPI_STARTUP_MS);
Expand All @@ -402,7 +400,7 @@ static bool detectSPISensorsAndUpdateDetectionResult(gyroDev_t *gyro, const gyro
// May need a bitmap of hardware to detection function to do it right?

for (size_t index = 0 ; gyroSpiDetectFnTable[index] ; index++) {
sensor = (gyroSpiDetectFnTable[index])(&gyro->dev);
uint8_t sensor = (gyroSpiDetectFnTable[index])(&gyro->dev);
if (sensor != MPU_NONE) {
gyro->mpuDetectionResult.sensor = sensor;
busDeviceRegister(&gyro->dev);
Expand Down
2 changes: 1 addition & 1 deletion src/main/drivers/adc.c
Original file line number Diff line number Diff line change
Expand Up @@ -55,7 +55,7 @@ uint8_t adcChannelByTag(ioTag_t ioTag)
return 0;
}

ADCDevice adcDeviceByInstance(ADC_TypeDef *instance)
ADCDevice adcDeviceByInstance(const ADC_TypeDef *instance)
{
if (instance == ADC1) {
return ADCDEV_1;
Expand Down
2 changes: 1 addition & 1 deletion src/main/drivers/adc.h
Original file line number Diff line number Diff line change
Expand Up @@ -114,5 +114,5 @@ int16_t adcInternalComputeTemperature(uint16_t tempAdcValue, uint16_t vrefValue)
#endif

#if !defined(SIMULATOR_BUILD)
ADCDevice adcDeviceByInstance(ADC_TypeDef *instance);
ADCDevice adcDeviceByInstance(const ADC_TypeDef *instance);
#endif
2 changes: 1 addition & 1 deletion src/main/drivers/adc_impl.h
Original file line number Diff line number Diff line change
Expand Up @@ -102,7 +102,7 @@ extern adcOperatingConfig_t adcOperatingConfig[ADC_CHANNEL_COUNT];
extern volatile uint16_t adcValues[ADC_CHANNEL_COUNT];

uint8_t adcChannelByTag(ioTag_t ioTag);
ADCDevice adcDeviceByInstance(ADC_TypeDef *instance);
ADCDevice adcDeviceByInstance(const ADC_TypeDef *instance);
bool adcVerifyPin(ioTag_t tag, ADCDevice device);

// Marshall values in DMA instance/channel based order to adcChannel based order.
Expand Down
4 changes: 2 additions & 2 deletions src/main/drivers/at32/timer_at32bsp.c
Original file line number Diff line number Diff line change
Expand Up @@ -300,7 +300,7 @@ uint8_t timerLookupChannelIndex(const uint16_t channel)
return lookupChannelIndex(channel);
}

rccPeriphTag_t timerRCC(tmr_type *tim)
rccPeriphTag_t timerRCC(const tmr_type *tim)
{
for (int i = 0; i < HARDWARE_TIMER_DEFINITION_COUNT; i++) {
if (timerDefinitions[i].TIMx == tim) {
Expand All @@ -310,7 +310,7 @@ rccPeriphTag_t timerRCC(tmr_type *tim)
return 0;
}

uint8_t timerInputIrq(tmr_type *tim)
uint8_t timerInputIrq(const tmr_type *tim)
{
for (int i = 0; i < HARDWARE_TIMER_DEFINITION_COUNT; i++) {
if (timerDefinitions[i].TIMx == tim) {
Expand Down

0 comments on commit f6876a9

Please sign in to comment.