mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-03 06:28:27 -04:00
AP_Airspeed: clarify mavlink packet assembly is re-ordered field order
This makes it clear that the fields must be arranged according to the order in the header file rather than that in the message definition
This commit is contained in:
parent
12cb09a3f4
commit
ef8baf28ad
@ -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);
|
||||
|
Loading…
Reference in New Issue
Block a user