5
0
mirror of https://github.com/ArduPilot/ardupilot synced 2025-01-05 15:38:29 -04:00

AP_Motors: add PWM min and max param conversion function

This commit is contained in:
Iampete1 2021-09-04 18:51:27 +01:00 committed by Willian Galvani
parent 328cf74df2
commit ba389e3395
2 changed files with 13 additions and 0 deletions

View File

@ -748,3 +748,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);
}

View File

@ -99,6 +99,9 @@ public:
// as vectoring is used for yaw control
virtual void disable_yaw_torque(void) {}
// 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[];