[rosserial_windows and rosserial_server] Increased buffer size from 1023 to 2047 Byte and get unsteady subscribe callbacks
Hello,
I am using rosserial_server socket_node and rosserial_windows to transmit Float32MultiArray messages from Windows to Linux. I transmit 354 float values per message which gives me a message size a bit largar than 1416 byte. My transmission rate is 60Hz (16,7ms interval). To be able to handle messages of size 1416byte, I increased the buffer size to 2047byte in: rosserial_windows->ros_lib->ros->node_handle.h:
[...]
int INPUT_SIZE=2047, // buffer size in byte, standard is 512
int OUTPUT_SIZE=2047> // buffer size in byte, standard is 512
[...]
rosserial_server->include->session.h:
[...]
enum { buffer_max = 2047 };
[...]
On the Linux side, I always receive the all messages at average 60Hz. With test message of size 45 byte (< 1023byte) everything works fine and the subscriber callback function is called every 16,7ms.
The problem is, once I raise the message size to 1416 byte, the subscribe callback function is called irregularly. Often two or three callbacks are called simultaneously, followed by ~35ms (216,7ms) or ~50ms (316,7ms) of no subscribe callback. (see attached output files)
The question is: Can I raise the buffer size to 2047 byte, while maintaining a constant subscribe callback from rosserial_server? If yes, what else do I need to adjust?
Thank you very much in advance!
My dummy subscriber and callback look like this:
int testCallback(){
ROS_INFO_STREAM("Time until last callback: " << (ros::Time::now().toSec() - lastReceiveTime.toSec())*1000 << "ms");
lastReceiveTime = ros::Time::now();
}
int main(){
[...]
std::string test_topic = "/test_data";
ros::Subscriber subscriber;
subscriber = nh.subscribe<std_msgs::Float32MultiArray>(test_topic, 5, boost::bind(testCallback));
ros::Rate testRate(60);
while(nh.ok()){
ros::getGlobalCallbackQueue() -> callAvailable();
testRate.sleep();
}
[...]
}
Output with message size 45 byte+Overhead:
[ INFO] [1493214005.231578721]: Time until last callback: 15.6999ms
[ INFO] [1493214005.248166332]: Time until last callback: 16.3519ms
[ INFO] [1493214005.265797264]: Time until last callback: 17.4086ms
[ INFO] [1493214005.282388842]: Time until last callback: 16.3724ms
Output with message size: 1416 byte+Overhead
[ INFO] [1493214119.088105762]: Time until last callback: 32.1336ms
[ INFO] [1493214119.088445591]: Time until last callback: 0.015974ms
[ INFO] [1493214119.138672379]: Time until last callback: 49.8383ms
[ INFO] [1493214119.138922372]: Time until last callback: 0.0116825ms
[ INFO] [1493214119.139050833]: Time until last callback: 0.00834465ms
[ INFO] [1493214119.172931266]: Time until last callback: 33.7234ms
[ INFO] [1493214119.173166752]: Time until last callback: 0.010252ms
[ INFO] [1493214119.189014642]: Time until last callback: 15.7049ms
[ INFO] [1493214119.205796725]: Time until last callback: 16.4757ms
Do you still get the issue when you try with rosserial_python rather than rosserial_server? Comparing the two would help narrow down the source of the issue.
Also, what does Wireshark say? That can be helpful as a source of truth about what's actually going back and forth.
@bluetjens Hi, did you figured out the problem in the end? Any information on this would be helpful, thank you!