From 190f1c5098337781a05c010e0d571ed27d2c8e3d Mon Sep 17 00:00:00 2001 From: =?UTF-8?q?Patrick=20Jos=C3=A9=20Pereira?= Date: Mon, 16 Aug 2021 09:09:01 -0400 Subject: [PATCH] Sub: Parameters: Add default value for MNT_TYPE MIME-Version: 1.0 Content-Type: text/plain; charset=UTF-8 Content-Transfer-Encoding: 8bit It's very unlikely that a ROV may exist without a gimbal or any kind of camera control, the common use case is to use a single servo to control the camera and this is why we set the default value of MNT_TYPE as 1 (Servo). Signed-off-by: Patrick José Pereira --- ArduSub/Parameters.cpp | 1 + 1 file changed, 1 insertion(+) diff --git a/ArduSub/Parameters.cpp b/ArduSub/Parameters.cpp index 0b7e303832..7d70b1daa9 100644 --- a/ArduSub/Parameters.cpp +++ b/ArduSub/Parameters.cpp @@ -725,6 +725,7 @@ void Sub::load_parameters() AP_Param::set_default_by_name("RC3_TRIM", 1100); AP_Param::set_default_by_name("COMPASS_OFFS_MAX", 1000); AP_Param::set_default_by_name("INS_GYR_CAL", 0); + AP_Param::set_default_by_name("MNT_TYPE", 1); AP_Param::set_default_by_name("MNT_DEFLT_MODE", MAV_MOUNT_MODE_RC_TARGETING); AP_Param::set_default_by_name("MNT_JSTICK_SPD", 100); AP_Param::set_by_name("MNT_RC_IN_PAN", 7);