diff --git a/ArduCopter/GCS_Mavlink.cpp b/ArduCopter/GCS_Mavlink.cpp index 02a2b28d8e..1ebe3e114c 100644 --- a/ArduCopter/GCS_Mavlink.cpp +++ b/ArduCopter/GCS_Mavlink.cpp @@ -1474,4 +1474,4 @@ uint8_t GCS_MAVLINK_Copter::high_latency_wind_direction() const } return 0; } -#endif // HAL_HIGH_LATENCY2_ENABLED \ No newline at end of file +#endif // HAL_HIGH_LATENCY2_ENABLED diff --git a/ArduCopter/autoyaw.cpp b/ArduCopter/autoyaw.cpp index ec2d1d3c08..ae34ebc46b 100644 --- a/ArduCopter/autoyaw.cpp +++ b/ArduCopter/autoyaw.cpp @@ -198,7 +198,7 @@ float Mode::AutoYaw::yaw() // keep heading pointing in the direction held in fixed_yaw // with no pilot input allowed const uint32_t now_ms = millis(); - float dt = now_ms - _last_update_ms; + float dt = (now_ms - _last_update_ms) * 0.001; _last_update_ms = now_ms; float yaw_angle_step = constrain_float(_fixed_yaw_offset_cd, - dt * _fixed_yaw_slewrate_cds, dt * _fixed_yaw_slewrate_cds); _fixed_yaw_offset_cd -= yaw_angle_step; @@ -225,7 +225,7 @@ float Mode::AutoYaw::yaw() case AUTO_YAW_ANGLE_RATE:{ const uint32_t now_ms = millis(); - float dt = now_ms - _last_update_ms; + float dt = (now_ms - _last_update_ms) * 0.001; _last_update_ms = now_ms; _yaw_angle_cd += _yaw_rate_cds * dt; return _yaw_angle_cd;