AP_NavEKF3: print extNav buff size

This commit is contained in:
Randy Mackay 2020-06-08 14:40:35 +09:00 committed by Andrew Tridgell
parent c4440a81f4
commit 345029ec67

View File

@ -158,11 +158,12 @@ bool NavEKF3_core::setup_core(uint8_t _imu_index, uint8_t _core_index)
if(!storedOutput.init(imu_buffer_length)) {
return false;
}
gcs().send_text(MAV_SEVERITY_INFO, "EKF3 IMU%u buffers IMU=%u OBS=%u OF=%u, dt=%.4f",
gcs().send_text(MAV_SEVERITY_INFO, "EKF3 IMU%u buffs IMU=%u OBS=%u OF=%u EN:%u, dt=%.4f",
(unsigned)imu_index,
(unsigned)imu_buffer_length,
(unsigned)obs_buffer_length,
(unsigned)flow_buffer_length,
(unsigned)extnav_buffer_length,
(double)dtEkfAvg);
if ((yawEstimator == nullptr) && (frontend->_gsfRunMask & (1U<<core_index))) {