From b12f62023319f338e56d5a3314515e296e92a986 Mon Sep 17 00:00:00 2001 From: Peter Barker Date: Fri, 30 Aug 2019 19:57:30 +1000 Subject: [PATCH] Plane: fix format string warnings --- ArduPlane/ArduPlane.cpp | 2 +- ArduPlane/commands_logic.cpp | 6 +++--- ArduPlane/takeoff.cpp | 2 +- 3 files changed, 5 insertions(+), 5 deletions(-) diff --git a/ArduPlane/ArduPlane.cpp b/ArduPlane/ArduPlane.cpp index f4ebe4d49b..6295fa2ab7 100644 --- a/ArduPlane/ArduPlane.cpp +++ b/ArduPlane/ArduPlane.cpp @@ -532,7 +532,7 @@ void Plane::set_flight_stage(AP_Vehicle::FixedWing::FlightStage fs) if (fs == AP_Vehicle::FixedWing::FLIGHT_ABORT_LAND) { gcs().send_text(MAV_SEVERITY_NOTICE, "Landing aborted, climbing to %dm", - auto_state.takeoff_altitude_rel_cm/100); + int(auto_state.takeoff_altitude_rel_cm/100)); } flight_stage = fs; diff --git a/ArduPlane/commands_logic.cpp b/ArduPlane/commands_logic.cpp index ca02ade46b..c548a72bab 100644 --- a/ArduPlane/commands_logic.cpp +++ b/ArduPlane/commands_logic.cpp @@ -528,8 +528,8 @@ bool Plane::verify_takeoff() float takeoff_course = wrap_PI(radians(gps.ground_course_cd()*0.01f)) - steer_state.locked_course_err; takeoff_course = wrap_PI(takeoff_course); steer_state.hold_course_cd = wrap_360_cd(degrees(takeoff_course)*100); - gcs().send_text(MAV_SEVERITY_INFO, "Holding course %ld at %.1fm/s (%.1f)", - steer_state.hold_course_cd, + gcs().send_text(MAV_SEVERITY_INFO, "Holding course %d at %.1fm/s (%.1f)", + (int)steer_state.hold_course_cd, (double)gps.ground_speed(), (double)degrees(steer_state.locked_course_err)); } @@ -741,7 +741,7 @@ bool Plane::verify_loiter_to_alt(const AP_Mission::Mission_Command &cmd) if (labs(loiter.sum_cd) > 1 && (loiter.reached_target_alt || loiter.unable_to_acheive_target_alt)) { // primary goal completed, initialize secondary heading goal if (loiter.unable_to_acheive_target_alt) { - gcs().send_text(MAV_SEVERITY_INFO,"Loiter to alt was stuck at %d", current_loc.alt/100); + gcs().send_text(MAV_SEVERITY_INFO,"Loiter to alt was stuck at %d", int(current_loc.alt/100)); } condition_value = 1; diff --git a/ArduPlane/takeoff.cpp b/ArduPlane/takeoff.cpp index 6f28034d69..702710997e 100644 --- a/ArduPlane/takeoff.cpp +++ b/ArduPlane/takeoff.cpp @@ -210,7 +210,7 @@ int16_t Plane::get_takeoff_pitch_min_cd(void) relative_alt_cm >= 1000 && sec_to_target <= g.takeoff_pitch_limit_reduction_sec) { // make a note of that altitude to use it as a start height for scaling - gcs().send_text(MAV_SEVERITY_INFO, "Takeoff level-off starting at %dm", remaining_height_to_target_cm/100); + gcs().send_text(MAV_SEVERITY_INFO, "Takeoff level-off starting at %dm", int(remaining_height_to_target_cm/100)); auto_state.height_below_takeoff_to_level_off_cm = remaining_height_to_target_cm; } }