mirror of https://github.com/ArduPilot/ardupilot
AP_Windvane: true wind if no windspeed fixed
This commit is contained in:
parent
3de3f57501
commit
2f69281040
|
@ -296,8 +296,8 @@ void AP_WindVane::update()
|
|||
update_apparent_wind_dir_from_true();
|
||||
}
|
||||
} else {
|
||||
// only have direction, cant to true wind calcs, set true direction to apparent
|
||||
_direction_true = _direction_apparent_raw + AP::ahrs().yaw;
|
||||
// only have direction, can't do true wind calcs, set true direction to apparent + heading
|
||||
_direction_true_raw = wrap_PI(_direction_apparent_raw + AP::ahrs().yaw);
|
||||
_speed_true = 0.0f;
|
||||
}
|
||||
|
||||
|
|
Loading…
Reference in New Issue