AP_InertialSensor: Change from magic number 0 to definition name.

This commit is contained in:
murata 2017-02-18 13:34:40 +09:00 committed by Francisco Ferreira
parent eb4d8963d0
commit a3f5b4f319
3 changed files with 8 additions and 8 deletions

View File

@ -152,7 +152,7 @@ void AP_InertialSensor_BMI160::start()
{ {
bool r; bool r;
if (!_dev->get_semaphore()->take(0)) { if (!_dev->get_semaphore()->take(HAL_SEMAPHORE_BLOCK_FOREVER)) {
return; return;
} }
@ -428,7 +428,7 @@ bool AP_InertialSensor_BMI160::_hardware_init()
hal.scheduler->delay(BMI160_POWERUP_DELAY_MSEC); hal.scheduler->delay(BMI160_POWERUP_DELAY_MSEC);
if (!_dev->get_semaphore()->take(0)) { if (!_dev->get_semaphore()->take(HAL_SEMAPHORE_BLOCK_FOREVER)) {
return false; return false;
} }

View File

@ -97,7 +97,7 @@ void AP_InertialSensor_Backend::_notify_new_gyro_raw_sample(uint8_t instance,
delta_coning = delta_coning % delta_angle; delta_coning = delta_coning % delta_angle;
delta_coning *= 0.5f; delta_coning *= 0.5f;
if (_sem->take(0)) { if (_sem->take(HAL_SEMAPHORE_BLOCK_FOREVER)) {
// integrate delta angle accumulator // integrate delta angle accumulator
// the angles and coning corrections are accumulated separately in the // the angles and coning corrections are accumulated separately in the
// referenced paper, but in simulation little difference was found between // referenced paper, but in simulation little difference was found between
@ -187,7 +187,7 @@ void AP_InertialSensor_Backend::_notify_new_accel_raw_sample(uint8_t instance,
_imu.calc_vibration_and_clipping(instance, accel, dt); _imu.calc_vibration_and_clipping(instance, accel, dt);
if (_sem->take(0)) { if (_sem->take(HAL_SEMAPHORE_BLOCK_FOREVER)) {
// delta velocity // delta velocity
_imu._delta_velocity_acc[instance] += accel * dt; _imu._delta_velocity_acc[instance] += accel * dt;
_imu._delta_velocity_acc_dt[instance] += dt; _imu._delta_velocity_acc_dt[instance] += dt;
@ -273,7 +273,7 @@ void AP_InertialSensor_Backend::_publish_temperature(uint8_t instance, float tem
*/ */
void AP_InertialSensor_Backend::update_gyro(uint8_t instance) void AP_InertialSensor_Backend::update_gyro(uint8_t instance)
{ {
if (!_sem->take(0)) { if (!_sem->take(HAL_SEMAPHORE_BLOCK_FOREVER)) {
return; return;
} }
@ -296,7 +296,7 @@ void AP_InertialSensor_Backend::update_gyro(uint8_t instance)
*/ */
void AP_InertialSensor_Backend::update_accel(uint8_t instance) void AP_InertialSensor_Backend::update_accel(uint8_t instance)
{ {
if (!_sem->take(0)) { if (!_sem->take(HAL_SEMAPHORE_BLOCK_FOREVER)) {
return; return;
} }

View File

@ -372,7 +372,7 @@ bool AP_InertialSensor_Invensense::_has_auxiliary_bus()
void AP_InertialSensor_Invensense::start() void AP_InertialSensor_Invensense::start()
{ {
if (!_dev->get_semaphore()->take(0)) { if (!_dev->get_semaphore()->take(HAL_SEMAPHORE_BLOCK_FOREVER)) {
return; return;
} }
@ -825,7 +825,7 @@ bool AP_InertialSensor_Invensense::_check_whoami(void)
bool AP_InertialSensor_Invensense::_hardware_init(void) bool AP_InertialSensor_Invensense::_hardware_init(void)
{ {
if (!_dev->get_semaphore()->take(0)) { if (!_dev->get_semaphore()->take(HAL_SEMAPHORE_BLOCK_FOREVER)) {
return false; return false;
} }