mirror of https://github.com/ArduPilot/ardupilot
AP_NavEKF2: send airspeed variance over mavlink
This commit is contained in:
parent
0b03562cf2
commit
fb0deba3aa
|
@ -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
|
||||
|
|
Loading…
Reference in New Issue