mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-02-06 07:53:57 -04:00
SITL: only report ground contact at most once per second
This commit is contained in:
parent
dd07ffce08
commit
62b2a2117d
@ -359,8 +359,9 @@ void Aircraft::update_dynamics(const Vector3f &rot_accel)
|
||||
|
||||
// constrain height to the ground
|
||||
if (on_ground(position)) {
|
||||
if (!on_ground(old_position)) {
|
||||
if (!on_ground(old_position) && AP_HAL::millis() - last_ground_contact_ms > 1000) {
|
||||
printf("Hit ground at %f m/s\n", velocity_ef.z);
|
||||
last_ground_contact_ms = AP_HAL::millis();
|
||||
}
|
||||
position.z = -(ground_level + frame_height - home.alt*0.01f);
|
||||
}
|
||||
|
@ -159,6 +159,7 @@ protected:
|
||||
private:
|
||||
uint64_t last_time_us = 0;
|
||||
uint32_t frame_counter = 0;
|
||||
uint32_t last_ground_contact_ms;
|
||||
const uint32_t min_sleep_time;
|
||||
};
|
||||
|
||||
|
Loading…
Reference in New Issue
Block a user