mirror of https://github.com/ArduPilot/ardupilot
Plane: relative_ground_altitude allow passing bool for terrain use
This commit is contained in:
parent
928a923f43
commit
76a10d9b26
|
@ -827,6 +827,7 @@ private:
|
|||
void setup_glide_slope(void);
|
||||
int32_t get_RTL_altitude_cm() const;
|
||||
float relative_ground_altitude(bool use_rangefinder_if_available);
|
||||
float relative_ground_altitude(bool use_rangefinder_if_available, bool use_terrain_if_available);
|
||||
void set_target_altitude_current(void);
|
||||
void set_target_altitude_current_adjusted(void);
|
||||
void set_target_altitude_location(const Location &loc);
|
||||
|
|
|
@ -92,7 +92,7 @@ int32_t Plane::get_RTL_altitude_cm() const
|
|||
return relative altitude in meters (relative to terrain, if available,
|
||||
or home otherwise)
|
||||
*/
|
||||
float Plane::relative_ground_altitude(bool use_rangefinder_if_available)
|
||||
float Plane::relative_ground_altitude(bool use_rangefinder_if_available, bool use_terrain_if_available)
|
||||
{
|
||||
if (use_rangefinder_if_available && rangefinder_state.in_range) {
|
||||
return rangefinder_state.height_estimate;
|
||||
|
@ -109,7 +109,7 @@ float Plane::relative_ground_altitude(bool use_rangefinder_if_available)
|
|||
|
||||
#if AP_TERRAIN_AVAILABLE
|
||||
float altitude;
|
||||
if (target_altitude.terrain_following &&
|
||||
if (use_terrain_if_available &&
|
||||
terrain.status() == AP_Terrain::TerrainStatusOK &&
|
||||
terrain.height_above_terrain(altitude, true)) {
|
||||
return altitude;
|
||||
|
@ -130,6 +130,17 @@ float Plane::relative_ground_altitude(bool use_rangefinder_if_available)
|
|||
return relative_altitude;
|
||||
}
|
||||
|
||||
// Helper for above method using terrain if the vehicle is currently terrain following
|
||||
float Plane::relative_ground_altitude(bool use_rangefinder_if_available)
|
||||
{
|
||||
#if AP_TERRAIN_AVAILABLE
|
||||
return relative_ground_altitude(use_rangefinder_if_available, target_altitude.terrain_following);
|
||||
#else
|
||||
return relative_ground_altitude(use_rangefinder_if_available, false);
|
||||
#endif
|
||||
}
|
||||
|
||||
|
||||
/*
|
||||
set the target altitude to the current altitude. This is used when
|
||||
setting up for altitude hold, such as when releasing elevator in
|
||||
|
|
Loading…
Reference in New Issue