mirror of https://github.com/ArduPilot/ardupilot
Plane: compiler warnings
- float to double in gcs_send_test (x2) - float to bool
This commit is contained in:
parent
1f58e0080a
commit
f1ee129423
|
@ -1356,16 +1356,16 @@ void GCS_MAVLINK::handleMessage(mavlink_message_t* msg)
|
|||
plane.home_is_set = HOME_SET_NOT_LOCKED;
|
||||
result = MAV_RESULT_ACCEPTED;
|
||||
plane.gcs_send_text_fmt(PSTR("set home to %.6f %.6f at %um"),
|
||||
new_home_loc.lat*1.0e-7f,
|
||||
new_home_loc.lng*1.0e-7f,
|
||||
(unsigned)(new_home_loc.alt*0.01f));
|
||||
(double)(new_home_loc.lat*1.0e-7f),
|
||||
(double)(new_home_loc.lng*1.0e-7f),
|
||||
(uint32_t)(new_home_loc.alt*0.01f));
|
||||
}
|
||||
break;
|
||||
}
|
||||
|
||||
case MAV_CMD_DO_AUTOTUNE_ENABLE:
|
||||
// param1 : enable/disable
|
||||
plane.autotune_enable(packet.param1);
|
||||
plane.autotune_enable(!is_zero(packet.param1));
|
||||
break;
|
||||
|
||||
default:
|
||||
|
|
|
@ -662,7 +662,7 @@ bool Plane::verify_altitude_wait(const AP_Mission::Mission_Command &cmd)
|
|||
return true;
|
||||
}
|
||||
if (auto_state.sink_rate > cmd.content.altitude_wait.descent_rate) {
|
||||
gcs_send_text_fmt(PSTR("Reached descent rate %.1f m/s"), auto_state.sink_rate);
|
||||
gcs_send_text_fmt(PSTR("Reached descent rate %.1f m/s"), (double)auto_state.sink_rate);
|
||||
return true;
|
||||
}
|
||||
|
||||
|
|
Loading…
Reference in New Issue