From 3eb368b027207e876ae3abbec508aa08f76bcd83 Mon Sep 17 00:00:00 2001 From: Youssof Date: Tue, 18 Jun 2024 11:54:42 -0300 Subject: [PATCH] Decrease buffer size and slowdown send rate --- src/CommunicationManager.cpp | 6 +++--- src/Xbee.cpp | 2 +- 2 files changed, 4 insertions(+), 4 deletions(-) diff --git a/src/CommunicationManager.cpp b/src/CommunicationManager.cpp index 4fc86a5..4cad263 100644 --- a/src/CommunicationManager.cpp +++ b/src/CommunicationManager.cpp @@ -22,7 +22,7 @@ namespace Xbee //***************************************************************************** CommunicationManager::CommunicationManager() : START_DLIMITER(static_cast(0x7E)), - LOOP_RATE(10), /* 10 fps */ + LOOP_RATE(5), /* 5 fps */ DEFAULT_RATE_DIVIDER_RSSI(5), DEFAULT_RATE_DIVIDER_PACKET_LOSS(20), DEFAULT_RSSI_PAYLOAD_SIZE(10), @@ -427,7 +427,7 @@ bool CommunicationManager::getRosParams() if (node_handle_.getParam("Xbee_In_From_Buzz", out_messages_topic)) { - mavlink_subscriber_ = node_handle_.subscribe(out_messages_topic.c_str(), 100, + mavlink_subscriber_ = node_handle_.subscribe(out_messages_topic.c_str(), 10, &CommunicationManager::Send_Mavlink_Message_Callback, this); success_get_param_in_topic = true; } @@ -439,7 +439,7 @@ bool CommunicationManager::getRosParams() if (node_handle_.getParam("Xbee_Out_To_Buzz", in_messages_topic)) { mavlink_publisher_ = node_handle_.advertise( - in_messages_topic.c_str(), 100); + in_messages_topic.c_str(), 10); success_get_param_out_topic = true; } else diff --git a/src/Xbee.cpp b/src/Xbee.cpp index 51448a5..ad3e5dc 100644 --- a/src/Xbee.cpp +++ b/src/Xbee.cpp @@ -47,7 +47,7 @@ int main(int argc, char *argv[]) { //setupXBee(device, static_cast(baud_rate)); - std::cout << "Going to init !!!!" << std::endl; + std::cout << "Initializing..." << std::endl; if (communication_manager.Init(device, static_cast(baud_rate))) {