From 10f1731f3a1015fcbfde68f9ee4ec9dbd495f508 Mon Sep 17 00:00:00 2001 From: James O'Shannessy <12959316+joshanne@users.noreply.github.com> Date: Tue, 21 May 2024 09:32:22 +1000 Subject: [PATCH] AP_Mount: Only save converted mount if mount was previously set in the first place The mount library force configures the mount type on conversion, even if the mount was never configured in the first place --- libraries/AP_Mount/AP_Mount.cpp | 8 ++++++-- 1 file changed, 6 insertions(+), 2 deletions(-) diff --git a/libraries/AP_Mount/AP_Mount.cpp b/libraries/AP_Mount/AP_Mount.cpp index 3bfed9c2924f6..8e6d68d97bd24 100644 --- a/libraries/AP_Mount/AP_Mount.cpp +++ b/libraries/AP_Mount/AP_Mount.cpp @@ -1014,7 +1014,10 @@ void AP_Mount::convert_params() // convert MNT_TYPE to MNT1_TYPE int8_t mnt_type = 0; IGNORE_RETURN(AP_Param::get_param_by_index(this, 19, AP_PARAM_INT8, &mnt_type)); - if (mnt_type > 0) { + if (mnt_type == 0) { + // if the mount was not previously set, no need to perform the upgrade logic + return; + } else if (mnt_type > 0) { int8_t stab_roll = 0; int8_t stab_pitch = 0; IGNORE_RETURN(AP_Param::get_param_by_index(this, 4, AP_PARAM_INT8, &stab_roll)); @@ -1024,8 +1027,9 @@ void AP_Mount::convert_params() // conversion is still done even if HAL_MOUNT_SERVO_ENABLED is false mnt_type = 7; // (int8_t)Type::BrushlessPWM; } + // if the mount was previously set, then we need to save the upgraded mount type + _params[0].type.set_and_save(mnt_type); } - _params[0].type.set_and_save(mnt_type); // convert MNT_JSTICK_SPD to MNT1_RC_RATE int8_t jstick_spd = 0;