mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-09 09:28:31 -04:00
AP_Motors: fixed override of MOT_PWM_MIN/MAX in defaults.parm
need to check configured() not configured_in_storage()
This commit is contained in:
parent
540dcc554f
commit
b2e43d1dee
@ -794,7 +794,7 @@ void AP_MotorsMulticopter::save_params_on_disarm()
|
|||||||
// convert to PWM min and max in the motor lib
|
// convert to PWM min and max in the motor lib
|
||||||
void AP_MotorsMulticopter::convert_pwm_min_max_param(int16_t radio_min, int16_t radio_max)
|
void AP_MotorsMulticopter::convert_pwm_min_max_param(int16_t radio_min, int16_t radio_max)
|
||||||
{
|
{
|
||||||
if (_pwm_min.configured_in_storage() || _pwm_max.configured_in_storage()) {
|
if (_pwm_min.configured() || _pwm_max.configured()) {
|
||||||
return;
|
return;
|
||||||
}
|
}
|
||||||
_pwm_min.set_and_save(radio_min);
|
_pwm_min.set_and_save(radio_min);
|
||||||
|
Loading…
Reference in New Issue
Block a user