Decrease buffer size and slowdown send rate

This commit is contained in:
Youssof 2024-06-18 11:54:42 -03:00
parent 2a6fe990bc
commit 3eb368b027
2 changed files with 4 additions and 4 deletions

View File

@ -22,7 +22,7 @@ namespace Xbee
//*****************************************************************************
CommunicationManager::CommunicationManager() :
START_DLIMITER(static_cast<unsigned char>(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<mavros_msgs::Mavlink>(
in_messages_topic.c_str(), 100);
in_messages_topic.c_str(), 10);
success_get_param_out_topic = true;
}
else

View File

@ -47,7 +47,7 @@ int main(int argc, char *argv[]) {
//setupXBee(device, static_cast<std::size_t>(baud_rate));
std::cout << "Going to init !!!!" << std::endl;
std::cout << "Initializing..." << std::endl;
if (communication_manager.Init(device, static_cast<std::size_t>(baud_rate)))
{