mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-09 09:28:31 -04:00
Copter: Commands_logic fix implicit cast to double
This commit is contained in:
parent
385e5badd8
commit
8d4bad0742
@ -752,7 +752,7 @@ bool Copter::verify_payload_place()
|
||||
// we have a valid calibration. Hopefully.
|
||||
nav_payload_place.hover_throttle_level = current_throttle_level;
|
||||
const float hover_throttle_delta = fabsf(nav_payload_place.hover_throttle_level - motors.get_throttle_hover());
|
||||
gcs_send_text_fmt(MAV_SEVERITY_INFO, "hover throttle delta: %f", hover_throttle_delta);
|
||||
gcs_send_text_fmt(MAV_SEVERITY_INFO, "hover throttle delta: %f", static_cast<double>(hover_throttle_delta));
|
||||
nav_payload_place.state = PayloadPlaceStateType_Descending_Start;
|
||||
// fall through
|
||||
};
|
||||
|
Loading…
Reference in New Issue
Block a user