APM_Control: avoid some float conversion warnings

This commit is contained in:
Andrew Tridgell 2014-07-08 20:26:20 +10:00
parent 3390224491
commit 198ada2b42
2 changed files with 3 additions and 3 deletions

View File

@ -189,7 +189,7 @@ int32_t AP_RollController::get_rate_out(float desired_rate, float scaler)
*/ */
int32_t AP_RollController::get_servo_out(int32_t angle_err, float scaler, bool disable_integrator) int32_t AP_RollController::get_servo_out(int32_t angle_err, float scaler, bool disable_integrator)
{ {
if (gains.tau < 0.1) { if (gains.tau < 0.1f) {
gains.tau.set(0.1f); gains.tau.set(0.1f);
} }

View File

@ -167,8 +167,8 @@ int32_t AP_SteerController::get_steering_out_lat_accel(float desired_accel)
*/ */
int32_t AP_SteerController::get_steering_out_angle_error(int32_t angle_err) int32_t AP_SteerController::get_steering_out_angle_error(int32_t angle_err)
{ {
if (_tau < 0.1) { if (_tau < 0.1f) {
_tau = 0.1; _tau = 0.1f;
} }
// Calculate the desired steering rate (deg/sec) from the angle error // Calculate the desired steering rate (deg/sec) from the angle error