From 237bdfdb61ea335df7c2baca0588fd7fa3e26c6d Mon Sep 17 00:00:00 2001 From: Lorenz Meier Date: Sat, 14 May 2016 18:22:34 +0200 Subject: [PATCH] EKF: Be less verbose, avoid floating ng point printing stack smashing --- .../ekf_att_pos_estimator/ekf_att_pos_estimator_main.cpp | 3 --- 1 file changed, 3 deletions(-) diff --git a/src/modules/ekf_att_pos_estimator/ekf_att_pos_estimator_main.cpp b/src/modules/ekf_att_pos_estimator/ekf_att_pos_estimator_main.cpp index e96ca53966..9432c5d2de 100644 --- a/src/modules/ekf_att_pos_estimator/ekf_att_pos_estimator_main.cpp +++ b/src/modules/ekf_att_pos_estimator/ekf_att_pos_estimator_main.cpp @@ -699,8 +699,6 @@ void AttitudePositionEstimatorEKF::task_main() _filter_ref_offset = -_baro.altitude; - PX4_INFO("filter ref off: baro_alt: %8.4f", (double)_filter_ref_offset); - } else { if (!_gps_initialized && _gpsIsGood) { @@ -785,7 +783,6 @@ void AttitudePositionEstimatorEKF::initReferencePosition(hrt_abstime timestamp, _local_pos.ref_timestamp = timestamp; map_projection_init(&_pos_ref, lat, lon); - mavlink_and_console_log_info(&_mavlink_log_pub, "[ekf] ref: LA %.4f,LO %.4f,ALT %.2f", lat, lon, (double)gps_alt); } }