From e12ed0fe1ca2c8496992b8aa51d777a410b870c1 Mon Sep 17 00:00:00 2001 From: Willian Galvani Date: Fri, 5 May 2023 08:56:32 +0200 Subject: [PATCH] Sub: set defaults for MOT_PWM_MIN and MOT_PWM_MAX --- ArduSub/Parameters.cpp | 2 ++ 1 file changed, 2 insertions(+) diff --git a/ArduSub/Parameters.cpp b/ArduSub/Parameters.cpp index 7bd1ff3eb1..b55b064b8b 100644 --- a/ArduSub/Parameters.cpp +++ b/ArduSub/Parameters.cpp @@ -719,6 +719,8 @@ void Sub::load_parameters() AP_Param::set_default_by_name("RC8_OPTION", 213); // MOUNT1_PITCH // We should ignore this parameter since ROVs are neutral buoyancy 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 #if AP_AIRSPEED_ENABLED