AP_NavEKF2: send airspeed variance over mavlink

This commit is contained in:
Andrew Tridgell 2018-04-30 15:39:59 +10:00
parent 0b03562cf2
commit fb0deba3aa
1 changed files with 1 additions and 2 deletions

View File

@ -588,8 +588,7 @@ void NavEKF2_core::send_status_report(mavlink_channel_t chan)
}
// send message
mavlink_msg_ekf_status_report_send(chan, flags, velVar, posVar, hgtVar, magVar.length(), temp);
mavlink_msg_ekf_status_report_send(chan, flags, velVar, posVar, hgtVar, magVar.length(), temp, tasVar);
}
// report the reason for why the backend is refusing to initialise