diff --git a/ArduCopter/GCS_Mavlink.cpp b/ArduCopter/GCS_Mavlink.cpp index eed69773dc..124a63e4f3 100644 --- a/ArduCopter/GCS_Mavlink.cpp +++ b/ArduCopter/GCS_Mavlink.cpp @@ -318,11 +318,6 @@ bool GCS_MAVLINK_Copter::try_send_message(enum ap_message id) copter.send_location(chan); break; - case MSG_LOCAL_POSITION: - CHECK_PAYLOAD_SIZE(LOCAL_POSITION_NED); - send_local_position(copter.ahrs); - break; - case MSG_NAV_CONTROLLER_OUTPUT: CHECK_PAYLOAD_SIZE(NAV_CONTROLLER_OUTPUT); copter.send_nav_controller_output(chan); @@ -389,18 +384,13 @@ bool GCS_MAVLINK_Copter::try_send_message(enum ap_message id) #endif break; - case MSG_AHRS: - CHECK_PAYLOAD_SIZE(AHRS); - send_ahrs(copter.ahrs); - break; - case MSG_SIMSTATE: #if CONFIG_HAL_BOARD == HAL_BOARD_SITL CHECK_PAYLOAD_SIZE(SIMSTATE); copter.send_simstate(chan); #endif CHECK_PAYLOAD_SIZE(AHRS2); - send_ahrs2(copter.ahrs); + send_ahrs2(); break; case MSG_MOUNT_STATUS: @@ -418,7 +408,7 @@ bool GCS_MAVLINK_Copter::try_send_message(enum ap_message id) case MSG_OPTICAL_FLOW: #if OPTFLOW == ENABLED CHECK_PAYLOAD_SIZE(OPTICAL_FLOW); - send_opticalflow(copter.ahrs, copter.optflow); + send_opticalflow(copter.optflow); #endif break;