diff --git a/libraries/AP_Airspeed/Airspeed_Calibration.cpp b/libraries/AP_Airspeed/Airspeed_Calibration.cpp index 9c34146a7d..393f764ea7 100644 --- a/libraries/AP_Airspeed/Airspeed_Calibration.cpp +++ b/libraries/AP_Airspeed/Airspeed_Calibration.cpp @@ -166,18 +166,18 @@ void AP_Airspeed::update_calibration(const Vector3f &vground, int16_t max_airspe void AP_Airspeed::send_airspeed_calibration(const Vector3f &vground) { const mavlink_airspeed_autocal_t packet{ - vground.x, - vground.y, - vground.z, - get_differential_pressure(primary), - AP::baro().get_EAS2TAS(), - param[primary].ratio.get(), - state[primary].calibration.state.x, - state[primary].calibration.state.y, - state[primary].calibration.state.z, - state[primary].calibration.P.a.x, - state[primary].calibration.P.b.y, - state[primary].calibration.P.c.z + vx: vground.x, + vy: vground.y, + vz: vground.z, + diff_pressure: get_differential_pressure(primary), + EAS2TAS: AP::baro().get_EAS2TAS(), + ratio: param[primary].ratio.get(), + state_x: state[primary].calibration.state.x, + state_y: state[primary].calibration.state.y, + state_z: state[primary].calibration.state.z, + Pax: state[primary].calibration.P.a.x, + Pby: state[primary].calibration.P.b.y, + Pcz: state[primary].calibration.P.c.z }; gcs().send_to_active_channels(MAVLINK_MSG_ID_AIRSPEED_AUTOCAL, (const char *)&packet);