mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-02-26 09:43:57 -04:00
AP_Param: add set_and_notify to vectors
This commit is contained in:
parent
00ed6bbc2b
commit
c81f1e1032
@ -638,6 +638,13 @@ public:
|
||||
_value = v;
|
||||
}
|
||||
|
||||
/// Value setter - set value, tell GCS
|
||||
///
|
||||
void set_and_notify(const T &v) {
|
||||
set(v);
|
||||
notify();
|
||||
}
|
||||
|
||||
/// Combined set and save
|
||||
///
|
||||
bool set_and_save(const T &v) {
|
||||
|
Loading…
Reference in New Issue
Block a user