Copter: ensure _spin_when_armed is not higher than _min_throttle

This commit is contained in:
Randy Mackay 2013-07-16 15:25:57 +09:00
parent 62f3eed4e0
commit 336357fbaf
2 changed files with 10 additions and 4 deletions

View File

@ -123,11 +123,14 @@ void AP_MotorsMatrix::output_armed()
// if we are not sending a throttle output, we cut the motors
if (_rc_throttle->servo_out == 0) {
// range check spin_when_armed
if (_spin_when_armed < 0) {
_spin_when_armed = 0;
}
if (_spin_when_armed > _min_throttle) {
_spin_when_armed = _min_throttle;
}
for (i=0; i<AP_MOTORS_MAX_NUM_MOTORS; i++) {
// range check spin_when_armed
if (_spin_when_armed < 0) {
_spin_when_armed = 0;
}
// spin motors at minimum
if (motor_enabled[i]) {
motor_out[i] = _rc_throttle->radio_min + _spin_when_armed;

View File

@ -89,6 +89,9 @@ void AP_MotorsTri::output_armed()
if (_spin_when_armed < 0) {
_spin_when_armed = 0;
}
if (_spin_when_armed > _min_throttle) {
_spin_when_armed = _min_throttle;
}
motor_out[AP_MOTORS_MOT_1] = _rc_throttle->radio_min + _spin_when_armed;
motor_out[AP_MOTORS_MOT_2] = _rc_throttle->radio_min + _spin_when_armed;
motor_out[AP_MOTORS_MOT_4] = _rc_throttle->radio_min + _spin_when_armed;