mirror of https://github.com/ArduPilot/ardupilot
SITL: limit on_ground() check to militer accuracy to prevent bouncing
This commit is contained in:
parent
0cf12ad47e
commit
5b0ae42725
|
@ -171,7 +171,7 @@ float Aircraft::hagl() const
|
||||||
*/
|
*/
|
||||||
bool Aircraft::on_ground() const
|
bool Aircraft::on_ground() const
|
||||||
{
|
{
|
||||||
return hagl() <= 0;
|
return hagl() <= 0.001f; // prevent bouncing around ground
|
||||||
}
|
}
|
||||||
|
|
||||||
/*
|
/*
|
||||||
|
|
Loading…
Reference in New Issue