mirror of https://github.com/ArduPilot/ardupilot
Copter: compiler warnings: unnecessary float promotion
This commit is contained in:
parent
514c83301c
commit
3f614534b3
|
@ -218,7 +218,7 @@ static void flip_run()
|
|||
}
|
||||
|
||||
// output pilot's throttle without angle boost
|
||||
if (throttle_out == 0.0f) {
|
||||
if (throttle_out == 0) {
|
||||
attitude_control.set_throttle_out_unstabilized(0,false,g.throttle_filt);
|
||||
} else {
|
||||
attitude_control.set_throttle_out(throttle_out, false, g.throttle_filt);
|
||||
|
|
Loading…
Reference in New Issue