AP_OpticalFlow: Change from magic number 0 to definition name.

This commit is contained in:
murata 2017-02-18 13:36:12 +09:00 committed by Francisco Ferreira
parent a3f5b4f319
commit d9dbf6e1eb
6 changed files with 11 additions and 11 deletions

View File

@ -66,7 +66,7 @@ bool AP_OpticalFlow_PX4Flow::scan_buses(void)
if (!tdev) {
continue;
}
if (!tdev->get_semaphore()->take(0)) {
if (!tdev->get_semaphore()->take(HAL_SEMAPHORE_BLOCK_FOREVER)) {
continue;
}
struct i2c_integral_frame frame;

View File

@ -100,7 +100,7 @@ AP_OpticalFlow_Pixart *AP_OpticalFlow_Pixart::detect(OpticalFlow &_frontend)
// setup the device
bool AP_OpticalFlow_Pixart::setup_sensor(void)
{
if (!_dev->get_semaphore()->take(0)) {
if (!_dev->get_semaphore()->take(HAL_SEMAPHORE_BLOCK_FOREVER)) {
AP_HAL::panic("Unable to get bus semaphore");
}
@ -278,7 +278,7 @@ void AP_OpticalFlow_Pixart::timer(void)
float dt = dt_us * 1.0e-6;
const Vector3f &gyro = get_ahrs().get_gyro();
if (_sem->take(0)) {
if (_sem->take(HAL_SEMAPHORE_BLOCK_FOREVER)) {
integral.sum.x += burst.delta_x;
integral.sum.y += burst.delta_y;
integral.sum_us += dt_us;
@ -316,7 +316,7 @@ void AP_OpticalFlow_Pixart::update(void)
state.device_id = 1;
state.surface_quality = burst.squal;
if (integral.sum_us > 0 && _sem->take(0)) {
if (integral.sum_us > 0 && _sem->take(HAL_SEMAPHORE_BLOCK_FOREVER)) {
const Vector2f flowScaler = _flowScaler();
float flowScaleFactorX = 1.0f + 0.001f * flowScaler.x;
float flowScaleFactorY = 1.0f + 0.001f * flowScaler.y;

View File

@ -45,7 +45,7 @@ AP_RangeFinder_Backend *AP_RangeFinder_LightWareI2C::detect(RangeFinder &_ranger
return nullptr;
}
if (sensor->_dev->get_semaphore()->take(0)) {
if (sensor->_dev->get_semaphore()->take(HAL_SEMAPHORE_BLOCK_FOREVER)) {
uint16_t reading_cm;
if (!sensor->get_reading(reading_cm)) {
sensor->_dev->get_semaphore()->give();

View File

@ -68,7 +68,7 @@ AP_RangeFinder_Backend *AP_RangeFinder_MaxsonarI2CXL::detect(RangeFinder &_range
*/
bool AP_RangeFinder_MaxsonarI2CXL::_init(void)
{
if (!_dev->get_semaphore()->take(0)) {
if (!_dev->get_semaphore()->take(HAL_SEMAPHORE_BLOCK_FOREVER)) {
return false;
}
@ -130,7 +130,7 @@ void AP_RangeFinder_MaxsonarI2CXL::_timer(void)
{
uint16_t d;
if (get_reading(d)) {
if (_sem->take(0)) {
if (_sem->take(HAL_SEMAPHORE_BLOCK_FOREVER)) {
distance = d;
new_distance = true;
_sem->give();

View File

@ -142,7 +142,7 @@ static const struct settings_table settings_v2[] = {
*/
bool AP_RangeFinder_PulsedLightLRF::init(void)
{
if (!_dev || !_dev->get_semaphore()->take(0)) {
if (!_dev || !_dev->get_semaphore()->take(HAL_SEMAPHORE_BLOCK_FOREVER)) {
return false;
}
_dev->set_retries(3);

View File

@ -67,7 +67,7 @@ AP_RangeFinder_Backend *AP_RangeFinder_trone::detect(uint8_t bus, RangeFinder &_
*/
bool AP_RangeFinder_trone::init(void)
{
if (!dev->get_semaphore()->take(0)) {
if (!dev->get_semaphore()->take(HAL_SEMAPHORE_BLOCK_FOREVER)) {
return false;
}
@ -138,7 +138,7 @@ void AP_RangeFinder_trone::timer(void)
{
// take a reading
uint16_t distance_cm;
if (collect(distance_cm) && _sem->take(0)) {
if (collect(distance_cm) && _sem->take(HAL_SEMAPHORE_BLOCK_FOREVER)) {
accum.sum += distance_cm;
accum.count++;
_sem->give();
@ -154,7 +154,7 @@ void AP_RangeFinder_trone::timer(void)
*/
void AP_RangeFinder_trone::update(void)
{
if (_sem->take(0)) {
if (_sem->take(HAL_SEMAPHORE_BLOCK_FOREVER)) {
if (accum.count > 0) {
state.distance_cm = accum.sum / accum.count;
accum.sum = 0;