mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-03 06:28:27 -04:00
AP_Param: use thread safe object buffer
This commit is contained in:
parent
a183d00b7e
commit
1ee14ffa75
@ -78,7 +78,7 @@ struct AP_Param::param_override *AP_Param::param_overrides = nullptr;
|
|||||||
uint16_t AP_Param::num_param_overrides = 0;
|
uint16_t AP_Param::num_param_overrides = 0;
|
||||||
uint16_t AP_Param::num_read_only = 0;
|
uint16_t AP_Param::num_read_only = 0;
|
||||||
|
|
||||||
ObjectBuffer<AP_Param::param_save> AP_Param::save_queue{30};
|
ObjectBuffer_TS<AP_Param::param_save> AP_Param::save_queue{30};
|
||||||
bool AP_Param::registered_save_handler;
|
bool AP_Param::registered_save_handler;
|
||||||
|
|
||||||
// we need a dummy object for the parameter save callback
|
// we need a dummy object for the parameter save callback
|
||||||
|
@ -666,7 +666,7 @@ private:
|
|||||||
AP_Param *param;
|
AP_Param *param;
|
||||||
bool force_save;
|
bool force_save;
|
||||||
};
|
};
|
||||||
static ObjectBuffer<struct param_save> save_queue;
|
static ObjectBuffer_TS<struct param_save> save_queue;
|
||||||
static bool registered_save_handler;
|
static bool registered_save_handler;
|
||||||
|
|
||||||
// background function for saving parameters
|
// background function for saving parameters
|
||||||
|
Loading…
Reference in New Issue
Block a user