mirror of https://github.com/ArduPilot/ardupilot
SITL: emit hit-ground via mavlink
This lets autotest look for it
This commit is contained in:
parent
78b1b54bb7
commit
4cc7df8e15
|
@ -29,6 +29,7 @@
|
|||
#include <mmsystem.h>
|
||||
#endif
|
||||
|
||||
#include <GCS_MAVLink/GCS.h>
|
||||
#include <AP_Logger/AP_Logger.h>
|
||||
#include <AP_Param/AP_Param.h>
|
||||
#include <AP_Declination/AP_Declination.h>
|
||||
|
@ -501,7 +502,7 @@ void Aircraft::update_dynamics(const Vector3f &rot_accel)
|
|||
// constrain height to the ground
|
||||
if (on_ground()) {
|
||||
if (!was_on_ground && AP_HAL::millis() - last_ground_contact_ms > 1000) {
|
||||
printf("Hit ground at %f m/s\n", velocity_ef.z);
|
||||
gcs().send_text(MAV_SEVERITY_INFO, "Hit ground at %f m/s", velocity_ef.z);
|
||||
last_ground_contact_ms = AP_HAL::millis();
|
||||
}
|
||||
position.z = -(ground_level + frame_height - home.alt * 0.01f + ground_height_difference());
|
||||
|
|
Loading…
Reference in New Issue