Use a positive named setting and variable instead of a negative one to

simplify the logic and aid understanding.
This commit is contained in:
Dominic Clifton 2015-03-09 22:50:27 +00:00
parent acabbf41db
commit ed434fe47b
5 changed files with 5 additions and 7 deletions

View File

@ -118,7 +118,7 @@ Re-apply any new defaults as desired.
| disarm_kill_switch | Enabled by default. Disarms the motors independently of throttle value. Setting to 0 reverts to the old behaviour of disarming only when the throttle is low. Only applies when arming and disarming with an AUX channel. | 0 | 1 | 1 | Master | UINT8 | | disarm_kill_switch | Enabled by default. Disarms the motors independently of throttle value. Setting to 0 reverts to the old behaviour of disarming only when the throttle is low. Only applies when arming and disarming with an AUX channel. | 0 | 1 | 1 | Master | UINT8 |
| auto_disarm_delay | | 0 | 60 | 5 | Master | UINT8 | | auto_disarm_delay | | 0 | 60 | 5 | Master | UINT8 |
| small_angle | If the copter tilt angle exceed this value the copter will refuse to arm. default is 25°. | 0 | 180 | 25 | Master | UINT8 | | small_angle | If the copter tilt angle exceed this value the copter will refuse to arm. default is 25°. | 0 | 180 | 25 | Master | UINT8 |
| disable_pid_at_min_throttle | If enabled, the copter will not process the pid algorithm at minimum throttle. | 0 | 1 | 0 | Master | UINT8 | | pid_at_min_throttle | If enabled, the copter will process the pid algorithm at minimum throttle. | 0 | 1 | 0 | Master | UINT8 |
| flaps_speed | | 0 | 100 | 0 | Master | UINT8 | | flaps_speed | | 0 | 100 | 0 | Master | UINT8 |
| fixedwing_althold_dir | | -1 | 1 | 1 | Master | INT8 | | fixedwing_althold_dir | | -1 | 1 | 1 | Master | INT8 |
| reboot_character | | 48 | 126 | 82 | Master | UINT8 | | reboot_character | | 48 | 126 | 82 | Master | UINT8 |

View File

@ -378,7 +378,7 @@ static void resetConf(void)
masterConfig.disarm_kill_switch = 1; masterConfig.disarm_kill_switch = 1;
masterConfig.auto_disarm_delay = 5; masterConfig.auto_disarm_delay = 5;
masterConfig.small_angle = 25; masterConfig.small_angle = 25;
masterConfig.disable_pid_at_min_throttle = 0; masterConfig.pid_at_min_throttle = 1;
masterConfig.airplaneConfig.flaps_speed = 0; masterConfig.airplaneConfig.flaps_speed = 0;

View File

@ -65,7 +65,7 @@ typedef struct master_t {
uint8_t disarm_kill_switch; // allow disarm via AUX switch regardless of throttle value uint8_t disarm_kill_switch; // allow disarm via AUX switch regardless of throttle value
uint8_t auto_disarm_delay; // allow automatically disarming multicopters after auto_disarm_delay seconds of zero throttle. Disabled when 0 uint8_t auto_disarm_delay; // allow automatically disarming multicopters after auto_disarm_delay seconds of zero throttle. Disabled when 0
uint8_t small_angle; uint8_t small_angle;
uint8_t disable_pid_at_min_throttle; // when enabled (nonzero), ignore pids at minimum throttle uint8_t pid_at_min_throttle; // when enabled pids are used at minimum throttle
airplaneConfig_t airplaneConfig; airplaneConfig_t airplaneConfig;

View File

@ -714,13 +714,11 @@ void mixTable(void)
} else { } else {
// If we're at minimum throttle and FEATURE_MOTOR_STOP enabled, // If we're at minimum throttle and FEATURE_MOTOR_STOP enabled,
// do not spin the motors. // do not spin the motors.
// If we're at minimum throttle and disable_pid_at_min_throttle
// is enabled, spin motors at minimum throttle.
motor[i] = constrain(motor[i], escAndServoConfig->minthrottle, escAndServoConfig->maxthrottle); motor[i] = constrain(motor[i], escAndServoConfig->minthrottle, escAndServoConfig->maxthrottle);
if ((rcData[THROTTLE]) < rxConfig->mincheck) { if ((rcData[THROTTLE]) < rxConfig->mincheck) {
if (feature(FEATURE_MOTOR_STOP)) { if (feature(FEATURE_MOTOR_STOP)) {
motor[i] = escAndServoConfig->mincommand; motor[i] = escAndServoConfig->mincommand;
} else if (masterConfig.disable_pid_at_min_throttle != 0) { } else if (masterConfig.pid_at_min_throttle == 0) {
motor[i] = escAndServoConfig->minthrottle; motor[i] = escAndServoConfig->minthrottle;
} }
} }

View File

@ -274,7 +274,7 @@ const clivalue_t valueTable[] = {
{ "disarm_kill_switch", VAR_UINT8 | MASTER_VALUE, &masterConfig.disarm_kill_switch, 0, 1 }, { "disarm_kill_switch", VAR_UINT8 | MASTER_VALUE, &masterConfig.disarm_kill_switch, 0, 1 },
{ "auto_disarm_delay", VAR_UINT8 | MASTER_VALUE, &masterConfig.auto_disarm_delay, 0, 60 }, { "auto_disarm_delay", VAR_UINT8 | MASTER_VALUE, &masterConfig.auto_disarm_delay, 0, 60 },
{ "small_angle", VAR_UINT8 | MASTER_VALUE, &masterConfig.small_angle, 0, 180 }, { "small_angle", VAR_UINT8 | MASTER_VALUE, &masterConfig.small_angle, 0, 180 },
{ "disable_pid_at_min_throttle", VAR_UINT8 | MASTER_VALUE, &masterConfig.disable_pid_at_min_throttle, 0, 1 }, { "pid_at_min_throttle", VAR_UINT8 | MASTER_VALUE, &masterConfig.pid_at_min_throttle, 0, 1 },
{ "flaps_speed", VAR_UINT8 | MASTER_VALUE, &masterConfig.airplaneConfig.flaps_speed, 0, 100 }, { "flaps_speed", VAR_UINT8 | MASTER_VALUE, &masterConfig.airplaneConfig.flaps_speed, 0, 100 },