mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-08 17:08:28 -04:00
Plane: remove GCS send_statustext spam
Plane: remove GCS send_statustext spam when recalculating glide slope
This commit is contained in:
parent
8437de8bff
commit
601ab9dad0
@ -182,9 +182,6 @@ void Plane::adjust_landing_slope_for_rangefinder_bump(void)
|
||||
|
||||
// re-calculate auto_state.land_slope with updated prev_WP_loc
|
||||
setup_landing_glide_slope();
|
||||
float new_slope_deg = degrees(atan(auto_state.land_slope));
|
||||
|
||||
GCS_MAVLINK::send_statustext_all(MAV_SEVERITY_INFO, "Landing glide slope re-calculated as %.1f degrees", (double)new_slope_deg);
|
||||
|
||||
if (rangefinder_state.correction >= 0) { // we're too low or object is below us
|
||||
// correction positive means we're too low so we should continue on with
|
||||
@ -198,6 +195,7 @@ void Plane::adjust_landing_slope_for_rangefinder_bump(void)
|
||||
// offset and "perfect" slope.
|
||||
|
||||
// calculate projected slope with projected alt
|
||||
float new_slope_deg = degrees(atan(auto_state.land_slope));
|
||||
float initial_slope_deg = degrees(atan(auto_state.initial_land_slope));
|
||||
|
||||
// is projected slope too steep?
|
||||
|
Loading…
Reference in New Issue
Block a user