AP_MotorsMatrix: make const a float

resolves compiler warning
This commit is contained in:
Randy Mackay 2016-04-23 09:34:33 +09:00 committed by Tom Pittenger
parent a50f5bfaf8
commit 7af9892bd1

View File

@ -200,7 +200,7 @@ void AP_MotorsMatrix::output_armed_stabilizing()
_thrust_rpyt_out[i] = roll_thrust * _roll_factor[i] + pitch_thrust * _pitch_factor[i]; _thrust_rpyt_out[i] = roll_thrust * _roll_factor[i] + pitch_thrust * _pitch_factor[i];
if (!is_zero(_yaw_factor[i])){ if (!is_zero(_yaw_factor[i])){
if (yaw_thrust * _yaw_factor[i] > 0.0f) { if (yaw_thrust * _yaw_factor[i] > 0.0f) {
unused_range = fabsf((1.0 - (throttle_thrust_best_rpy + _thrust_rpyt_out[i]))/_yaw_factor[i]); unused_range = fabsf((1.0f - (throttle_thrust_best_rpy + _thrust_rpyt_out[i]))/_yaw_factor[i]);
if (yaw_allowed > unused_range) { if (yaw_allowed > unused_range) {
yaw_allowed = unused_range; yaw_allowed = unused_range;
} }