Plane: take advantage of rangefinder support in relative_ground_altitude()
This commit is contained in:
parent
55ad1548e4
commit
b3f182157c
@ -826,7 +826,7 @@ private:
|
||||
int32_t get_RTL_altitude();
|
||||
float relative_altitude(void);
|
||||
int32_t relative_altitude_abs_cm(void);
|
||||
float relative_ground_altitude(void);
|
||||
float relative_ground_altitude(bool use_rangefinder_if_available);
|
||||
void set_target_altitude_current(void);
|
||||
void set_target_altitude_current_adjusted(void);
|
||||
void set_target_altitude_location(const Location &loc);
|
||||
|
@ -137,8 +137,12 @@ int32_t Plane::relative_altitude_abs_cm(void)
|
||||
return relative altitude in meters (relative to terrain, if available,
|
||||
or home otherwise)
|
||||
*/
|
||||
float Plane::relative_ground_altitude(void)
|
||||
float Plane::relative_ground_altitude(bool use_rangefinder_if_available)
|
||||
{
|
||||
if (use_rangefinder_if_available && rangefinder_state.in_range) {
|
||||
return rangefinder_state.height_estimate;
|
||||
}
|
||||
|
||||
#if AP_TERRAIN_AVAILABLE
|
||||
float altitude;
|
||||
if (terrain.status() == AP_Terrain::TerrainStatusOK && terrain.height_above_terrain(altitude, true)) {
|
||||
|
Loading…
Reference in New Issue
Block a user