diff --git a/ArduPlane/commands.cpp b/ArduPlane/commands.cpp index 785509eb91..59b93ec5a0 100644 --- a/ArduPlane/commands.cpp +++ b/ArduPlane/commands.cpp @@ -111,8 +111,6 @@ void Plane::init_home() Log_Write_Home_And_Origin(); GCS_MAVLINK::send_home_all(gps.location()); - gcs_send_text_fmt(MAV_SEVERITY_INFO, "GPS alt: %lu", (unsigned long)home.alt); - // Save Home to EEPROM mission.write_home_to_storage(); diff --git a/ArduPlane/commands_logic.cpp b/ArduPlane/commands_logic.cpp index 6b4b8b0b6f..8df203eb99 100644 --- a/ArduPlane/commands_logic.cpp +++ b/ArduPlane/commands_logic.cpp @@ -746,7 +746,7 @@ bool Plane::verify_RTL() update_loiter(abs(g.rtl_radius)); if (auto_state.wp_distance <= (uint32_t)MAX(g.waypoint_radius,0) || reached_loiter_target()) { - gcs_send_text(MAV_SEVERITY_INFO,"Reached HOME"); + gcs_send_text(MAV_SEVERITY_INFO,"Reached RTL location"); return true; } else { return false; diff --git a/ArduPlane/system.cpp b/ArduPlane/system.cpp index 72b0de1f9b..83f0dedddf 100644 --- a/ArduPlane/system.cpp +++ b/ArduPlane/system.cpp @@ -275,11 +275,11 @@ void Plane::startup_ground(void) { set_mode(INITIALISING, MODE_REASON_UNKNOWN); - gcs_send_text(MAV_SEVERITY_INFO," Ground start"); - #if (GROUND_START_DELAY > 0) - gcs_send_text(MAV_SEVERITY_NOTICE," With delay"); + gcs_send_text(MAV_SEVERITY_NOTICE,"Ground start with delay"); delay(GROUND_START_DELAY * 1000); +#else + gcs_send_text(MAV_SEVERITY_INFO,"Ground start"); #endif //INS ground start @@ -312,7 +312,7 @@ void Plane::startup_ground(void) ins.set_raw_logging(should_log(MASK_LOG_IMU_RAW)); ins.set_dataflash(&DataFlash); - gcs_send_text(MAV_SEVERITY_INFO,"Ready to fly"); + gcs_send_text(MAV_SEVERITY_INFO,"Ground start complete"); } enum FlightMode Plane::get_previous_mode() {