Sub: set defaults for MOT_PWM_MIN and MOT_PWM_MAX

This commit is contained in:
Willian Galvani 2023-05-05 08:56:32 +02:00
parent 82bae765ff
commit e12ed0fe1c
1 changed files with 2 additions and 0 deletions

View File

@ -719,6 +719,8 @@ void Sub::load_parameters()
AP_Param::set_default_by_name("RC8_OPTION", 213); // MOUNT1_PITCH AP_Param::set_default_by_name("RC8_OPTION", 213); // MOUNT1_PITCH
// We should ignore this parameter since ROVs are neutral buoyancy // We should ignore this parameter since ROVs are neutral buoyancy
AP_Param::set_by_name("MOT_THST_HOVER", 0.5); AP_Param::set_by_name("MOT_THST_HOVER", 0.5);
AP_Param::set_default_by_name("MOT_PWM_MIN", 1100);
AP_Param::set_default_by_name("MOT_PWM_MAX", 1900);
// PARAMETER_CONVERSION - Added: JAN-2022 // PARAMETER_CONVERSION - Added: JAN-2022
#if AP_AIRSPEED_ENABLED #if AP_AIRSPEED_ENABLED