mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-03-03 12:14:10 -04:00
APM_Control: avoid some float conversion warnings
This commit is contained in:
parent
3390224491
commit
198ada2b42
@ -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);
|
||||||
}
|
}
|
||||||
|
|
||||||
|
@ -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
|
||||||
|
Loading…
Reference in New Issue
Block a user