mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-03 14:38:30 -04:00
APM_Control: Change from division to multiplication
This commit is contained in:
parent
bf738b03a6
commit
bb72f91dda
@ -173,7 +173,7 @@ int32_t AP_YawController::get_servo_out(float scaler, bool disable_integrator)
|
||||
aspd_min = 1;
|
||||
}
|
||||
|
||||
float delta_time = (float) dt / 1000.0f;
|
||||
float delta_time = (float) dt * 0.001f;
|
||||
|
||||
// Calculate yaw rate required to keep up with a constant height coordinated turn
|
||||
float aspeed;
|
||||
|
Loading…
Reference in New Issue
Block a user