Browse Source

RangeFinder_I2C: fixed bug with interchanged min max values

- add usage of mode-filter and min-max constrain, similar to MaxsonarXL
mission-4.1.18
Christopher Hrabia 12 years ago committed by rmackay9
parent
commit
744f610409
  1. 11
      libraries/AP_RangeFinder/AP_RangeFinder_MaxsonarI2CXL.cpp

11
libraries/AP_RangeFinder/AP_RangeFinder_MaxsonarI2CXL.cpp

@ -34,8 +34,8 @@ AP_RangeFinder_MaxsonarI2CXL::AP_RangeFinder_MaxsonarI2CXL( FilterInt16 *filter @@ -34,8 +34,8 @@ AP_RangeFinder_MaxsonarI2CXL::AP_RangeFinder_MaxsonarI2CXL( FilterInt16 *filter
healthy(true),
_addr(AP_RANGE_FINDER_MAXSONARI2CXL_DEFAULT_ADDR)
{
max_distance = AP_RANGE_FINDER_MAXSONARI2CXL_MIN_DISTANCE;
min_distance = AP_RANGE_FINDER_MAXSONARI2CXL_MAX_DISTANCE;
min_distance = AP_RANGE_FINDER_MAXSONARI2CXL_MIN_DISTANCE;
max_distance = AP_RANGE_FINDER_MAXSONARI2CXL_MAX_DISTANCE;
}
// Public Methods //////////////////////////////////////////////////////////////
@ -69,6 +69,11 @@ int AP_RangeFinder_MaxsonarI2CXL::read() @@ -69,6 +69,11 @@ int AP_RangeFinder_MaxsonarI2CXL::read()
ret_value = buff[0] << 8 | buff[1];
healthy = true;
}
// ensure distance is within min and max
ret_value = constrain(ret_value, min_distance, max_distance);
ret_value = _mode_filter->apply(ret_value);
return ret_value;
}

Loading…
Cancel
Save