mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-02-21 23:33:57 -04:00
AP_Motors: add PWM min and max param conversion function
This commit is contained in:
parent
12c1b3e8f5
commit
d16be50e57
@ -774,3 +774,13 @@ void AP_MotorsMulticopter::save_params_on_disarm()
|
||||
_throttle_hover.save();
|
||||
}
|
||||
}
|
||||
|
||||
// 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)
|
||||
{
|
||||
if (_pwm_min.configured_in_storage() || _pwm_max.configured_in_storage()) {
|
||||
return;
|
||||
}
|
||||
_pwm_min.set_and_save(radio_min);
|
||||
_pwm_max.set_and_save(radio_max);
|
||||
}
|
||||
|
@ -105,6 +105,9 @@ public:
|
||||
// return whether a motor is enabled or not
|
||||
bool is_motor_enabled(uint8_t i) override { return motor_enabled[i]; }
|
||||
|
||||
// convert values to PWM min and max if not configured
|
||||
void convert_pwm_min_max_param(int16_t radio_min, int16_t radio_max);
|
||||
|
||||
// var_info for holding Parameter information
|
||||
static const struct AP_Param::GroupInfo var_info[];
|
||||
|
||||
|
Loading…
Reference in New Issue
Block a user