AP_Windvane: set true to apparent if no speed sensor

This commit is contained in:
Iampete1 2021-04-14 23:21:50 +01:00 committed by Peter Barker
parent ab1d54745d
commit 29534a7e2d
1 changed files with 4 additions and 0 deletions

View File

@ -295,6 +295,10 @@ void AP_WindVane::update()
// assume true wind has not changed, calculate the apparent wind direction and speed
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;
_speed_true = 0.0f;
}
/*