mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-08 17:08:28 -04:00
GCS_MAVLink: invalidate param count on set of ENABLE param
This commit is contained in:
parent
d0a509eef1
commit
65e790a48c
@ -298,6 +298,10 @@ void GCS_MAVLINK::handle_param_set(const mavlink_message_t &msg)
|
||||
// save the change
|
||||
vp->save(force_save);
|
||||
|
||||
if (force_save && (parameter_flags & AP_PARAM_FLAG_ENABLE)) {
|
||||
AP_Param::invalidate_count();
|
||||
}
|
||||
|
||||
AP_Logger *logger = AP_Logger::get_singleton();
|
||||
if (logger != nullptr) {
|
||||
logger->Write_Parameter(key, vp->cast_to_float(var_type));
|
||||
|
Loading…
Reference in New Issue
Block a user