mirror of https://github.com/ArduPilot/ardupilot
AP_Compass: Change from magic number 0 to definition name.
This commit is contained in:
parent
f5c3de2a61
commit
bc7b2144e7
|
@ -69,7 +69,7 @@ AP_Compass_AK09916::AP_Compass_AK09916(Compass &compass,
|
|||
|
||||
bool AP_Compass_AK09916::init()
|
||||
{
|
||||
if (!dev->get_semaphore()->take(0)) {
|
||||
if (!dev->get_semaphore()->take(HAL_SEMAPHORE_BLOCK_FOREVER)) {
|
||||
return false;
|
||||
}
|
||||
|
||||
|
@ -147,7 +147,7 @@ void AP_Compass_AK09916::timer()
|
|||
/* correct raw_field for known errors */
|
||||
correct_field(field, compass_instance);
|
||||
|
||||
if (_sem->take(0)) {
|
||||
if (_sem->take(HAL_SEMAPHORE_BLOCK_FOREVER)) {
|
||||
accum += field;
|
||||
accum_count++;
|
||||
_sem->give();
|
||||
|
|
|
@ -250,7 +250,7 @@ void AP_Compass_AK8963::_update()
|
|||
// correct raw_field for known errors
|
||||
correct_field(raw_field, _compass_instance);
|
||||
|
||||
if (_sem->take(0)) {
|
||||
if (_sem->take(HAL_SEMAPHORE_BLOCK_FOREVER)) {
|
||||
_mag_x_accum += raw_field.x;
|
||||
_mag_y_accum += raw_field.y;
|
||||
_mag_z_accum += raw_field.z;
|
||||
|
|
|
@ -261,7 +261,7 @@ void AP_Compass_HMC5843::_timer()
|
|||
// correct raw_field for known errors
|
||||
correct_field(raw_field, _compass_instance);
|
||||
|
||||
if (_sem->take(0)) {
|
||||
if (_sem->take(HAL_SEMAPHORE_BLOCK_FOREVER)) {
|
||||
_mag_x_accum += raw_field.x;
|
||||
_mag_y_accum += raw_field.y;
|
||||
_mag_z_accum += raw_field.z;
|
||||
|
|
|
@ -167,7 +167,7 @@ void AP_Compass_IST8310::timer()
|
|||
/* correct raw_field for known errors */
|
||||
correct_field(field, _instance);
|
||||
|
||||
if (_sem->take(0)) {
|
||||
if (_sem->take(HAL_SEMAPHORE_BLOCK_FOREVER)) {
|
||||
_accum += field;
|
||||
_accum_count++;
|
||||
_sem->give();
|
||||
|
|
|
@ -78,7 +78,7 @@ AP_Compass_LIS3MDL::AP_Compass_LIS3MDL(Compass &compass,
|
|||
|
||||
bool AP_Compass_LIS3MDL::init()
|
||||
{
|
||||
if (!dev->get_semaphore()->take(0)) {
|
||||
if (!dev->get_semaphore()->take(HAL_SEMAPHORE_BLOCK_FOREVER)) {
|
||||
return false;
|
||||
}
|
||||
|
||||
|
@ -169,7 +169,7 @@ void AP_Compass_LIS3MDL::timer()
|
|||
/* correct raw_field for known errors */
|
||||
correct_field(field, compass_instance);
|
||||
|
||||
if (_sem->take(0)) {
|
||||
if (_sem->take(HAL_SEMAPHORE_BLOCK_FOREVER)) {
|
||||
accum += field;
|
||||
accum_count++;
|
||||
_sem->give();
|
||||
|
|
|
@ -360,7 +360,7 @@ void AP_Compass_LSM303D::_update()
|
|||
// correct raw_field for known errors
|
||||
correct_field(raw_field, _compass_instance);
|
||||
|
||||
if (_sem->take(0)) {
|
||||
if (_sem->take(HAL_SEMAPHORE_BLOCK_FOREVER)) {
|
||||
_mag_x_accum += raw_field.x;
|
||||
_mag_y_accum += raw_field.y;
|
||||
_mag_z_accum += raw_field.z;
|
||||
|
|
|
@ -168,7 +168,7 @@ void AP_Compass_LSM9DS1::_update(void)
|
|||
// correct raw_field for known errors
|
||||
correct_field(raw_field, _compass_instance);
|
||||
|
||||
if (_sem->take(0)) {
|
||||
if (_sem->take(HAL_SEMAPHORE_BLOCK_FOREVER)) {
|
||||
_mag_x_accum += raw_field.x;
|
||||
_mag_y_accum += raw_field.y;
|
||||
_mag_z_accum += raw_field.z;
|
||||
|
|
Loading…
Reference in New Issue