MissionFeasibiltyChecker: Do not delete uorb data on reset.

This commit is contained in:
Konrad 2024-03-06 13:25:23 +01:00 committed by Silvan Fuhrer
parent 7fb584adbe
commit 6c6142ba79
1 changed files with 6 additions and 7 deletions

View File

@ -46,13 +46,6 @@ FeasibilityChecker::FeasibilityChecker() :
void FeasibilityChecker::reset()
{
_is_landed = false;
_home_alt_msl = NAN;
_home_lat_lon = matrix::Vector2d((double)NAN, (double)NAN);
_current_position_lat_lon = matrix::Vector2d((double)NAN, (double)NAN);
_vehicle_type = VehicleType::RotaryWing;
_mission_validity_failed = false;
_takeoff_failed = false;
_land_pattern_validity_failed = false;
@ -86,10 +79,16 @@ void FeasibilityChecker::updateData()
if (home.valid_hpos) {
_home_lat_lon = matrix::Vector2d(home.lat, home.lon);
} else {
_home_lat_lon = matrix::Vector2d((double)NAN, (double)NAN);
}
if (home.valid_alt) {
_home_alt_msl = home.alt;
} else {
_home_alt_msl = NAN;
}
}