mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-26 18:48:30 -04:00
AP_RangeFinder: use RNGFND_OFFSET for distance offset in PWM and I2C
This commit is contained in:
parent
55019abd71
commit
389148ac54
@ -136,6 +136,7 @@ void AP_RangeFinder_PX4::update(void)
|
||||
|
||||
if (count != 0) {
|
||||
state.distance_cm = sum / count * 100.0f;
|
||||
state.distance_cm += ranger._offset[state.instance];
|
||||
}
|
||||
}
|
||||
|
||||
|
@ -105,7 +105,7 @@ void AP_RangeFinder_PX4_PWM::update(void)
|
||||
_last_pulse_time_ms = now;
|
||||
|
||||
// setup for scaling in meters per millisecond
|
||||
float distance_cm = pwm.pulse_width * 0.1f * scaling;
|
||||
float distance_cm = pwm.pulse_width * 0.1f * scaling + ranger._offset[state.instance];
|
||||
|
||||
if (distance_cm > ranger._max_distance_cm[state.instance] ||
|
||||
distance_cm < ranger._min_distance_cm[state.instance]) {
|
||||
|
@ -44,7 +44,7 @@ const AP_Param::GroupInfo RangeFinder::var_info[] PROGMEM = {
|
||||
|
||||
// @Param: _OFFSET
|
||||
// @DisplayName: rangefinder offset
|
||||
// @Description: Offset in volts for zero distance
|
||||
// @Description: Offset in volts for zero distance for analog rangefinders. Offset added to distance in centimeters for PWM and I2C Lidars
|
||||
// @Units: Volts
|
||||
// @Increment: 0.001
|
||||
AP_GROUPINFO("_OFFSET", 3, RangeFinder, _offset[0], 0.0),
|
||||
|
Loading…
Reference in New Issue
Block a user