mirror of https://github.com/ArduPilot/ardupilot
AP_Landing: use GPS singleton
This commit is contained in:
parent
d1d5a484ce
commit
a4584431a2
|
@ -96,18 +96,18 @@ bool AP_Landing::type_slope_verify_land(const Location &prev_WP_loc, Location &n
|
|||
if (type_slope_stage != SLOPE_STAGE_FINAL) {
|
||||
type_slope_flags.post_stats = true;
|
||||
if (is_flying && (AP_HAL::millis()-last_flying_ms) > 3000) {
|
||||
gcs().send_text(MAV_SEVERITY_CRITICAL, "Flare crash detected: speed=%.1f", (double)ahrs.get_gps().ground_speed());
|
||||
gcs().send_text(MAV_SEVERITY_CRITICAL, "Flare crash detected: speed=%.1f", (double)AP::gps().ground_speed());
|
||||
} else {
|
||||
gcs().send_text(MAV_SEVERITY_INFO, "Flare %.1fm sink=%.2f speed=%.1f dist=%.1f",
|
||||
(double)height, (double)sink_rate,
|
||||
(double)ahrs.get_gps().ground_speed(),
|
||||
(double)AP::gps().ground_speed(),
|
||||
(double)get_distance(current_loc, next_WP_loc));
|
||||
}
|
||||
type_slope_stage = SLOPE_STAGE_FINAL;
|
||||
}
|
||||
|
||||
|
||||
if (ahrs.get_gps().ground_speed() < 3) {
|
||||
if (AP::gps().ground_speed() < 3) {
|
||||
// reload any airspeed or groundspeed parameters that may have
|
||||
// been set for landing. We don't do this till ground
|
||||
// speed drops below 3.0 m/s as otherwise we will change
|
||||
|
|
Loading…
Reference in New Issue