move min/max distance to ground limits to FlightTask ManualAltitude

This commit is contained in:
Daniel Agar
2021-02-21 11:08:26 -05:00
committed by Matthias Grob
parent ecd5e57ab5
commit 0eb327743e
2 changed files with 3 additions and 3 deletions
@@ -227,9 +227,6 @@ protected:
float _dist_to_bottom{}; /**< current height above ground level */
float _dist_to_ground{}; /**< equals _dist_to_bottom if valid, height above home otherwise */
float _min_distance_to_ground{-INFINITY}; /**< min distance to ground constraint */
float _max_distance_to_ground{INFINITY}; /**< max distance to ground constraint */
/**
* Setpoints which the position controller has to execute.
* Setpoints that are set to NAN are not controlled. Not all setpoints can be set at the same time.
@@ -139,6 +139,9 @@ private:
bool _terrain_follow{false}; /**< true when the vehicle is following the terrain height */
bool _terrain_hold{false}; /**< true when vehicle is controlling height above a static ground position */
float _min_distance_to_ground{-INFINITY}; /**< min distance to ground constraint */
float _max_distance_to_ground{INFINITY}; /**< max distance to ground constraint */
/**
* Distance to ground during terrain following.
* If user does not demand velocity change in D-direction and the vehcile