AP_Landing: eliminate GCS_MAVLINK::send_statustext_all

This commit is contained in:
Peter Barker 2017-07-09 14:13:11 +10:00 committed by Francisco Ferreira
parent 1beb1550ae
commit cc150f75c7
3 changed files with 21 additions and 21 deletions

View File

@ -212,7 +212,7 @@ bool AP_Landing::verify_land(const Location &prev_WP_loc, Location &next_WP_loc,
default:
// returning TRUE while executing verify_land() will increment the
// mission index which in many cases will trigger an RTL for end-of-mission
GCS_MAVLINK::send_statustext_all(MAV_SEVERITY_CRITICAL, "Landing configuration error, invalid LAND_TYPE");
gcs().send_text(MAV_SEVERITY_CRITICAL, "Landing configuration error, invalid LAND_TYPE");
success = true;
break;
}
@ -419,14 +419,14 @@ bool AP_Landing::restart_landing_sequence()
mission.set_current_cmd(current_index+1))
{
// if the next immediate command is MAV_CMD_NAV_CONTINUE_AND_CHANGE_ALT to climb, do it
GCS_MAVLINK::send_statustext_all(MAV_SEVERITY_NOTICE, "Restarted landing sequence. Climbing to %dm", cmd.content.location.alt/100);
gcs().send_text(MAV_SEVERITY_NOTICE, "Restarted landing sequence. Climbing to %dm", cmd.content.location.alt/100);
success = true;
}
else if (do_land_start_index != 0 &&
mission.set_current_cmd(do_land_start_index))
{
// look for a DO_LAND_START and use that index
GCS_MAVLINK::send_statustext_all(MAV_SEVERITY_NOTICE, "Restarted landing via DO_LAND_START: %d",do_land_start_index);
gcs().send_text(MAV_SEVERITY_NOTICE, "Restarted landing via DO_LAND_START: %d",do_land_start_index);
success = true;
}
else if (prev_cmd_with_wp_index != AP_MISSION_CMD_INDEX_NONE &&
@ -434,10 +434,10 @@ bool AP_Landing::restart_landing_sequence()
{
// if a suitable navigation waypoint was just executed, one that contains lat/lng/alt, then
// repeat that cmd to restart the landing from the top of approach to repeat intended glide slope
GCS_MAVLINK::send_statustext_all(MAV_SEVERITY_NOTICE, "Restarted landing sequence at waypoint %d", prev_cmd_with_wp_index);
gcs().send_text(MAV_SEVERITY_NOTICE, "Restarted landing sequence at waypoint %d", prev_cmd_with_wp_index);
success = true;
} else {
GCS_MAVLINK::send_statustext_all(MAV_SEVERITY_WARNING, "Unable to restart landing sequence");
gcs().send_text(MAV_SEVERITY_WARNING, "Unable to restart landing sequence");
success = false;
}

View File

@ -287,7 +287,7 @@ bool AP_Landing_Deepstall::override_servos(void)
if (elevator == nullptr) {
// deepstalls are impossible without these channels, abort the process
GCS_MAVLINK::send_statustext_all(MAV_SEVERITY_CRITICAL,
gcs().send_text(MAV_SEVERITY_CRITICAL,
"Deepstall: Unable to find the elevator channels");
request_go_around();
return false;
@ -419,17 +419,17 @@ void AP_Landing_Deepstall::build_approach_path(void)
#ifdef DEBUG_PRINTS
// TODO: Send this information via a MAVLink packet
GCS_MAVLINK::send_statustext_all(MAV_SEVERITY_INFO, "Arc: %3.8f %3.8f",
gcs().send_text(MAV_SEVERITY_INFO, "Arc: %3.8f %3.8f",
(double)(arc.lat / 1e7),(double)( arc.lng / 1e7));
GCS_MAVLINK::send_statustext_all(MAV_SEVERITY_INFO, "Loiter en: %3.8f %3.8f",
gcs().send_text(MAV_SEVERITY_INFO, "Loiter en: %3.8f %3.8f",
(double)(arc_entry.lat / 1e7), (double)(arc_entry.lng / 1e7));
GCS_MAVLINK::send_statustext_all(MAV_SEVERITY_INFO, "Loiter ex: %3.8f %3.8f",
gcs().send_text(MAV_SEVERITY_INFO, "Loiter ex: %3.8f %3.8f",
(double)(arc_exit.lat / 1e7), (double)(arc_exit.lng / 1e7));
GCS_MAVLINK::send_statustext_all(MAV_SEVERITY_INFO, "Extended: %3.8f %3.8f",
gcs().send_text(MAV_SEVERITY_INFO, "Extended: %3.8f %3.8f",
(double)(extended_approach.lat / 1e7), (double)(extended_approach.lng / 1e7));
GCS_MAVLINK::send_statustext_all(MAV_SEVERITY_INFO, "Extended by: %f (%f)", (double)approach_extension_m,
gcs().send_text(MAV_SEVERITY_INFO, "Extended by: %f (%f)", (double)approach_extension_m,
(double)expected_travel_distance);
GCS_MAVLINK::send_statustext_all(MAV_SEVERITY_INFO, "Target Heading: %3.1f", (double)target_heading_deg);
gcs().send_text(MAV_SEVERITY_INFO, "Target Heading: %3.1f", (double)target_heading_deg);
#endif // DEBUG_PRINTS
}
@ -476,7 +476,7 @@ float AP_Landing_Deepstall::predict_travel_distance(const Vector3f wind, const f
if(print) {
// allow printing the travel distances on the final entry as its used for tuning
GCS_MAVLINK::send_statustext_all(MAV_SEVERITY_INFO, "Deepstall: Entry: %0.1f (m) Travel: %0.1f (m)",
gcs().send_text(MAV_SEVERITY_INFO, "Deepstall: Entry: %0.1f (m) Travel: %0.1f (m)",
(double)stall_distance, (double)predicted_travel_distance);
}
@ -506,7 +506,7 @@ float AP_Landing_Deepstall::update_steering()
// panic if no position source is available
// continue the but target just holding the wings held level as deepstall should be a minimal energy
// configuration on the aircraft, and if a position isn't available aborting would be worse
GCS_MAVLINK::send_statustext_all(MAV_SEVERITY_CRITICAL, "Deepstall: No position available. Attempting to hold level");
gcs().send_text(MAV_SEVERITY_CRITICAL, "Deepstall: No position available. Attempting to hold level");
memcpy(&current_loc, &landing_point, sizeof(Location));
}
uint32_t time = AP_HAL::millis();
@ -536,7 +536,7 @@ float AP_Landing_Deepstall::update_steering()
-yaw_rate_limit_rps, yaw_rate_limit_rps) - yaw_rate);
#ifdef DEBUG_PRINTS
GCS_MAVLINK::send_statustext_all(MAV_SEVERITY_INFO, "x: %f e: %f r: %f d: %f",
gcs().send_text(MAV_SEVERITY_INFO, "x: %f e: %f r: %f d: %f",
(double)crosstrack_error,
(double)error,
(double)degrees(yaw_rate),

View File

@ -30,7 +30,7 @@ void AP_Landing::type_slope_do_land(const AP_Mission::Mission_Command& cmd, cons
type_slope_flags.post_stats = false;
type_slope_stage = SLOPE_STAGE_NORMAL;
GCS_MAVLINK::send_statustext_all(MAV_SEVERITY_INFO, "Landing approach start at %.1fm", (double)relative_altitude);
gcs().send_text(MAV_SEVERITY_INFO, "Landing approach start at %.1fm", (double)relative_altitude);
}
void AP_Landing::type_slope_verify_abort_landing(const Location &prev_WP_loc, Location &next_WP_loc, bool &throttle_suppressed)
@ -96,9 +96,9 @@ 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_MAVLINK::send_statustext_all(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)ahrs.get_gps().ground_speed());
} else {
GCS_MAVLINK::send_statustext_all(MAV_SEVERITY_INFO, "Flare %.1fm sink=%.2f speed=%.1f dist=%.1f",
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)get_distance(current_loc, next_WP_loc));
@ -139,7 +139,7 @@ bool AP_Landing::type_slope_verify_land(const Location &prev_WP_loc, Location &n
// this is done before disarm_if_autoland_complete() so that it happens on the next loop after the disarm
if (type_slope_flags.post_stats && !is_armed) {
type_slope_flags.post_stats = false;
GCS_MAVLINK::send_statustext_all(MAV_SEVERITY_INFO, "Distance from LAND point=%.2fm", (double)get_distance(current_loc, next_WP_loc));
gcs().send_text(MAV_SEVERITY_INFO, "Distance from LAND point=%.2fm", (double)get_distance(current_loc, next_WP_loc));
}
// check if we should auto-disarm after a confirmed landing
@ -196,7 +196,7 @@ void AP_Landing::type_slope_adjust_landing_slope_for_rangefinder_bump(AP_Vehicle
// is projected slope too steep?
if (new_slope_deg - initial_slope_deg > slope_recalc_steep_threshold_to_abort) {
GCS_MAVLINK::send_statustext_all(MAV_SEVERITY_INFO, "Landing slope too steep, aborting (%.0fm %.1fdeg)",
gcs().send_text(MAV_SEVERITY_INFO, "Landing slope too steep, aborting (%.0fm %.1fdeg)",
(double)rangefinder_state.correction, (double)(new_slope_deg - initial_slope_deg));
alt_offset = rangefinder_state.correction;
flags.commanded_go_around = true;
@ -265,7 +265,7 @@ void AP_Landing::type_slope_setup_landing_glide_slope(const Location &prev_WP_lo
bool is_first_calc = is_zero(slope);
slope = (sink_height - aim_height) / total_distance;
if (is_first_calc) {
GCS_MAVLINK::send_statustext_all(MAV_SEVERITY_INFO, "Landing glide slope %.1f degrees", (double)degrees(atanf(slope)));
gcs().send_text(MAV_SEVERITY_INFO, "Landing glide slope %.1f degrees", (double)degrees(atanf(slope)));
}