From cd1eb3db19c35424c875d482318212e4c0f27006 Mon Sep 17 00:00:00 2001 From: vivek-shankar Date: Sun, 29 Jan 2017 14:24:30 -0500 Subject: [PATCH] reduced message size and debug --- src/CommunicationManager.cpp | 12 ++++++------ 1 file changed, 6 insertions(+), 6 deletions(-) diff --git a/src/CommunicationManager.cpp b/src/CommunicationManager.cpp index f673433..651ec3d 100644 --- a/src/CommunicationManager.cpp +++ b/src/CommunicationManager.cpp @@ -455,11 +455,11 @@ inline void CommunicationManager::Check_In_Messages_and_Transfer_To_Topics() Generate_Transmit_Request_Frame(temporary_buffer, &frame,tot); serial_device_.Send_Frame(frame); /*tmp*/ - uint64_t tmp_printer; - sscanf(frame.c_str(), "%" PRIu64 " ",&tmp_printer); - uint16_t* tmp_printer_16 =u64_cvt_u16(tmp_printer); - std::cout << "Send ACK for " < >::iterator it = multi_msgs_receive.find(header[2]); if(it!=multi_msgs_receive.end()){ @@ -604,7 +604,7 @@ inline void CommunicationManager::Send_Mavlink_Message_Callback( const mavros_msgs::Mavlink::ConstPtr& mavlink_msg) { const unsigned short MAX_BUFFER_SIZE = 211; /* 20 (length(uint64_t)) * 10 (max int number) + 10 (spaces) + 1 */ - const unsigned short MAX_NBR_OF_INT64 = 21; + const unsigned short MAX_NBR_OF_INT64 = 25; char temporary_buffer[MAX_BUFFER_SIZE]; std::string frame; int converted_bytes = 0;