diff --git a/src/PacketsHandler.cpp b/src/PacketsHandler.cpp index 0bd0ed9..a71eb24 100644 --- a/src/PacketsHandler.cpp +++ b/src/PacketsHandler.cpp @@ -106,7 +106,7 @@ void PacketsHandler::Handle_Mavlink_Message(const mavros_msgs::Mavlink::ConstPtr fragmented_packet->at(i)->append(serialized_packet->c_str() + offset, NBR_of_bytes); offset += NBR_of_bytes; } - std::cout << "[Debug: ] Multi packets received from buzz" << std::endl; + std::cout << "[Debug: ] Multi packets received from buzz with framgents: "<msgid, fragmented_packet}); } else if (serialized_packet->size() < XBEE_NETWORK_MTU) @@ -126,7 +126,7 @@ void PacketsHandler::Process_Fragment(std::shared_ptr fragment) uint16_t offset = static_cast( static_cast(static_cast(fragment->at(4))) << 8 | static_cast(static_cast(fragment->at(5)))); - std::cout << "[Debug: ] Fragment received with id"<< fragment_ID<< std::endl; + std::cout << "[Debug: ] Fragment received with id"<< (int)fragment_ID<< std::endl; assembly_map_it_ = packets_assembly_map_.find(node_8_bits_address); if (assembly_map_it_ != packets_assembly_map_.end())