mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-23 17:18:28 -04:00
Copter: ensure _spin_when_armed is not higher than _min_throttle
This commit is contained in:
parent
62f3eed4e0
commit
336357fbaf
@ -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;
|
||||
|
@ -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;
|
||||
|
Loading…
Reference in New Issue
Block a user