|
|
|
@ -568,9 +568,9 @@ float Plane::rangefinder_correction(void)
@@ -568,9 +568,9 @@ float Plane::rangefinder_correction(void)
|
|
|
|
|
*/ |
|
|
|
|
void Plane::rangefinder_height_update(void) |
|
|
|
|
{ |
|
|
|
|
float distance = rangefinder.distance_cm()*0.01f; |
|
|
|
|
float distance = rangefinder.distance_cm_orient(ROTATION_PITCH_270)*0.01f; |
|
|
|
|
|
|
|
|
|
if ((rangefinder.status() == RangeFinder::RangeFinder_Good) && home_is_set != HOME_UNSET) { |
|
|
|
|
if ((rangefinder.status_orient(ROTATION_PITCH_270) == RangeFinder::RangeFinder_Good) && home_is_set != HOME_UNSET) { |
|
|
|
|
if (!rangefinder_state.have_initial_reading) { |
|
|
|
|
rangefinder_state.have_initial_reading = true; |
|
|
|
|
rangefinder_state.initial_range = distance; |
|
|
|
@ -586,10 +586,10 @@ void Plane::rangefinder_height_update(void)
@@ -586,10 +586,10 @@ void Plane::rangefinder_height_update(void)
|
|
|
|
|
// to misconfiguration or a faulty sensor
|
|
|
|
|
if (rangefinder_state.in_range_count < 10) { |
|
|
|
|
if (!is_equal(distance, rangefinder_state.last_distance) && |
|
|
|
|
fabsf(rangefinder_state.initial_range - distance) > 0.05f * rangefinder.max_distance_cm()*0.01f) { |
|
|
|
|
fabsf(rangefinder_state.initial_range - distance) > 0.05f * rangefinder.max_distance_cm_orient(ROTATION_PITCH_270)*0.01f) { |
|
|
|
|
rangefinder_state.in_range_count++; |
|
|
|
|
} |
|
|
|
|
if (fabsf(rangefinder_state.last_distance - distance) > rangefinder.max_distance_cm()*0.01*0.2) { |
|
|
|
|
if (fabsf(rangefinder_state.last_distance - distance) > rangefinder.max_distance_cm_orient(ROTATION_PITCH_270)*0.01*0.2) { |
|
|
|
|
// changes by more than 20% of full range will reset counter
|
|
|
|
|
rangefinder_state.in_range_count = 0; |
|
|
|
|
} |
|
|
|
|