mirror of https://github.com/ArduPilot/ardupilot
GCS_MAVLink: move try_send_message sending of scaled_pressure up
This commit is contained in:
parent
12f62a44ce
commit
c887a5c188
|
@ -2776,6 +2776,11 @@ bool GCS_MAVLINK::try_send_message(const enum ap_message id)
|
|||
send_raw_imu();
|
||||
break;
|
||||
|
||||
case MSG_RAW_IMU2:
|
||||
CHECK_PAYLOAD_SIZE(SCALED_PRESSURE);
|
||||
send_scaled_pressure();
|
||||
break;
|
||||
|
||||
case MSG_RAW_IMU3:
|
||||
CHECK_PAYLOAD_SIZE(SENSOR_OFFSETS);
|
||||
send_sensor_offsets();
|
||||
|
|
Loading…
Reference in New Issue