Plane: move try_send_message sending of sensor offsets up
This commit is contained in:
parent
88883c7c7f
commit
0e3ad3f023
@ -475,11 +475,6 @@ bool GCS_MAVLINK_Plane::try_send_message(enum ap_message id)
|
||||
send_scaled_pressure();
|
||||
break;
|
||||
|
||||
case MSG_RAW_IMU3:
|
||||
CHECK_PAYLOAD_SIZE(SENSOR_OFFSETS);
|
||||
send_sensor_offsets(plane.ins, plane.compass);
|
||||
break;
|
||||
|
||||
case MSG_FENCE_STATUS:
|
||||
#if GEOFENCE_ENABLED == ENABLED
|
||||
CHECK_PAYLOAD_SIZE(FENCE_STATUS);
|
||||
|
Loading…
Reference in New Issue
Block a user