mirror of https://github.com/ArduPilot/ardupilot
Copter: Provide downward facing rangefinder readings to proximity lib
This commit is contained in:
parent
e9c0e50185
commit
e727d08266
|
@ -90,12 +90,15 @@ void Copter::read_rangefinder(void)
|
|||
rf_state.last_healthy_ms = now;
|
||||
}
|
||||
|
||||
// send downward facing lidar altitude and health to waypoint and circle navigation libraries
|
||||
// send downward facing lidar altitude and health to the libraries that require it
|
||||
if (rf_orient == ROTATION_PITCH_270) {
|
||||
if (rangefinder_state.alt_healthy || timed_out) {
|
||||
wp_nav->set_rangefinder_alt(rangefinder_state.enabled, rangefinder_state.alt_healthy, rangefinder_state.alt_cm_filt.get());
|
||||
#if MODE_CIRCLE_ENABLED
|
||||
circle_nav->set_rangefinder_alt(rangefinder_state.enabled && wp_nav->rangefinder_used(), rangefinder_state.alt_healthy, rangefinder_state.alt_cm_filt.get());
|
||||
#endif
|
||||
#if PROXIMITY_ENABLED == ENABLED
|
||||
g2.proximity.set_rangefinder_alt(rangefinder_state.enabled, rangefinder_state.alt_healthy, rangefinder_state.alt_cm_filt.get());
|
||||
#endif
|
||||
}
|
||||
}
|
||||
|
|
Loading…
Reference in New Issue