Merge branch 'master' of github.com:PX4/Firmware

This commit is contained in:
Lorenz Meier
2014-12-21 12:11:07 +01:00

View File

@@ -1052,10 +1052,6 @@ int position_estimator_inav_thread_main(int argc, char *argv[])
landed = false;
landed_time = 0;
}
/* reset xy velocity estimates when landed */
x_est[1] = 0.0f;
y_est[1] = 0.0f;
} else {
if (alt_disp2 < land_disp2 && thrust < params.land_thr) {
if (landed_time == 0) {