diff --git a/APMrover2/GCS_Mavlink.cpp b/APMrover2/GCS_Mavlink.cpp index 1a83cdf19d..19bd9df669 100644 --- a/APMrover2/GCS_Mavlink.cpp +++ b/APMrover2/GCS_Mavlink.cpp @@ -483,7 +483,6 @@ bool GCS_MAVLINK_Rover::try_send_message(enum ap_message id) case MSG_RPM: case MSG_POSITION_TARGET_GLOBAL_INT: break; // just here to prevent a warning - } return true; } @@ -726,7 +725,6 @@ void GCS_MAVLINK_Rover::handle_change_alt_request(AP_Mission::Mission_Command &c void GCS_MAVLINK_Rover::handleMessage(mavlink_message_t* msg) { switch (msg->msgid) { - case MAVLINK_MSG_ID_REQUEST_DATA_STREAM: { handle_request_data_stream(msg, true); @@ -806,7 +804,6 @@ void GCS_MAVLINK_Rover::handleMessage(mavlink_message_t* msg) // do command switch (packet.command) { - case MAV_CMD_START_RX_PAIR: result = handle_rc_bind(packet); break; @@ -1476,7 +1473,6 @@ void GCS_MAVLINK_Rover::handleMessage(mavlink_message_t* msg) default: handle_common_message(msg); break; - } // end switch } // end handle mavlink @@ -1521,7 +1517,7 @@ void Rover::mavlink_delay_cb() */ void Rover::gcs_send_message(enum ap_message id) { - for (uint8_t i=0; i