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

Converted 'SKIP_' defines to 'USE_'.

This commit is contained in:
mikeller 2018-10-25 00:38:05 +13:00
parent 05f935d38e
commit a03f30efa0
13 changed files with 30 additions and 31 deletions

View file

@ -134,7 +134,7 @@ STATIC_UNIT_TESTED void imuComputeRotationMatrix(void){
rMat[2][1] = 2.0f * (qP.yz - -qP.wx); rMat[2][1] = 2.0f * (qP.yz - -qP.wx);
rMat[2][2] = 1.0f - 2.0f * qP.xx - 2.0f * qP.yy; rMat[2][2] = 1.0f - 2.0f * qP.xx - 2.0f * qP.yy;
#if defined(SIMULATOR_BUILD) && defined(SKIP_IMU_CALC) && !defined(SET_IMU_FROM_EULER) #if defined(SIMULATOR_BUILD) && !defined(USE_IMU_CALC) && !defined(SET_IMU_FROM_EULER)
rMat[1][0] = -2.0f * (qP.xy - -qP.wz); rMat[1][0] = -2.0f * (qP.xy - -qP.wz);
rMat[2][0] = -2.0f * (qP.xz + -qP.wy); rMat[2][0] = -2.0f * (qP.xz + -qP.wy);
#endif #endif
@ -472,7 +472,7 @@ static void imuCalculateEstimatedAttitude(timeUs_t currentTimeUs)
} }
#endif #endif
#if defined(SIMULATOR_BUILD) && defined(SKIP_IMU_CALC) #if defined(SIMULATOR_BUILD) && !defined(USE_IMU_CALC)
UNUSED(imuMahonyAHRSupdate); UNUSED(imuMahonyAHRSupdate);
UNUSED(imuIsAccelerometerHealthy); UNUSED(imuIsAccelerometerHealthy);
UNUSED(useAcc); UNUSED(useAcc);

View file

@ -1094,7 +1094,7 @@ static void cliSerial(char *cmdline)
} }
#ifndef SKIP_SERIAL_PASSTHROUGH #if defined(USE_SERIAL_PASSTHROUGH)
#ifdef USE_PINIO #ifdef USE_PINIO
static void cbCtrlLine(void *context, uint16_t ctrl) static void cbCtrlLine(void *context, uint16_t ctrl)
{ {
@ -3608,7 +3608,7 @@ static void cliStatus(char *cmdline)
cliPrintLinefeed(); cliPrintLinefeed();
} }
#ifndef SKIP_TASK_STATISTICS #if defined(USE_TASK_STATISTICS)
static void cliTasks(char *cmdline) static void cliTasks(char *cmdline)
{ {
UNUSED(cmdline); UNUSED(cmdline);
@ -4522,7 +4522,7 @@ const clicmd_t cmdTable[] = {
CLI_COMMAND_DEF("sd_info", "sdcard info", NULL, cliSdInfo), CLI_COMMAND_DEF("sd_info", "sdcard info", NULL, cliSdInfo),
#endif #endif
CLI_COMMAND_DEF("serial", "configure serial ports", NULL, cliSerial), CLI_COMMAND_DEF("serial", "configure serial ports", NULL, cliSerial),
#ifndef SKIP_SERIAL_PASSTHROUGH #if defined(USE_SERIAL_PASSTHROUGH)
CLI_COMMAND_DEF("serialpassthrough", "passthrough serial data to port", "<id> [baud] [mode] [DTR PINIO]: passthrough to serial", cliSerialPassthrough), CLI_COMMAND_DEF("serialpassthrough", "passthrough serial data to port", "<id> [baud] [mode] [DTR PINIO]: passthrough to serial", cliSerialPassthrough),
#endif #endif
#ifdef USE_SERVOS #ifdef USE_SERVOS
@ -4539,7 +4539,7 @@ const clicmd_t cmdTable[] = {
"\treverse <servo> <source> r|n", cliServoMix), "\treverse <servo> <source> r|n", cliServoMix),
#endif #endif
CLI_COMMAND_DEF("status", "show status", NULL, cliStatus), CLI_COMMAND_DEF("status", "show status", NULL, cliStatus),
#ifndef SKIP_TASK_STATISTICS #if defined(USE_TASK_STATISTICS)
CLI_COMMAND_DEF("tasks", "show task stats", NULL, cliTasks), CLI_COMMAND_DEF("tasks", "show task stats", NULL, cliTasks),
#endif #endif
#ifdef USE_TIMER_MGMT #ifdef USE_TIMER_MGMT

View file

@ -1064,7 +1064,7 @@ const clivalue_t valueTable[] = {
#endif #endif
// PG_SYSTEM_CONFIG // PG_SYSTEM_CONFIG
#ifndef SKIP_TASK_STATISTICS #if defined(USE_TASK_STATISTICS)
{ "task_statistics", VAR_INT8 | MASTER_VALUE | MODE_LOOKUP, .config.lookup = { TABLE_OFF_ON }, PG_SYSTEM_CONFIG, offsetof(systemConfig_t, task_statistics) }, { "task_statistics", VAR_INT8 | MASTER_VALUE | MODE_LOOKUP, .config.lookup = { TABLE_OFF_ON }, PG_SYSTEM_CONFIG, offsetof(systemConfig_t, task_statistics) },
#endif #endif
{ "debug_mode", VAR_UINT8 | MASTER_VALUE | MODE_LOOKUP, .config.lookup = { TABLE_DEBUG }, PG_SYSTEM_CONFIG, offsetof(systemConfig_t, debug_mode) }, { "debug_mode", VAR_UINT8 | MASTER_VALUE | MODE_LOOKUP, .config.lookup = { TABLE_DEBUG }, PG_SYSTEM_CONFIG, offsetof(systemConfig_t, debug_mode) },

View file

@ -526,7 +526,7 @@ static void showSensorsPage(void)
} }
#ifndef SKIP_TASK_STATISTICS #if defined(USE_TASK_STATISTICS)
static void showTasksPage(void) static void showTasksPage(void)
{ {
uint8_t rowIndex = PAGE_TITLE_LINE_COUNT; uint8_t rowIndex = PAGE_TITLE_LINE_COUNT;
@ -576,7 +576,7 @@ static const pageEntry_t pages[PAGE_COUNT] = {
{ PAGE_RX, "RX", showRxPage, PAGE_FLAGS_NONE }, { PAGE_RX, "RX", showRxPage, PAGE_FLAGS_NONE },
{ PAGE_BATTERY, "BATTERY", showBatteryPage, PAGE_FLAGS_NONE }, { PAGE_BATTERY, "BATTERY", showBatteryPage, PAGE_FLAGS_NONE },
{ PAGE_SENSORS, "SENSORS", showSensorsPage, PAGE_FLAGS_NONE }, { PAGE_SENSORS, "SENSORS", showSensorsPage, PAGE_FLAGS_NONE },
#ifndef SKIP_TASK_STATISTICS #if defined(USE_TASK_STATISTICS)
{ PAGE_TASKS, "TASKS", showTasksPage, PAGE_FLAGS_NONE }, { PAGE_TASKS, "TASKS", showTasksPage, PAGE_FLAGS_NONE },
#endif #endif
#ifdef ENABLE_DEBUG_DASHBOARD_PAGE #ifdef ENABLE_DEBUG_DASHBOARD_PAGE

View file

@ -43,7 +43,7 @@ typedef enum {
PAGE_SENSORS, PAGE_SENSORS,
PAGE_RX, PAGE_RX,
PAGE_PROFILE, PAGE_PROFILE,
#ifndef SKIP_TASK_STATISTICS #if defined(USE_TASK_STATISTICS)
PAGE_TASKS, PAGE_TASKS,
#endif #endif
#ifdef USE_GPS #ifdef USE_GPS

View file

@ -505,7 +505,7 @@ void waitForSerialPortToFinishTransmitting(serialPort_t *serialPort)
}; };
} }
#if defined(USE_GPS) || ! defined(SKIP_SERIAL_PASSTHROUGH) #if defined(USE_GPS) || defined(USE_SERIAL_PASSTHROUGH)
// Default data consumer for serialPassThrough. // Default data consumer for serialPassThrough.
static void nopConsumer(uint8_t data) static void nopConsumer(uint8_t data)
{ {

View file

@ -138,7 +138,7 @@ void taskSystemLoad(timeUs_t currentTimeUs)
#endif #endif
} }
#ifndef SKIP_TASK_STATISTICS #if defined(USE_TASK_STATISTICS)
#define MOVING_SUM_COUNT 32 #define MOVING_SUM_COUNT 32
timeUs_t checkFuncMaxExecutionTime; timeUs_t checkFuncMaxExecutionTime;
timeUs_t checkFuncTotalExecutionTime; timeUs_t checkFuncTotalExecutionTime;
@ -206,9 +206,7 @@ void schedulerSetCalulateTaskStatistics(bool calculateTaskStatisticsToUse)
void schedulerResetTaskStatistics(cfTaskId_e taskId) void schedulerResetTaskStatistics(cfTaskId_e taskId)
{ {
#ifdef SKIP_TASK_STATISTICS #if defined(USE_TASK_STATISTICS)
UNUSED(taskId);
#else
if (taskId == TASK_SELF) { if (taskId == TASK_SELF) {
currentTask->movingSumExecutionTime = 0; currentTask->movingSumExecutionTime = 0;
currentTask->totalExecutionTime = 0; currentTask->totalExecutionTime = 0;
@ -218,19 +216,21 @@ void schedulerResetTaskStatistics(cfTaskId_e taskId)
cfTasks[taskId].totalExecutionTime = 0; cfTasks[taskId].totalExecutionTime = 0;
cfTasks[taskId].maxExecutionTime = 0; cfTasks[taskId].maxExecutionTime = 0;
} }
#else
UNUSED(taskId);
#endif #endif
} }
void schedulerResetTaskMaxExecutionTime(cfTaskId_e taskId) void schedulerResetTaskMaxExecutionTime(cfTaskId_e taskId)
{ {
#ifdef SKIP_TASK_STATISTICS #if defined(USE_TASK_STATISTICS)
UNUSED(taskId);
#else
if (taskId == TASK_SELF) { if (taskId == TASK_SELF) {
currentTask->maxExecutionTime = 0; currentTask->maxExecutionTime = 0;
} else if (taskId < TASK_COUNT) { } else if (taskId < TASK_COUNT) {
cfTasks[taskId].maxExecutionTime = 0; cfTasks[taskId].maxExecutionTime = 0;
} }
#else
UNUSED(taskId);
#endif #endif
} }
@ -279,7 +279,7 @@ FAST_CODE void scheduler(void)
#if defined(SCHEDULER_DEBUG) #if defined(SCHEDULER_DEBUG)
DEBUG_SET(DEBUG_SCHEDULER, 3, micros() - currentTimeBeforeCheckFuncCall); DEBUG_SET(DEBUG_SCHEDULER, 3, micros() - currentTimeBeforeCheckFuncCall);
#endif #endif
#ifndef SKIP_TASK_STATISTICS #if defined(USE_TASK_STATISTICS)
if (calculateTaskStatistics) { if (calculateTaskStatistics) {
const uint32_t checkFuncExecutionTime = micros() - currentTimeBeforeCheckFuncCall; const uint32_t checkFuncExecutionTime = micros() - currentTimeBeforeCheckFuncCall;
checkFuncMovingSumExecutionTime += checkFuncExecutionTime - checkFuncMovingSumExecutionTime / MOVING_SUM_COUNT; checkFuncMovingSumExecutionTime += checkFuncExecutionTime - checkFuncMovingSumExecutionTime / MOVING_SUM_COUNT;
@ -328,9 +328,7 @@ FAST_CODE void scheduler(void)
selectedTask->dynamicPriority = 0; selectedTask->dynamicPriority = 0;
// Execute task // Execute task
#ifdef SKIP_TASK_STATISTICS #if defined(USE_TASK_STATISTICS)
selectedTask->taskFunc(currentTimeUs);
#else
if (calculateTaskStatistics) { if (calculateTaskStatistics) {
const timeUs_t currentTimeBeforeTaskCall = micros(); const timeUs_t currentTimeBeforeTaskCall = micros();
selectedTask->taskFunc(currentTimeBeforeTaskCall); selectedTask->taskFunc(currentTimeBeforeTaskCall);
@ -338,11 +336,12 @@ FAST_CODE void scheduler(void)
selectedTask->movingSumExecutionTime += taskExecutionTime - selectedTask->movingSumExecutionTime / MOVING_SUM_COUNT; selectedTask->movingSumExecutionTime += taskExecutionTime - selectedTask->movingSumExecutionTime / MOVING_SUM_COUNT;
selectedTask->totalExecutionTime += taskExecutionTime; // time consumed by scheduler + task selectedTask->totalExecutionTime += taskExecutionTime; // time consumed by scheduler + task
selectedTask->maxExecutionTime = MAX(selectedTask->maxExecutionTime, taskExecutionTime); selectedTask->maxExecutionTime = MAX(selectedTask->maxExecutionTime, taskExecutionTime);
} else { } else
#endif
{
selectedTask->taskFunc(currentTimeUs); selectedTask->taskFunc(currentTimeUs);
} }
#endif
#if defined(SCHEDULER_DEBUG) #if defined(SCHEDULER_DEBUG)
DEBUG_SET(DEBUG_SCHEDULER, 2, micros() - currentTimeUs - taskExecutionTime); // time spent in scheduler DEBUG_SET(DEBUG_SCHEDULER, 2, micros() - currentTimeUs - taskExecutionTime); // time spent in scheduler
} else { } else {

View file

@ -156,7 +156,7 @@ typedef struct {
timeUs_t lastExecutedAt; // last time of invocation timeUs_t lastExecutedAt; // last time of invocation
timeUs_t lastSignaledAt; // time of invocation event for event-driven tasks timeUs_t lastSignaledAt; // time of invocation event for event-driven tasks
#ifndef SKIP_TASK_STATISTICS #if defined(USE_TASK_STATISTICS)
// Statistics // Statistics
timeUs_t movingSumExecutionTime; // moving sum over 32 samples timeUs_t movingSumExecutionTime; // moving sum over 32 samples
timeUs_t maxExecutionTime; timeUs_t maxExecutionTime;

View file

@ -108,7 +108,6 @@
#undef USE_MAG #undef USE_MAG
#ifdef CC3D_OPBL #ifdef CC3D_OPBL
#define SKIP_CLI_COMMAND_HELP
//#undef USE_SERVOS //#undef USE_SERVOS
#undef USE_BARO #undef USE_BARO
#undef USE_RANGEFINDER #undef USE_RANGEFINDER

View file

@ -103,8 +103,6 @@
#ifdef USE_SERIAL_RX #ifdef USE_SERIAL_RX
#undef USE_SERIAL_RX #undef USE_SERIAL_RX
#endif #endif
//#undef SKIP_TASK_STATISTICS
#else #else
#define DEFAULT_RX_FEATURE FEATURE_RX_PPM #define DEFAULT_RX_FEATURE FEATURE_RX_PPM
@ -114,7 +112,7 @@
#define BRUSHED_MOTORS #define BRUSHED_MOTORS
#define DEFAULT_FEATURES FEATURE_MOTOR_STOP #define DEFAULT_FEATURES FEATURE_MOTOR_STOP
#define SKIP_SERIAL_PASSTHROUGH #undef USE_SERIAL_PASSTHROUGH
#undef USE_CLI #undef USE_CLI
// Since the CJMCU PCB has holes for 4 motors in each corner we can save same flash space by disabling support for other mixers. // Since the CJMCU PCB has holes for 4 motors in each corner we can save same flash space by disabling support for other mixers.

View file

@ -114,7 +114,7 @@ void updateState(const fdm_packet* pkt) {
fakeGyroSet(fakeGyroDev, x, y, z); fakeGyroSet(fakeGyroDev, x, y, z);
// printf("[gyr]%lf,%lf,%lf\n", pkt->imu_angular_velocity_rpy[0], pkt->imu_angular_velocity_rpy[1], pkt->imu_angular_velocity_rpy[2]); // printf("[gyr]%lf,%lf,%lf\n", pkt->imu_angular_velocity_rpy[0], pkt->imu_angular_velocity_rpy[1], pkt->imu_angular_velocity_rpy[2]);
#if defined(SKIP_IMU_CALC) #if !defined(USE_IMU_CALC)
#if defined(SET_IMU_FROM_EULER) #if defined(SET_IMU_FROM_EULER)
// set from Euler // set from Euler
double qw = pkt->imu_orientation_quat[0]; double qw = pkt->imu_orientation_quat[0];

View file

@ -33,7 +33,7 @@
// use simulatior's attitude directly // use simulatior's attitude directly
// disable this if wants to test AHRS algorithm // disable this if wants to test AHRS algorithm
#define SKIP_IMU_CALC #undef USE_IMU_CALC
//#define SIMULATOR_ACC_SYNC //#define SIMULATOR_ACC_SYNC
//#define SIMULATOR_GYRO_SYNC //#define SIMULATOR_GYRO_SYNC

View file

@ -124,7 +124,10 @@
#define USE_BRUSHED_ESC_AUTODETECT // Detect if brushed motors are connected and set defaults appropriately to avoid motors spinning on boot #define USE_BRUSHED_ESC_AUTODETECT // Detect if brushed motors are connected and set defaults appropriately to avoid motors spinning on boot
#define USE_CLI #define USE_CLI
#define USE_SERIAL_PASSTHROUGH
#define USE_TASK_STATISTICS
#define USE_GYRO_REGISTER_DUMP // Adds gyroregisters command to cli to dump configured register values #define USE_GYRO_REGISTER_DUMP // Adds gyroregisters command to cli to dump configured register values
#define USE_IMU_CALC
#define USE_PPM #define USE_PPM
#define USE_PWM #define USE_PWM
#define USE_SERIAL_RX #define USE_SERIAL_RX