mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-10 09:58:28 -04:00
AP_Compass: use HAL_SEMAPHORE_BLOCK_FOREVER macro
This commit is contained in:
parent
ccc495e4c1
commit
b39da462ec
@ -98,7 +98,7 @@ void AP_Compass_UAVCAN::read(void)
|
||||
return;
|
||||
}
|
||||
|
||||
if (_mag_baro->take(0)) {
|
||||
if (_mag_baro->take(HAL_SEMAPHORE_BLOCK_FOREVER)) {
|
||||
_sum /= _count;
|
||||
|
||||
publish_filtered_field(_sum, _instance);
|
||||
@ -123,7 +123,7 @@ void AP_Compass_UAVCAN::handle_mag_msg(Vector3f &mag)
|
||||
// correct raw_field for known errors
|
||||
correct_field(raw_field, _instance);
|
||||
|
||||
if (_mag_baro->take(0)) {
|
||||
if (_mag_baro->take(HAL_SEMAPHORE_BLOCK_FOREVER)) {
|
||||
// accumulate into averaging filter
|
||||
_sum += raw_field;
|
||||
_count++;
|
||||
|
Loading…
Reference in New Issue
Block a user