Copter: move try_send_message handling of EKF_STATUS_REPORT up
This commit is contained in:
parent
424d243c7f
commit
78d2c52a3f
@ -343,11 +343,6 @@ bool GCS_MAVLINK_Copter::try_send_message(enum ap_message id)
|
||||
#endif
|
||||
break;
|
||||
|
||||
case MSG_EKF_STATUS_REPORT:
|
||||
CHECK_PAYLOAD_SIZE(EKF_STATUS_REPORT);
|
||||
copter.ahrs.send_ekf_status_report(chan);
|
||||
break;
|
||||
|
||||
case MSG_WIND:
|
||||
case MSG_SERVO_OUT:
|
||||
case MSG_AOA_SSA:
|
||||
|
Loading…
Reference in New Issue
Block a user