diff --git a/src/CommunicationManager.cpp b/src/CommunicationManager.cpp index 753629e..32679e7 100644 --- a/src/CommunicationManager.cpp +++ b/src/CommunicationManager.cpp @@ -677,10 +677,23 @@ inline void CommunicationManager::Send_Mavlink_Message_Callback( else */ if( !( multi_msgs_send_dict.empty() ) ){ /*If the sent message chunk not the last message then send else clear the dict*/ - if( multi_msgs_send_dict.size() - 1 != sending_chunk_no ){ - if(ack_received_dict.size() == (uint16_t) no_of_dev){ + if( (uint16_t)(multi_msgs_send_dict.size() ) - 1 == sending_chunk_no && (uint16_t)ack_received_dict.size() == (uint16_t)no_of_dev){ + std::cout << "clearing multi msg queue and telling buzz"<< std::endl; + multi_msgs_send_dict.clear(); + sending_chunk_no=0; + /*Multi message packet sent tell rosbuzz this*/ + mavros_msgs::Mavlink mavlink_msg; + mavlink_msg.payload64.push_back(XBEE_MESSAGE_CONSTANT); + mavlink_publisher_.publish(mavlink_msg); + + } + + else{ + std::cout << "current size of ack in sender " <