1
0
Fork 0
mirror of https://github.com/betaflight/betaflight.git synced 2025-07-13 11:29:58 +03:00

Fix clang unitests (#13551)

This commit is contained in:
Petr Ledvina 2024-04-21 08:51:23 +02:00 committed by GitHub
parent 1da9515427
commit 4ae1a672b4
No known key found for this signature in database
GPG key ID: B5690EEEBB952194
18 changed files with 25 additions and 25 deletions

View file

@ -4250,7 +4250,6 @@ static void cliDefaults(const char *cmdName, char *cmdline)
char *saveptr; char *saveptr;
char* tok = strtok_r(cmdline, " ", &saveptr); char* tok = strtok_r(cmdline, " ", &saveptr);
int index = 0;
bool expectParameterGroupId = false; bool expectParameterGroupId = false;
while (tok != NULL) { while (tok != NULL) {
if (expectParameterGroupId) { if (expectParameterGroupId) {
@ -4271,7 +4270,6 @@ static void cliDefaults(const char *cmdName, char *cmdline)
return; return;
} }
index++;
tok = strtok_r(NULL, " ", &saveptr); tok = strtok_r(NULL, " ", &saveptr);
} }

View file

@ -119,8 +119,12 @@ static int32_t gyroCyclesNow;
static timeMs_t lastFailsafeCheckMs = 0; static timeMs_t lastFailsafeCheckMs = 0;
// No need for a linked list for the queue, since items are only inserted at startup // No need for a linked list for the queue, since items are only inserted at startup
#ifdef UNIT_TEST
STATIC_UNIT_TESTED FAST_DATA_ZERO_INIT task_t* taskQueueArray[TASK_COUNT + 1]; // extra item for NULL pointer at end of queue #define TASK_QUEUE_RESERVE 1
#else
#define TASK_QUEUE_RESERVE 0
#endif
STATIC_UNIT_TESTED FAST_DATA_ZERO_INIT task_t* taskQueueArray[TASK_COUNT + 1 + TASK_QUEUE_RESERVE]; // extra item for NULL pointer at end of queue (+ overflow check in UNTT_TEST)
void queueClear(void) void queueClear(void)
{ {
@ -443,8 +447,8 @@ FAST_CODE timeUs_t schedulerExecuteTask(task_t *selectedTask, timeUs_t currentTi
} }
#if defined(UNIT_TEST) #if defined(UNIT_TEST)
task_t *unittest_scheduler_selectedTask; STATIC_UNIT_TESTED task_t *unittest_scheduler_selectedTask;
uint8_t unittest_scheduler_selectedTaskDynamicPriority; STATIC_UNIT_TESTED uint8_t unittest_scheduler_selectedTaskDynamicPriority;
static void readSchedulerLocals(task_t *selectedTask, uint8_t selectedTaskDynamicPriority) static void readSchedulerLocals(task_t *selectedTask, uint8_t selectedTaskDynamicPriority)
{ {

View file

@ -329,8 +329,6 @@ void hottPrepareEAMResponse(HOTT_EAM_MSG_t *hottEAMMessage)
static void hottSerialWrite(uint8_t c) static void hottSerialWrite(uint8_t c)
{ {
static uint8_t serialWrites = 0;
serialWrites++;
serialWrite(hottPort, c); serialWrite(hottPort, c);
} }

View file

@ -517,11 +517,11 @@ CXX_VERSION = $(shell $(CXX) -dumpversion)
ifeq ($(shell $(CC) -v 2>&1 | grep -q "clang version" && echo "clang"),clang) ifeq ($(shell $(CC) -v 2>&1 | grep -q "clang version" && echo "clang"),clang)
# Please revisit versions when new clang version arrive. Supported versions: { Linux / OSX: 7 - 14 } # Please revisit versions when new clang version arrive. Supported versions: { Linux / OSX: 7 - 16 }
# Travis reports CC_VERSION of 4.2.1 # Travis reports CC_VERSION of 4.2.1
CC_VERSION_MAJOR := $(firstword $(subst ., ,$(CC_VERSION))) CC_VERSION_MAJOR := $(firstword $(subst ., ,$(CC_VERSION)))
CC_VERSION_CHECK_MIN := 7 CC_VERSION_CHECK_MIN := 7
CC_VERSION_CHECK_MAX := 14 CC_VERSION_CHECK_MAX := 16
# Added flags for clang 11 - 13 are not backwards compatible # Added flags for clang 11 - 13 are not backwards compatible
ifeq ($(shell expr $(CC_VERSION_MAJOR) \> 10 \& $(CC_VERSION_MAJOR) \< 14), 1) ifeq ($(shell expr $(CC_VERSION_MAJOR) \> 10 \& $(CC_VERSION_MAJOR) \< 14), 1)

View file

@ -78,7 +78,6 @@ extern "C" {
PG_REGISTER(gpsRescueConfig_t, gpsRescueConfig, PG_GPS_RESCUE, 0); PG_REGISTER(gpsRescueConfig_t, gpsRescueConfig, PG_GPS_RESCUE, 0);
PG_REGISTER(positionConfig_t, positionConfig, PG_POSITION, 0); PG_REGISTER(positionConfig_t, positionConfig, PG_POSITION, 0);
float rcCommand[4];
float rcData[MAX_SUPPORTED_RC_CHANNEL_COUNT]; float rcData[MAX_SUPPORTED_RC_CHANNEL_COUNT];
uint16_t averageSystemLoadPercent = 0; uint16_t averageSystemLoadPercent = 0;
uint8_t cliMode = 0; uint8_t cliMode = 0;

View file

@ -50,7 +50,7 @@ typedef struct {
int16_t oversampling_setting; int16_t oversampling_setting;
} bmp085_t; } bmp085_t;
bmp085_t bmp085; extern bmp085_t bmp085;
} }

View file

@ -44,7 +44,7 @@ typedef struct bmp280_calib_param_s {
int16_t dig_P9; /* calibration P9 data */ int16_t dig_P9; /* calibration P9 data */
} __attribute__((packed)) bmp280_calib_param_t; // packed as we read directly from the device into this structure. } __attribute__((packed)) bmp280_calib_param_t; // packed as we read directly from the device into this structure.
bmp280_calib_param_t bmp280_cal; extern bmp280_calib_param_t bmp280_cal;
} }

View file

@ -46,7 +46,7 @@ typedef struct bmp388_calib_param_s {
int8_t P11; int8_t P11;
} __attribute__((packed)) bmp388_calib_param_t; // packed as we read directly from the device into this structure. } __attribute__((packed)) bmp388_calib_param_t; // packed as we read directly from the device into this structure.
bmp388_calib_param_t bmp388_cal; extern bmp388_calib_param_t bmp388_cal;
} // extern "C" } // extern "C"

View file

@ -346,7 +346,7 @@ const uint32_t baudRates[] = {0, 9600, 19200, 38400, 57600, 115200, 230400, 2500
400000, 460800, 500000, 921600, 1000000, 1500000, 2000000, 2470000}; // see baudRate_e 400000, 460800, 500000, 921600, 1000000, 1500000, 2000000, 2470000}; // see baudRate_e
uint8_t debugMode = 0; uint8_t debugMode = 0;
int16_t debug[DEBUG16_VALUE_COUNT]; int16_t debug[DEBUG16_VALUE_COUNT];
int32_t blackboxHeaderBudget; extern int32_t blackboxHeaderBudget;
gpsSolutionData_t gpsSol; gpsSolutionData_t gpsSol;
int32_t GPS_home[2]; int32_t GPS_home[2];

View file

@ -385,7 +385,7 @@ INSTANTIATE_TEST_SUITE_P(
// STUBS // STUBS
extern "C" { extern "C" {
boxBitmask_t rcModeActivationMask; extern boxBitmask_t rcModeActivationMask;
float rcCommand[4]; float rcCommand[4];
float rcData[MAX_SUPPORTED_RC_CHANNEL_COUNT]; float rcData[MAX_SUPPORTED_RC_CHANNEL_COUNT];

View file

@ -303,7 +303,7 @@ uint8_t stateFlags = 0;
uint16_t flightModeFlags = 0; uint16_t flightModeFlags = 0;
float rcCommand[4]; float rcCommand[4];
float rcData[MAX_SUPPORTED_RC_CHANNEL_COUNT]; float rcData[MAX_SUPPORTED_RC_CHANNEL_COUNT];
boxBitmask_t rcModeActivationMask; extern boxBitmask_t rcModeActivationMask;
gpsSolutionData_t gpsSol; gpsSolutionData_t gpsSol;
batteryState_e getBatteryState(void) batteryState_e getBatteryState(void)

View file

@ -70,7 +70,7 @@ extern "C" {
float rMat[3][3]; float rMat[3][3];
pidProfile_t *currentPidProfile; pidProfile_t *currentPidProfile;
float rcData[MAX_SUPPORTED_RC_CHANNEL_COUNT]; extern float rcData[MAX_SUPPORTED_RC_CHANNEL_COUNT];
uint8_t GPS_numSat; uint8_t GPS_numSat;
uint16_t GPS_distanceToHome; uint16_t GPS_distanceToHome;
int16_t GPS_directionToHome; int16_t GPS_directionToHome;
@ -104,7 +104,7 @@ extern "C" {
extern "C" { extern "C" {
PG_REGISTER(flight3DConfig_t, flight3DConfig, PG_MOTOR_3D_CONFIG, 0); PG_REGISTER(flight3DConfig_t, flight3DConfig, PG_MOTOR_3D_CONFIG, 0);
boxBitmask_t rcModeActivationMask; extern boxBitmask_t rcModeActivationMask;
int16_t debug[DEBUG16_VALUE_COUNT]; int16_t debug[DEBUG16_VALUE_COUNT];
uint8_t debugMode = 0; uint8_t debugMode = 0;

View file

@ -43,7 +43,7 @@ extern "C" {
PG_REGISTER(flight3DConfig_t, flight3DConfig, PG_MOTOR_3D_CONFIG, 0); PG_REGISTER(flight3DConfig_t, flight3DConfig, PG_MOTOR_3D_CONFIG, 0);
PG_REGISTER(failsafeConfig_t, failsafeConfig, PG_FAILSAFE_CONFIG, 0); PG_REGISTER(failsafeConfig_t, failsafeConfig, PG_FAILSAFE_CONFIG, 0);
boxBitmask_t rcModeActivationMask; extern boxBitmask_t rcModeActivationMask;
int16_t debug[DEBUG16_VALUE_COUNT]; int16_t debug[DEBUG16_VALUE_COUNT];
uint8_t debugMode = 0; uint8_t debugMode = 0;
uint8_t armingFlags = 0; uint8_t armingFlags = 0;

View file

@ -38,7 +38,7 @@ extern "C" {
#include "pg/pg_ids.h" #include "pg/pg_ids.h"
#include "io/beeper.h" #include "io/beeper.h"
boxBitmask_t rcModeActivationMask; extern boxBitmask_t rcModeActivationMask;
int16_t debug[DEBUG16_VALUE_COUNT]; int16_t debug[DEBUG16_VALUE_COUNT];
uint8_t debugMode = 0; uint8_t debugMode = 0;
uint8_t armingFlags = 0; uint8_t armingFlags = 0;

View file

@ -55,8 +55,8 @@ const int TEST_UPDATE_OSD_TIME = 30;
#define TASK_PERIOD_HZ(hz) (1000000 / (hz)) #define TASK_PERIOD_HZ(hz) (1000000 / (hz))
extern "C" { extern "C" {
task_t * unittest_scheduler_selectedTask; extern task_t * unittest_scheduler_selectedTask;
uint8_t unittest_scheduler_selectedTaskDynPrio; extern uint8_t unittest_scheduler_selectedTaskDynPrio;
timeDelta_t unittest_scheduler_taskRequiredTimeUs; timeDelta_t unittest_scheduler_taskRequiredTimeUs;
bool taskGyroRan = false; bool taskGyroRan = false;
bool taskFilterRan = false; bool taskFilterRan = false;

View file

@ -256,7 +256,7 @@ extern "C" {
gpsSolutionData_t gpsSol; gpsSolutionData_t gpsSol;
attitudeEulerAngles_t attitude = { { 0, 0, 0 } }; attitudeEulerAngles_t attitude = { { 0, 0, 0 } };
uint8_t responseBuffer[MSP_TLM_OUTBUF_SIZE]; extern uint8_t responseBuffer[MSP_TLM_OUTBUF_SIZE];
uint32_t micros(void) {return dummyTimeUs;} uint32_t micros(void) {return dummyTimeUs;}
uint32_t microsISR(void) {return micros();} uint32_t microsISR(void) {return micros();}

View file

@ -18,6 +18,7 @@
#pragma once #pragma once
#include <string.h> #include <string.h>
#include <stdarg.h>
extern "C" { extern "C" {
#include "drivers/display.h" #include "drivers/display.h"

View file

@ -71,7 +71,7 @@ extern "C" {
PG_REGISTER(imuConfig_t, imuConfig, PG_IMU_CONFIG, 0); PG_REGISTER(imuConfig_t, imuConfig, PG_IMU_CONFIG, 0);
PG_REGISTER(gpsRescueConfig_t, gpsRescueConfig, PG_GPS_CONFIG, 0); PG_REGISTER(gpsRescueConfig_t, gpsRescueConfig, PG_GPS_CONFIG, 0);
float rcCommand[4]; extern float rcCommand[4];
float rcData[MAX_SUPPORTED_RC_CHANNEL_COUNT]; float rcData[MAX_SUPPORTED_RC_CHANNEL_COUNT];
uint16_t averageSystemLoadPercent = 0; uint16_t averageSystemLoadPercent = 0;
uint8_t cliMode = 0; uint8_t cliMode = 0;