IDLE UP switch // Remove pid_at_min_throttle

This commit is contained in:
borisbstyle 2015-12-04 16:16:21 +01:00
parent 769ddd39af
commit eafa631a32
7 changed files with 11 additions and 40 deletions

View File

@ -329,7 +329,6 @@ void resetRcControlsConfig(rcControlsConfig_t *rcControlsConfig) {
}
void resetMixerConfig(mixerConfig_t *mixerConfig) {
mixerConfig->pid_at_min_throttle = 1;
mixerConfig->yaw_motor_direction = 1;
mixerConfig->yaw_jump_prevention_limit = 200;
#ifdef USE_SERVOS
@ -827,14 +826,6 @@ void validateAndFixConfig(void)
masterConfig.telemetryConfig.telemetry_inversion = 1;
#endif
/*
* The retarded_arm setting is incompatible with pid_at_min_throttle because full roll causes the craft to roll over on the ground.
* The pid_at_min_throttle implementation ignores yaw on the ground, but doesn't currently ignore roll when retarded_arm is enabled.
*/
if (masterConfig.retarded_arm && masterConfig.mixerConfig.pid_at_min_throttle) {
masterConfig.mixerConfig.pid_at_min_throttle = 0;
}
#if defined(CC3D) && defined(SONAR) && defined(USE_SOFTSERIAL1)
if (feature(FEATURE_SONAR) && feature(FEATURE_SOFTSERIAL)) {
featureClear(FEATURE_SONAR);

View File

@ -783,7 +783,7 @@ void mixTable(void)
motor[i] -= maxThrottleDifference;
if (feature(FEATURE_3D)) {
if (mixerConfig->pid_at_min_throttle
if ((IS_RC_MODE_ACTIVE(BOXIDLE_UP))
|| rcData[THROTTLE] <= rxConfig->midrc - flight3DConfig->deadband3d_throttle
|| rcData[THROTTLE] >= rxConfig->midrc + flight3DConfig->deadband3d_throttle) {
if (rcData[THROTTLE] > rxConfig->midrc) {
@ -805,10 +805,10 @@ void mixTable(void)
// If we're at minimum throttle and FEATURE_MOTOR_STOP enabled,
// do not spin the motors.
motor[i] = constrain(motor[i], escAndServoConfig->minthrottle, escAndServoConfig->maxthrottle);
if ((rcData[THROTTLE]) < rxConfig->mincheck) {
if (((rcData[THROTTLE]) < rxConfig->mincheck) && !(IS_RC_MODE_ACTIVE(BOXIDLE_UP))) {
if (feature(FEATURE_MOTOR_STOP)) {
motor[i] = escAndServoConfig->mincommand;
} else if (mixerConfig->pid_at_min_throttle == 0) {
} else {
motor[i] = escAndServoConfig->minthrottle;
}
}

View File

@ -69,7 +69,6 @@ typedef struct mixer_s {
} mixer_t;
typedef struct mixerConfig_s {
uint8_t pid_at_min_throttle; // when enabled pids are used at minimum throttle
int8_t yaw_motor_direction;
uint16_t yaw_jump_prevention_limit; // make limit configurable (original fixed value was 100)
#ifdef USE_SERVOS

View File

@ -48,6 +48,7 @@ typedef enum {
BOXSERVO3,
BOXBLACKBOX,
BOXFAILSAFE,
BOXIDLE_UP,
CHECKBOX_ITEM_COUNT
} boxId_e;

View File

@ -356,12 +356,6 @@ static const char * const lookupTableGyroSampling[] = {
"1KHZ"
};
static const char * const lookupTablePidAtMinThrottle[] = {
"OFF",
"PD",
"PID"
};
typedef struct lookupTableEntry_s {
const char * const *values;
const uint8_t valueCount;
@ -384,7 +378,6 @@ typedef enum {
TABLE_SERIAL_RX,
TABLE_GYRO_FILTER,
TABLE_GYRO_SAMPLING,
TABLE_PID_AT_MIN_THROTTLE,
} lookupTableIndex_e;
static const lookupTableEntry_t lookupTables[] = {
@ -401,8 +394,7 @@ static const lookupTableEntry_t lookupTables[] = {
{ lookupTablePidController, sizeof(lookupTablePidController) / sizeof(char *) },
{ lookupTableSerialRX, sizeof(lookupTableSerialRX) / sizeof(char *) },
{ lookupTableGyroFilter, sizeof(lookupTableGyroFilter) / sizeof(char *) },
{ lookupTableGyroSampling, sizeof(lookupTableGyroSampling) / sizeof(char *) },
{ lookupTablePidAtMinThrottle, sizeof(lookupTablePidAtMinThrottle) / sizeof(char *) }
{ lookupTableGyroSampling, sizeof(lookupTableGyroSampling) / sizeof(char *) }
};
#define VALUE_TYPE_OFFSET 0
@ -568,7 +560,6 @@ const clivalue_t valueTable[] = {
{ "yaw_control_direction", VAR_INT8 | MASTER_VALUE, &masterConfig.yaw_control_direction, .config.minmax = { -1, 1 } },
{ "pid_at_min_throttle", VAR_UINT8 | MASTER_VALUE | MODE_LOOKUP, &masterConfig.mixerConfig.pid_at_min_throttle, .config.lookup = { TABLE_PID_AT_MIN_THROTTLE } },
{ "yaw_motor_direction", VAR_INT8 | MASTER_VALUE, &masterConfig.mixerConfig.yaw_motor_direction, .config.minmax = { -1, 1 } },
{ "yaw_jump_prevention_limit", VAR_UINT16 | MASTER_VALUE, &masterConfig.mixerConfig.yaw_jump_prevention_limit, .config.minmax = { YAW_JUMP_PREVENTION_LIMIT_LOW, YAW_JUMP_PREVENTION_LIMIT_HIGH } },
#ifdef USE_SERVOS

View File

@ -356,6 +356,7 @@ static const box_t boxes[CHECKBOX_ITEM_COUNT + 1] = {
{ BOXSERVO3, "SERVO3;", 25 },
{ BOXBLACKBOX, "BLACKBOX;", 26 },
{ BOXFAILSAFE, "FAILSAFE;", 27 },
{ BOXIDLE_UP, "IDLE UP;", 28 },
{ CHECKBOX_ITEM_COUNT, NULL, 0xFF }
};
@ -641,6 +642,7 @@ void mspInit(serialConfig_t *serialConfig)
activeBoxIdCount = 0;
activeBoxIds[activeBoxIdCount++] = BOXARM;
activeBoxIds[activeBoxIdCount++] = BOXIDLE_UP;
if (sensors(SENSOR_ACC)) {
activeBoxIds[activeBoxIdCount++] = BOXANGLE;
@ -834,7 +836,8 @@ static bool processOutCommand(uint8_t cmdMSP)
IS_ENABLED(FLIGHT_MODE(SONAR_MODE)) << BOXSONAR |
IS_ENABLED(ARMING_FLAG(ARMED)) << BOXARM |
IS_ENABLED(IS_RC_MODE_ACTIVE(BOXBLACKBOX)) << BOXBLACKBOX |
IS_ENABLED(FLIGHT_MODE(FAILSAFE_MODE)) << BOXFAILSAFE;
IS_ENABLED(FLIGHT_MODE(FAILSAFE_MODE)) << BOXFAILSAFE |
IS_ENABLED(IS_RC_MODE_ACTIVE(BOXIDLE_UP)) << BOXIDLE_UP;
for (i = 0; i < activeBoxIdCount; i++) {
int flag = (tmp & (1 << activeBoxIds[i]));
if (flag)

View File

@ -100,7 +100,6 @@ enum {
#define PREVENT_RX_PROCESS_PRE_LOOP_TRIGGER 80 // Prevent RX processing before expected loop trigger
#define PREVENT_BARO_READ_PRE_LOOP_TRIGGER 150 // Prevent BARO processing before expected loop trigger
#define GYRO_RATE 0.001f // Gyro refresh rate 1khz
#define PID_AT_MIN_THROTTLE_ITERM_DELAY (3 * 1000)
uint32_t currentTime = 0;
uint32_t previousTime = 0;
@ -542,7 +541,6 @@ void executePeriodicTasks(bool skipBaroUpdate)
void processRx(void)
{
static bool armedBeeperOn = false;
static uint32_t pidResetErrorGyroTimeout = 0;
calculateRxChannelsAndUpdateFailsafe(currentTime);
@ -565,21 +563,9 @@ void processRx(void)
throttleStatus_e throttleStatus = calculateThrottleStatus(&masterConfig.rxConfig, masterConfig.flight3DConfig.deadband3d_throttle);
if (throttleStatus == THROTTLE_LOW) {
if (throttleStatus == THROTTLE_LOW && !(IS_RC_MODE_ACTIVE(BOXIDLE_UP))) {
pidResetErrorAngle();
/*
* Additional code to prevent Iterm reset below min_check. pid_at_min_throttle higher than 1 will
* activate the feature. Experimental yet. Minimum configuration is 2 sec and maxx is 5seconds.
*/
if (masterConfig.mixerConfig.pid_at_min_throttle > 1 && ARMING_FLAG(ARMED)) {
if (pidResetErrorGyroTimeout < millis()) {
pidResetErrorGyro();
}
} else {
pidResetErrorGyro();
}
} else {
pidResetErrorGyroTimeout = millis() + PID_AT_MIN_THROTTLE_ITERM_DELAY;
pidResetErrorGyro();
}
// When armed and motors aren't spinning, do beeps and then disarm