mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-03 14:38:30 -04:00
AP_Param: avoid a notify if value is already correct
This commit is contained in:
parent
69f3c83c20
commit
eaa68f32e3
@ -536,9 +536,11 @@ public:
|
||||
/// Value setter - set value, tell GCS
|
||||
///
|
||||
void set_and_notify(const T &v) {
|
||||
if (v != _value) {
|
||||
set(v);
|
||||
notify();
|
||||
}
|
||||
}
|
||||
|
||||
/// Combined set and save
|
||||
///
|
||||
|
Loading…
Reference in New Issue
Block a user