|
|
|
@ -54,6 +54,9 @@ void Copter::read_rangefinder(void)
@@ -54,6 +54,9 @@ void Copter::read_rangefinder(void)
|
|
|
|
|
// tilt corrected but unfiltered, not glitch protected alt
|
|
|
|
|
rf_state.alt_cm = tilt_correction * rangefinder.distance_cm_orient(rf_orient); |
|
|
|
|
|
|
|
|
|
// remember inertial alt to allow us to interpolate rangefinder
|
|
|
|
|
rf_state.inertial_alt_cm = inertial_nav.get_altitude(); |
|
|
|
|
|
|
|
|
|
// glitch handling. rangefinder readings more than RANGEFINDER_GLITCH_ALT_CM from the last good reading
|
|
|
|
|
// are considered a glitch and glitch_count becomes non-zero
|
|
|
|
|
// glitches clear after RANGEFINDER_GLITCH_NUM_SAMPLES samples in a row.
|
|
|
|
@ -120,6 +123,24 @@ bool Copter::rangefinder_up_ok()
@@ -120,6 +123,24 @@ bool Copter::rangefinder_up_ok()
|
|
|
|
|
return (rangefinder_up_state.enabled && rangefinder_up_state.alt_healthy); |
|
|
|
|
} |
|
|
|
|
|
|
|
|
|
/*
|
|
|
|
|
get inertially interpolated rangefinder height. Inertial height is |
|
|
|
|
recorded whenever we update the rangefinder height, then we use the |
|
|
|
|
difference between the inertial height at that time and the current |
|
|
|
|
inertial height to give us interpolation of height from rangefinder |
|
|
|
|
*/ |
|
|
|
|
bool Copter::get_rangefinder_height_interpolated_cm(int32_t& ret) |
|
|
|
|
{ |
|
|
|
|
if (!rangefinder_alt_ok()) { |
|
|
|
|
return false; |
|
|
|
|
} |
|
|
|
|
ret = rangefinder_state.alt_cm_filt.get(); |
|
|
|
|
float inertial_alt_cm = inertial_nav.get_altitude(); |
|
|
|
|
ret += inertial_alt_cm - rangefinder_state.inertial_alt_cm; |
|
|
|
|
return true; |
|
|
|
|
} |
|
|
|
|
|
|
|
|
|
|
|
|
|
|
/*
|
|
|
|
|
update RPM sensors |
|
|
|
|
*/ |
|
|
|
|