-
Notifications
You must be signed in to change notification settings - Fork 927
regression from #2132: ros::param::set limited to 32 kB on localhost on computers with kernel 4.x #2182
Description
Minimum non-working example (edited at 10 Nov 2021):
#include <ros/ros.h>
int main(int argc, char **argv)
{
ros::init(argc, argv, "node");
ros::NodeHandle nh;
nh.setParam("param", std::string(32654, 'a'));
return 0;
}
Running this program with a ROS master on localhost results in the following error message on some computers:
[ERROR 1630469544.713298952 /node] [setParam] Failed to contact master at [localhost:11311]. Retrying...
It seems that computers running a 4.x kernel have this 32 kB limit whereas 5.x kernels allow 100s of MBs.
Affected:
- Kontron KTQM87 with Core i7 4th gen (amd64 platform, Intel CPU, kernel 4.15)
- NVidia Xavier AGX (arm64 platform, Maxwell CPU, kernel 4.9)
Non-affected:
- Intel NUC 10th gen (amd64 platform, Intel CPU, kernel 5.4)
- Lenovo T14s notebook (amd64 platform, AMD Ryzen CPU, kernel 5.13)
ulimit -a doesn't show any related limitation:
core file size (blocks, -c) unlimited
data seg size (kbytes, -d) unlimited
scheduling priority (-e) 40
file size (blocks, -f) unlimited
pending signals (-i) 63543
max locked memory (kbytes, -l) 65536
max memory size (kbytes, -m) unlimited
open files (-n) 1024
pipe size (512 bytes, -p) 8
POSIX message queues (bytes, -q) 819200
real-time priority (-r) 99
stack size (kbytes, -s) 8192
cpu time (seconds, -t) unlimited
max user processes (-u) 63543
virtual memory (kbytes, -v) unlimited
file locks (-x) unlimited
Decreasing the payload size to 32653 or less makes the program work on all computers.
I tried running the program with XmlRpc client debug logs and here's what I get around the setParam call:
XmlRpcClient::execute: method setParam (_connectionState IDLE).
XmlRpcClient::generateRequest: header is 115 bytes, content-length is 32654.
XmlRpcClient::writeRequest (attempt 1):
POST / HTTP/1.1
User-Agent: XMLRPC++ 0.7
Host: localhost:11311
Content-Type: text/xml
Content-length: 32654
<?xml version="1.0"?>
<methodCall><methodName>setParam</methodName>
<params><param><value>/node</value></param><param><value>/node/param</value></param><param><value>aaaaaaaaaaaaaaaaaaaaaaaaaaaaaaaaaaaaaaaaaaaaaaaaaaaaaaaaaaaaaaaaaaaaaaaaaaaaaaaaaaaaaaaaaaaaaaaaaaaaaaaaaaaaaaaaaaaaaaaaaaaaaaaaaaaaaaaaaaaaaaaaaaaaaaaaaaaaaaaaaaaaaaaaaaaaaaaaaaaaaaaaaaaaaaaaaaaaaaaaaaaaaaaaaaaaaaaaaaaaaaaaaaaaaaaaaaaaaaaaaaaaaaaaaaaaaaaaaaaaaaaaaaaaaaaaaaaaaaaaaaaaaaaaaaaaaaaaaaaaaaaaaaaaaaaaaaaaaaaaaaaaaaaaaaaaaaaaaaaaaaaaaaaaaaaaaaaaaaaaaaaaaaaaaaaaaaaaaaaaaaaaaaaaaaaaaaaaaaaaaaaaaaaaaaaaaaaaaaaaaaaaaaaaaaaaaaaaaaaaaaaaaaaaaaaaaaaaaaaaaaaaaaaaaaaaaaaaaaaaaaaaaaaaaaaaaaaaaaaaaaaaaaaaaaaaaaaaaaaaaaaaaaaaaaaaaaaaaaaaaaaaaaaaaaaaaaaaaaaaaaaaaaaaaaaaaaaaaaaaaaaaaaaaaaaaaaaaaaaaaaaaaaaaaaaaaaaaaaaaaaaaaaaaaaaaaaaaaa
XmlRpcSocket::nbWrite: send/write returned 32768.
XmlRpcSocket::nbWrite: send/write returned -1.
XmlRpcClient::close: fd 3.
XmlRpcSource::close: closing socket 3.
XmlRpcSocket::close: fd 3.
XmlRpcSource::close: done closing socket 3.
[ERROR 1630465298.375945115 /node] [setParam] Failed to contact master at [localhost:11311]. Retrying...
The two nbWrite are interesting - the second one ends with error, but the error message is not outputted. I tried manually reading errno in this case and the error is EPIPE. According to the docs that means that the other side (rosmaster) has closed the connection before it read all the data.
That would point towards a bug in rosmaster, but if I run a similar program using rospy, then I can set parameters as large as I want. So it is probably some incompatibility between the C++ XMLRPC client and Python XMLRPC server.
Also, if ROS master is running on a different computer in LAN, no combination of master/client computers leads to this error. It is solely affecting the case when master and the node are running on the same machine.
Last, if I edit the patch from #2132 and force HTTP/1.1 even on the 4.x kernels, the 32 kB limit is away. @jikawa-az @fujitatomoya @emersonknapp any ideas how to get both the fix from #2132 and allow larger params again?