Skip to content
New issue

Have a question about this project? Sign up for a free GitHub account to open an issue and contact its maintainers and the community.

By clicking “Sign up for GitHub”, you agree to our terms of service and privacy statement. We’ll occasionally send you account related emails.

Already on GitHub? Sign in to your account

AP_Mount: Only save converted mount parameter if mount was previously set in the first place #27109

Merged
Changes from all commits
Commits
File filter

Filter by extension

Filter by extension

Conversations
Failed to load comments.
Loading
Jump to
Jump to file
Failed to load files.
Loading
Diff view
Diff view
8 changes: 6 additions & 2 deletions libraries/AP_Mount/AP_Mount.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -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;
Copy link
Contributor Author

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

If the old MNT_TYPE value is zero, it is not configured, and upgrade is not required - so bail.

} 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));
Expand All @@ -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);
Copy link
Contributor Author

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

Moving this inside the else ensures that we only write a value to MNT1_TYPE if the previous MNT_TYPE was set to a non zero value.

ie. don't set MNT1_TYPE to a configured value of zero, as this is no longer "default".


// convert MNT_JSTICK_SPD to MNT1_RC_RATE
int8_t jstick_spd = 0;
Expand Down
Loading