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