mirror of https://github.com/ArduPilot/ardupilot
AP_Baro: added semaphore for safe multi-thread use of APIs
This commit is contained in:
parent
e4de5a17d1
commit
5023b51679
|
@ -737,6 +737,8 @@ bool AP_Baro::should_log() const
|
|||
*/
|
||||
void AP_Baro::update(void)
|
||||
{
|
||||
WITH_SEMAPHORE(_rsem);
|
||||
|
||||
if (fabsf(_alt_offset - _alt_offset_active) > 0.01f) {
|
||||
// If there's more than 1cm difference then slowly slew to it via LPF.
|
||||
// The EKF does not like step inputs so this keeps it happy.
|
||||
|
|
|
@ -181,6 +181,11 @@ public:
|
|||
void set_log_baro_bit(uint32_t bit) { _log_baro_bit = bit; }
|
||||
bool should_log() const;
|
||||
|
||||
// allow threads to lock against baro update
|
||||
HAL_Semaphore &get_semaphore(void) {
|
||||
return _rsem;
|
||||
}
|
||||
|
||||
private:
|
||||
// singleton
|
||||
static AP_Baro *_singleton;
|
||||
|
@ -246,6 +251,9 @@ private:
|
|||
void _probe_i2c_barometers(void);
|
||||
AP_Int8 _filter_range; // valid value range from mean value
|
||||
AP_Int32 _baro_probe_ext;
|
||||
|
||||
// semaphore for API access from threads
|
||||
HAL_Semaphore_Recursive _rsem;
|
||||
};
|
||||
|
||||
namespace AP {
|
||||
|
|
Loading…
Reference in New Issue