mirror of
https://github.com/betaflight/betaflight.git
synced 2025-07-13 19:40:31 +03:00
refactor motor idle, rename dshot_idle_value to motor_idle (#13936)
* use idleOffset, simplify idle : check PWM idle * remove get for dshot idle and calculate it once only * fixes from reviews, thanks * use motor_idle for CLI name * use motorConfig->motorIdle not idleOffset * rename dshotmotorIdle variable to motorIdlePercent * small comment improvement
This commit is contained in:
parent
10d5963d24
commit
5ffeea6ab1
17 changed files with 29 additions and 66 deletions
|
@ -1406,7 +1406,6 @@ static bool blackboxWriteSysinfo(void)
|
|||
BLACKBOX_PRINT_HEADER_LINE("I interval", "%d", blackboxIInterval);
|
||||
BLACKBOX_PRINT_HEADER_LINE("P interval", "%d", blackboxPInterval);
|
||||
BLACKBOX_PRINT_HEADER_LINE("P ratio", "%d", (uint16_t)(blackboxIInterval / blackboxPInterval));
|
||||
BLACKBOX_PRINT_HEADER_LINE("minthrottle", "%d", motorConfig()->minthrottle);
|
||||
BLACKBOX_PRINT_HEADER_LINE("maxthrottle", "%d", motorConfig()->maxthrottle);
|
||||
BLACKBOX_PRINT_HEADER_LINE("gyro_scale","0x%x", castFloatBytesToInt(1.0f));
|
||||
BLACKBOX_PRINT_HEADER_LINE("motorOutput", "%d,%d", motorOutputLowInt, motorOutputHighInt);
|
||||
|
@ -1632,7 +1631,7 @@ static bool blackboxWriteSysinfo(void)
|
|||
BLACKBOX_PRINT_HEADER_LINE(PARAM_NAME_USE_UNSYNCED_PWM, "%d", motorConfig()->dev.useUnsyncedPwm);
|
||||
BLACKBOX_PRINT_HEADER_LINE(PARAM_NAME_MOTOR_PWM_PROTOCOL, "%d", motorConfig()->dev.motorPwmProtocol);
|
||||
BLACKBOX_PRINT_HEADER_LINE(PARAM_NAME_MOTOR_PWM_RATE, "%d", motorConfig()->dev.motorPwmRate);
|
||||
BLACKBOX_PRINT_HEADER_LINE(PARAM_NAME_DSHOT_IDLE_VALUE, "%d", motorConfig()->digitalIdleOffsetValue);
|
||||
BLACKBOX_PRINT_HEADER_LINE(PARAM_NAME_MOTOR_IDLE, "%d", motorConfig()->motorIdle);
|
||||
BLACKBOX_PRINT_HEADER_LINE(PARAM_NAME_DEBUG_MODE, "%d", debugMode);
|
||||
BLACKBOX_PRINT_HEADER_LINE("features", "%d", featureConfig()->enabledFeatures);
|
||||
|
||||
|
|
|
@ -857,12 +857,11 @@ const clivalue_t valueTable[] = {
|
|||
#endif
|
||||
|
||||
// PG_MOTOR_CONFIG
|
||||
{ "min_throttle", VAR_UINT16 | MASTER_VALUE, .config.minmaxUnsigned = { PWM_PULSE_MIN, PWM_PULSE_MAX }, PG_MOTOR_CONFIG, offsetof(motorConfig_t, minthrottle) },
|
||||
{ "max_throttle", VAR_UINT16 | MASTER_VALUE, .config.minmaxUnsigned = { PWM_PULSE_MIN, PWM_PULSE_MAX }, PG_MOTOR_CONFIG, offsetof(motorConfig_t, maxthrottle) },
|
||||
{ "min_command", VAR_UINT16 | MASTER_VALUE, .config.minmaxUnsigned = { PWM_PULSE_MIN, PWM_PULSE_MAX }, PG_MOTOR_CONFIG, offsetof(motorConfig_t, mincommand) },
|
||||
{ "motor_kv", VAR_UINT16 | HARDWARE_VALUE, .config.minmaxUnsigned = { 1, 40000 }, PG_MOTOR_CONFIG, offsetof(motorConfig_t, kv) },
|
||||
{ PARAM_NAME_MOTOR_IDLE, VAR_UINT16 | MASTER_VALUE, .config.minmaxUnsigned = { 0, 2000 }, PG_MOTOR_CONFIG, offsetof(motorConfig_t, motorIdle) },
|
||||
#ifdef USE_DSHOT
|
||||
{ PARAM_NAME_DSHOT_IDLE_VALUE, VAR_UINT16 | MASTER_VALUE, .config.minmaxUnsigned = { 0, 2000 }, PG_MOTOR_CONFIG, offsetof(motorConfig_t, digitalIdleOffsetValue) },
|
||||
#ifdef USE_DSHOT_DMAR
|
||||
{ "dshot_burst", VAR_UINT8 | HARDWARE_VALUE | MODE_LOOKUP, .config.lookup = { TABLE_OFF_ON_AUTO }, PG_MOTOR_CONFIG, offsetof(motorConfig_t, dev.useBurstDshot) },
|
||||
#endif
|
||||
|
@ -874,7 +873,7 @@ const clivalue_t valueTable[] = {
|
|||
{ "dshot_bitbang", VAR_UINT8 | HARDWARE_VALUE | MODE_LOOKUP, .config.lookup = { TABLE_OFF_ON_AUTO }, PG_MOTOR_CONFIG, offsetof(motorConfig_t, dev.useDshotBitbang) },
|
||||
{ "dshot_bitbang_timer", VAR_UINT8 | HARDWARE_VALUE | MODE_LOOKUP, .config.lookup = { TABLE_DSHOT_BITBANGED_TIMER }, PG_MOTOR_CONFIG, offsetof(motorConfig_t, dev.useDshotBitbangedTimer) },
|
||||
#endif
|
||||
#endif
|
||||
#endif // USE_DSHOT
|
||||
{ PARAM_NAME_USE_UNSYNCED_PWM, VAR_UINT8 | MASTER_VALUE | MODE_LOOKUP, .config.lookup = { TABLE_OFF_ON }, PG_MOTOR_CONFIG, offsetof(motorConfig_t, dev.useUnsyncedPwm) },
|
||||
{ PARAM_NAME_MOTOR_PWM_PROTOCOL, VAR_UINT8 | MASTER_VALUE | MODE_LOOKUP, .config.lookup = { TABLE_MOTOR_PWM_PROTOCOL }, PG_MOTOR_CONFIG, offsetof(motorConfig_t, dev.motorPwmProtocol) },
|
||||
{ PARAM_NAME_MOTOR_PWM_RATE, VAR_UINT16 | MASTER_VALUE, .config.minmaxUnsigned = { 200, 32000 }, PG_MOTOR_CONFIG, offsetof(motorConfig_t, dev.motorPwmRate) },
|
||||
|
|
|
@ -127,8 +127,7 @@ CMS_Menu cmsx_menuRcPreview = {
|
|||
.entries = cmsx_menuRcEntries
|
||||
};
|
||||
|
||||
static uint16_t motorConfig_minthrottle;
|
||||
static uint8_t motorConfig_digitalIdleOffsetValue;
|
||||
static uint8_t motorConfig_motorIdle;
|
||||
static uint8_t rxConfig_fpvCamAngleDegrees;
|
||||
static uint8_t mixerConfig_crashflip_rate;
|
||||
|
||||
|
@ -136,8 +135,7 @@ static const void *cmsx_menuMiscOnEnter(displayPort_t *pDisp)
|
|||
{
|
||||
UNUSED(pDisp);
|
||||
|
||||
motorConfig_minthrottle = motorConfig()->minthrottle;
|
||||
motorConfig_digitalIdleOffsetValue = motorConfig()->digitalIdleOffsetValue / 10;
|
||||
motorConfig_motorIdle = motorConfig()->motorIdle / 10;
|
||||
rxConfig_fpvCamAngleDegrees = rxConfig()->fpvCamAngleDegrees;
|
||||
mixerConfig_crashflip_rate = mixerConfig()->crashflip_rate;
|
||||
|
||||
|
@ -149,8 +147,7 @@ static const void *cmsx_menuMiscOnExit(displayPort_t *pDisp, const OSD_Entry *se
|
|||
UNUSED(pDisp);
|
||||
UNUSED(self);
|
||||
|
||||
motorConfigMutable()->minthrottle = motorConfig_minthrottle;
|
||||
motorConfigMutable()->digitalIdleOffsetValue = 10 * motorConfig_digitalIdleOffsetValue;
|
||||
motorConfigMutable()->motorIdle = 10 * motorConfig_motorIdle;
|
||||
rxConfigMutable()->fpvCamAngleDegrees = rxConfig_fpvCamAngleDegrees;
|
||||
mixerConfigMutable()->crashflip_rate = mixerConfig_crashflip_rate;
|
||||
|
||||
|
@ -161,11 +158,10 @@ static const OSD_Entry menuMiscEntries[]=
|
|||
{
|
||||
{ "-- MISC --", OME_Label, NULL, NULL },
|
||||
|
||||
{ "MIN THR", OME_UINT16 | REBOOT_REQUIRED, NULL, &(OSD_UINT16_t){ &motorConfig_minthrottle, 1000, 2000, 1 } },
|
||||
{ "DIGITAL IDLE", OME_UINT8 | REBOOT_REQUIRED, NULL, &(OSD_UINT8_t) { &motorConfig_digitalIdleOffsetValue, 0, 200, 1 } },
|
||||
{ "FPV CAM ANGLE", OME_UINT8, NULL, &(OSD_UINT8_t) { &rxConfig_fpvCamAngleDegrees, 0, 90, 1 } },
|
||||
{ "IDLE OFFSET", OME_UINT8 | REBOOT_REQUIRED, NULL, &(OSD_UINT8_t) { &motorConfig_motorIdle, 0, 200, 1 } },
|
||||
{ "FPV CAM ANGLE", OME_UINT8, NULL, &(OSD_UINT8_t) { &rxConfig_fpvCamAngleDegrees, 0, 90, 1 } },
|
||||
{ "CRASHFLIP RATE", OME_UINT8 | REBOOT_REQUIRED, NULL, &(OSD_UINT8_t) { &mixerConfig_crashflip_rate, 0, 100, 1 } },
|
||||
{ "RC PREV", OME_Submenu, cmsMenuChange, &cmsx_menuRcPreview},
|
||||
{ "RC PREV", OME_Submenu, cmsMenuChange, &cmsx_menuRcPreview},
|
||||
#ifdef USE_GPS_LAP_TIMER
|
||||
{ "GPS LAP TIMER", OME_Submenu, cmsMenuChange, &cms_menuGpsLapTimer },
|
||||
#endif // USE_GPS_LAP_TIMER
|
||||
|
|
|
@ -149,11 +149,6 @@ uint8_t getCurrentControlRateProfileIndex(void)
|
|||
return systemConfig()->activeRateProfile;
|
||||
}
|
||||
|
||||
uint16_t getCurrentMinthrottle(void)
|
||||
{
|
||||
return motorConfig()->minthrottle;
|
||||
}
|
||||
|
||||
void resetConfig(void)
|
||||
{
|
||||
pgResetAll();
|
||||
|
|
|
@ -83,8 +83,6 @@ void changeControlRateProfile(uint8_t profileIndex);
|
|||
|
||||
bool canSoftwareSerialBeUsed(void);
|
||||
|
||||
uint16_t getCurrentMinthrottle(void);
|
||||
|
||||
void resetConfig(void);
|
||||
void targetConfiguration(void);
|
||||
void targetValidateConfiguration(void);
|
||||
|
|
|
@ -58,14 +58,15 @@
|
|||
void dshotInitEndpoints(const motorConfig_t *motorConfig, float outputLimit, float *outputLow, float *outputHigh, float *disarm, float *deadbandMotor3dHigh, float *deadbandMotor3dLow)
|
||||
{
|
||||
float outputLimitOffset = DSHOT_RANGE * (1 - outputLimit);
|
||||
const float motorIdlePercent = CONVERT_PARAMETER_TO_PERCENT(motorConfig->motorIdle * 0.01f);
|
||||
*disarm = DSHOT_CMD_MOTOR_STOP;
|
||||
if (featureIsEnabled(FEATURE_3D)) {
|
||||
*outputLow = DSHOT_MIN_THROTTLE + getDigitalIdleOffset(motorConfig) * (DSHOT_3D_FORWARD_MIN_THROTTLE - 1 - DSHOT_MIN_THROTTLE);
|
||||
*outputLow = DSHOT_MIN_THROTTLE + motorIdlePercent * (DSHOT_3D_FORWARD_MIN_THROTTLE - 1 - DSHOT_MIN_THROTTLE);
|
||||
*outputHigh = DSHOT_MAX_THROTTLE - outputLimitOffset / 2;
|
||||
*deadbandMotor3dHigh = DSHOT_3D_FORWARD_MIN_THROTTLE + getDigitalIdleOffset(motorConfig) * (DSHOT_MAX_THROTTLE - DSHOT_3D_FORWARD_MIN_THROTTLE);
|
||||
*deadbandMotor3dHigh = DSHOT_3D_FORWARD_MIN_THROTTLE + motorIdlePercent * (DSHOT_MAX_THROTTLE - DSHOT_3D_FORWARD_MIN_THROTTLE);
|
||||
*deadbandMotor3dLow = DSHOT_3D_FORWARD_MIN_THROTTLE - 1 - outputLimitOffset / 2;
|
||||
} else {
|
||||
*outputLow = DSHOT_MIN_THROTTLE + getDigitalIdleOffset(motorConfig) * DSHOT_RANGE;
|
||||
*outputLow = DSHOT_MIN_THROTTLE + motorIdlePercent * DSHOT_RANGE;
|
||||
*outputHigh = DSHOT_MAX_THROTTLE - outputLimitOffset;
|
||||
}
|
||||
}
|
||||
|
|
|
@ -147,8 +147,9 @@ static void analogInitEndpoints(const motorConfig_t *motorConfig, float outputLi
|
|||
*deadbandMotor3dLow = flight3DConfig()->deadband3d_low;
|
||||
} else {
|
||||
*disarm = motorConfig->mincommand;
|
||||
*outputLow = motorConfig->minthrottle;
|
||||
*outputHigh = motorConfig->maxthrottle - ((motorConfig->maxthrottle - motorConfig->minthrottle) * (1 - outputLimit));
|
||||
const float minThrottle = motorConfig->mincommand + motorConfig->motorIdle * 0.1f;
|
||||
*outputLow = minThrottle;
|
||||
*outputHigh = motorConfig->maxthrottle - ((motorConfig->maxthrottle - minThrottle) * (1 - outputLimit));
|
||||
}
|
||||
}
|
||||
|
||||
|
@ -403,9 +404,4 @@ bool isDshotBitbangActive(const motorDevConfig_t *motorDevConfig)
|
|||
#endif
|
||||
}
|
||||
#endif
|
||||
|
||||
float getDigitalIdleOffset(const motorConfig_t *motorConfig)
|
||||
{
|
||||
return CONVERT_PARAMETER_TO_PERCENT(motorConfig->digitalIdleOffsetValue * 0.01f);
|
||||
}
|
||||
#endif // USE_MOTOR
|
||||
|
|
|
@ -105,5 +105,3 @@ struct motorDevConfig_s;
|
|||
typedef struct motorDevConfig_s motorDevConfig_t;
|
||||
bool isDshotBitbangActive(const motorDevConfig_t *motorConfig);
|
||||
#endif
|
||||
|
||||
float getDigitalIdleOffset(const motorConfig_t *motorConfig);
|
||||
|
|
|
@ -43,7 +43,7 @@
|
|||
#define PARAM_NAME_RC_SMOOTHING_DEBUG_AXIS "rc_smoothing_debug_axis"
|
||||
#define PARAM_NAME_RC_SMOOTHING_ACTIVE_CUTOFFS "rc_smoothing_active_cutoffs_ff_sp_thr"
|
||||
#define PARAM_NAME_SERIAL_RX_PROVIDER "serialrx_provider"
|
||||
#define PARAM_NAME_DSHOT_IDLE_VALUE "dshot_idle_value"
|
||||
#define PARAM_NAME_MOTOR_IDLE "motor_idle"
|
||||
#define PARAM_NAME_DSHOT_BIDIR "dshot_bidir"
|
||||
#define PARAM_NAME_USE_UNSYNCED_PWM "use_unsynced_pwm"
|
||||
#define PARAM_NAME_MOTOR_PWM_PROTOCOL "motor_pwm_protocol"
|
||||
|
|
|
@ -348,7 +348,7 @@ void mixerInitProfile(void)
|
|||
mixerRuntime.dynIdleMaxIncrease = currentPidProfile->dyn_idle_max_increase * 0.001f;
|
||||
// before takeoff, use the static idle value as the dynamic idle limit.
|
||||
// whoop users should first adjust static idle to ensure reliable motor start before enabling dynamic idle
|
||||
mixerRuntime.dynIdleStartIncrease = motorConfig()->digitalIdleOffsetValue * 0.0001f;
|
||||
mixerRuntime.dynIdleStartIncrease = motorConfig()->motorIdle * 0.0001f;
|
||||
mixerRuntime.minRpsDelayK = 800 * pidGetDT() / 20.0f; //approx 20ms D delay, arbitrarily suits many motors
|
||||
if (!mixerRuntime.feature3dEnabled && mixerRuntime.dynIdleMinRps) {
|
||||
mixerRuntime.motorOutputLow = DSHOT_MIN_THROTTLE; // Override value set by initEscEndpoints to allow zero motor drive
|
||||
|
@ -486,7 +486,6 @@ void mixerInit(mixerMode_e mixerMode)
|
|||
#endif
|
||||
|
||||
#ifdef USE_DYN_IDLE
|
||||
mixerRuntime.idleThrottleOffset = getDigitalIdleOffset(motorConfig());
|
||||
mixerRuntime.dynIdleI = 0.0f;
|
||||
mixerRuntime.prevMinRps = 0.0f;
|
||||
#endif
|
||||
|
|
|
@ -39,7 +39,6 @@ typedef struct mixerRuntime_s {
|
|||
#ifdef USE_DYN_IDLE
|
||||
float dynIdleMaxIncrease;
|
||||
float dynIdleStartIncrease;
|
||||
float idleThrottleOffset;
|
||||
float dynIdleMinRps;
|
||||
float dynIdlePGain;
|
||||
float prevMinRps;
|
||||
|
|
|
@ -1445,7 +1445,7 @@ case MSP_NAME:
|
|||
break;
|
||||
|
||||
case MSP_MOTOR_CONFIG:
|
||||
sbufWriteU16(dst, motorConfig()->minthrottle);
|
||||
sbufWriteU16(dst, 0); // was minthrottle until after 4.5
|
||||
sbufWriteU16(dst, motorConfig()->maxthrottle);
|
||||
sbufWriteU16(dst, motorConfig()->mincommand);
|
||||
|
||||
|
@ -1857,7 +1857,7 @@ case MSP_NAME:
|
|||
sbufWriteU8(dst, motorConfig()->dev.useUnsyncedPwm);
|
||||
sbufWriteU8(dst, motorConfig()->dev.motorPwmProtocol);
|
||||
sbufWriteU16(dst, motorConfig()->dev.motorPwmRate);
|
||||
sbufWriteU16(dst, motorConfig()->digitalIdleOffsetValue);
|
||||
sbufWriteU16(dst, motorConfig()->motorIdle);
|
||||
sbufWriteU8(dst, 0); // DEPRECATED: gyro_use_32kHz
|
||||
sbufWriteU8(dst, motorConfig()->dev.motorPwmInversion);
|
||||
sbufWriteU8(dst, gyroConfig()->gyro_to_use);
|
||||
|
@ -2837,7 +2837,7 @@ static mspResult_e mspProcessInCommand(mspDescriptor_t srcDesc, int16_t cmdMSP,
|
|||
break;
|
||||
|
||||
case MSP_SET_MOTOR_CONFIG:
|
||||
motorConfigMutable()->minthrottle = sbufReadU16(src);
|
||||
sbufReadU16(src); // minthrottle deprecated in 4.6
|
||||
motorConfigMutable()->maxthrottle = sbufReadU16(src);
|
||||
motorConfigMutable()->mincommand = sbufReadU16(src);
|
||||
|
||||
|
@ -3023,7 +3023,7 @@ static mspResult_e mspProcessInCommand(mspDescriptor_t srcDesc, int16_t cmdMSP,
|
|||
motorConfigMutable()->dev.motorPwmProtocol = sbufReadU8(src);
|
||||
motorConfigMutable()->dev.motorPwmRate = sbufReadU16(src);
|
||||
if (sbufBytesRemaining(src) >= 2) {
|
||||
motorConfigMutable()->digitalIdleOffsetValue = sbufReadU16(src);
|
||||
motorConfigMutable()->motorIdle = sbufReadU16(src);
|
||||
}
|
||||
if (sbufBytesRemaining(src)) {
|
||||
sbufReadU8(src); // DEPRECATED: gyro_use_32khz
|
||||
|
|
|
@ -48,17 +48,15 @@
|
|||
#define DEFAULT_DSHOT_TELEMETRY DSHOT_TELEMETRY_OFF
|
||||
#endif
|
||||
|
||||
PG_REGISTER_WITH_RESET_FN(motorConfig_t, motorConfig, PG_MOTOR_CONFIG, 2);
|
||||
PG_REGISTER_WITH_RESET_FN(motorConfig_t, motorConfig, PG_MOTOR_CONFIG, 3);
|
||||
|
||||
void pgResetFn_motorConfig(motorConfig_t *motorConfig)
|
||||
{
|
||||
#ifdef BRUSHED_MOTORS
|
||||
motorConfig->minthrottle = 1000;
|
||||
motorConfig->dev.motorPwmRate = BRUSHED_MOTORS_PWM_RATE;
|
||||
motorConfig->dev.motorPwmProtocol = PWM_TYPE_BRUSHED;
|
||||
motorConfig->dev.useUnsyncedPwm = true;
|
||||
#else
|
||||
motorConfig->minthrottle = 1070;
|
||||
motorConfig->dev.motorPwmRate = BRUSHLESS_MOTORS_PWM_RATE;
|
||||
#ifndef USE_DSHOT
|
||||
if (motorConfig->dev.motorPwmProtocol == PWM_TYPE_STANDARD) {
|
||||
|
@ -74,7 +72,11 @@ void pgResetFn_motorConfig(motorConfig_t *motorConfig)
|
|||
|
||||
motorConfig->maxthrottle = 2000;
|
||||
motorConfig->mincommand = 1000;
|
||||
motorConfig->digitalIdleOffsetValue = 550;
|
||||
#ifdef BRUSHED_MOTORS
|
||||
motorConfig->motorIdle = 700; // historical default minThrottle for brushed was 1070
|
||||
#else
|
||||
motorConfig->motorIdle = 550;
|
||||
#endif // BRUSHED_MOTORS
|
||||
motorConfig->kv = 1960;
|
||||
|
||||
#ifdef USE_TIMER
|
||||
|
|
|
@ -59,8 +59,7 @@ typedef struct motorDevConfig_s {
|
|||
|
||||
typedef struct motorConfig_s {
|
||||
motorDevConfig_t dev;
|
||||
uint16_t digitalIdleOffsetValue; // Idle value for DShot protocol, full motor output = 10000
|
||||
uint16_t minthrottle; // Set the minimum throttle command sent to the ESC (Electronic Speed Controller). This is the minimum value that allow motors to run at a idle speed.
|
||||
uint16_t motorIdle; // When motors are idling, the percentage of the motor range added above the disarmed value, in percent * 100.
|
||||
uint16_t maxthrottle; // This is the maximum value for the ESCs at full power. This value can be increased up to 2000
|
||||
uint16_t mincommand; // This is the value for the ESCs when they are not armed. In some cases, this value must be lowered down to 900 for some specific ESCs
|
||||
uint16_t kv; // Motor velocity constant (Kv) to estimate RPM under no load (unloadedRpm = Kv * batteryVoltage)
|
||||
|
|
|
@ -51,7 +51,6 @@ extern "C" {
|
|||
#include "gtest/gtest.h"
|
||||
|
||||
uint32_t testFeatureMask = 0;
|
||||
uint16_t testMinThrottle = 0;
|
||||
throttleStatus_e throttleStatus = THROTTLE_HIGH;
|
||||
|
||||
enum {
|
||||
|
@ -755,11 +754,6 @@ void beeper(beeperMode_e mode)
|
|||
UNUSED(mode);
|
||||
}
|
||||
|
||||
uint16_t getCurrentMinthrottle(void)
|
||||
{
|
||||
return testMinThrottle;
|
||||
}
|
||||
|
||||
bool isUsingSticksForArming(void)
|
||||
{
|
||||
return isUsingSticksToArm;
|
||||
|
|
|
@ -32,7 +32,6 @@ extern "C" {
|
|||
extern "C" {
|
||||
|
||||
bool featureIsEnabled(uint8_t f);
|
||||
float getDigitalIdleOffset(const motorConfig_t *motorConfig);
|
||||
float scaleRangef(float a, float b, float c, float d, float e);
|
||||
|
||||
// Mocking functions
|
||||
|
@ -43,12 +42,6 @@ bool featureIsEnabled(uint8_t f)
|
|||
return true;
|
||||
}
|
||||
|
||||
float getDigitalIdleOffset(const motorConfig_t *motorConfig)
|
||||
{
|
||||
UNUSED(motorConfig);
|
||||
return 0;
|
||||
}
|
||||
|
||||
float scaleRangef(float a, float b, float c, float d, float e)
|
||||
{
|
||||
UNUSED(a);
|
||||
|
|
|
@ -36,7 +36,6 @@ PG_REGISTER_WITH_RESET_TEMPLATE(motorConfig_t, motorConfig, PG_MOTOR_CONFIG, 1);
|
|||
|
||||
PG_RESET_TEMPLATE(motorConfig_t, motorConfig,
|
||||
.dev = {.motorPwmRate = 400},
|
||||
.minthrottle = 1150,
|
||||
.maxthrottle = 1850,
|
||||
.mincommand = 1000,
|
||||
);
|
||||
|
@ -50,7 +49,6 @@ TEST(ParameterGroupsfTest, Test_pgResetAll)
|
|||
{
|
||||
memset(motorConfigMutable(), 0, sizeof(motorConfig_t));
|
||||
pgResetAll();
|
||||
EXPECT_EQ(1150, motorConfig()->minthrottle);
|
||||
EXPECT_EQ(1850, motorConfig()->maxthrottle);
|
||||
EXPECT_EQ(1000, motorConfig()->mincommand);
|
||||
EXPECT_EQ(400, motorConfig()->dev.motorPwmRate);
|
||||
|
@ -61,7 +59,6 @@ TEST(ParameterGroupsfTest, Test_pgFind)
|
|||
memset(motorConfigMutable(), 0, sizeof(motorConfig_t));
|
||||
const pgRegistry_t *pgRegistry = pgFind(PG_MOTOR_CONFIG);
|
||||
pgReset(pgRegistry);
|
||||
EXPECT_EQ(1150, motorConfig()->minthrottle);
|
||||
EXPECT_EQ(1850, motorConfig()->maxthrottle);
|
||||
EXPECT_EQ(1000, motorConfig()->mincommand);
|
||||
EXPECT_EQ(400, motorConfig()->dev.motorPwmRate);
|
||||
|
@ -70,7 +67,6 @@ TEST(ParameterGroupsfTest, Test_pgFind)
|
|||
memset(&motorConfig2, 0, sizeof(motorConfig_t));
|
||||
motorConfigMutable()->dev.motorPwmRate = 500;
|
||||
pgStore(pgRegistry, &motorConfig2, sizeof(motorConfig_t));
|
||||
EXPECT_EQ(1150, motorConfig2.minthrottle);
|
||||
EXPECT_EQ(1850, motorConfig2.maxthrottle);
|
||||
EXPECT_EQ(1000, motorConfig2.mincommand);
|
||||
EXPECT_EQ(500, motorConfig2.dev.motorPwmRate);
|
||||
|
@ -78,7 +74,6 @@ TEST(ParameterGroupsfTest, Test_pgFind)
|
|||
motorConfig_t motorConfig3;
|
||||
memset(&motorConfig3, 0, sizeof(motorConfig_t));
|
||||
pgResetCopy(&motorConfig3, PG_MOTOR_CONFIG);
|
||||
EXPECT_EQ(1150, motorConfig3.minthrottle);
|
||||
EXPECT_EQ(1850, motorConfig3.maxthrottle);
|
||||
EXPECT_EQ(1000, motorConfig3.mincommand);
|
||||
EXPECT_EQ(400, motorConfig3.dev.motorPwmRate);
|
||||
|
|
Loading…
Add table
Add a link
Reference in a new issue