Browse Source

Plane: fix format string warnings

master
Peter Barker 6 years ago committed by Andrew Tridgell
parent
commit
b12f620233
  1. 2
      ArduPlane/ArduPlane.cpp
  2. 6
      ArduPlane/commands_logic.cpp
  3. 2
      ArduPlane/takeoff.cpp

2
ArduPlane/ArduPlane.cpp

@ -532,7 +532,7 @@ void Plane::set_flight_stage(AP_Vehicle::FixedWing::FlightStage fs) @@ -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;

6
ArduPlane/commands_logic.cpp

@ -528,8 +528,8 @@ bool Plane::verify_takeoff() @@ -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) @@ -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;

2
ArduPlane/takeoff.cpp

@ -210,7 +210,7 @@ int16_t Plane::get_takeoff_pitch_min_cd(void) @@ -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;
}
}

Loading…
Cancel
Save