mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-31 04:58:30 -04:00
SITL: add a hagl method to aircraft
This commit is contained in:
parent
f1c23dc9be
commit
f8918d15b1
@ -132,12 +132,19 @@ float Aircraft::ground_height_difference() const
|
|||||||
return 0.0f;
|
return 0.0f;
|
||||||
}
|
}
|
||||||
|
|
||||||
|
/*
|
||||||
|
return current height above ground level (metres)
|
||||||
|
*/
|
||||||
|
float Aircraft::hagl() const
|
||||||
|
{
|
||||||
|
return (-position.z) + home.alt*0.01f - ground_level - frame_height - ground_height_difference();
|
||||||
|
}
|
||||||
/*
|
/*
|
||||||
return true if we are on the ground
|
return true if we are on the ground
|
||||||
*/
|
*/
|
||||||
bool Aircraft::on_ground() const
|
bool Aircraft::on_ground() const
|
||||||
{
|
{
|
||||||
return (-position.z) + home.alt*0.01f <= ground_level + frame_height + ground_height_difference();
|
return hagl() <= 0;
|
||||||
}
|
}
|
||||||
|
|
||||||
/*
|
/*
|
||||||
|
@ -173,6 +173,9 @@ protected:
|
|||||||
|
|
||||||
bool on_ground() const;
|
bool on_ground() const;
|
||||||
|
|
||||||
|
// returns height above ground level in metres
|
||||||
|
float hagl() const; // metres
|
||||||
|
|
||||||
/* update location from position */
|
/* update location from position */
|
||||||
void update_position(void);
|
void update_position(void);
|
||||||
|
|
||||||
|
Loading…
Reference in New Issue
Block a user