ROS Resources: Documentation | Support | Discussion Forum | Index | Service Status | ros @ Robotics Stack Exchange |
1 | initial version |
I've observed this memory leak with roscpp services as well. I noiced that the memory usage of a node which was making service calls at 20 Hz rose from 50 MB to over 10 GB when I let my code run continuously over the weekend. I created a simplified test case consisting of two nodes, one which just advertises a service and one that calls that service at 20 Hz. I ran them under valgrind for 5 minutes. I can't upload a tgz of my package, so I've added my test nodes and the valgrind results here. I've also made an issue on the roscpp issue tracker.
I am using Ubuntu 14.04 with ROS Indigo and valgrind version valgrind-3.10.0.SVN.
This is the client code:
// leaky_client.cpp
#include <ros/ros.h>
#include <std_srvs/Empty.h>
int main(int argc, char** argv) {
ros::init(argc, argv, "LeakyClient");
ros::NodeHandle nh;
ros::ServiceClient serviceClient = nh.serviceClient<std_srvs::Empty>("/EmptyService", false);
ros::Rate loopRate(20);
while (ros::ok()) {
// Call the service
ROS_INFO("Calling empty service.");
std_srvs::Empty emptyMsg;
serviceClient.call(emptyMsg);
loopRate.sleep();
}
return EXIT_SUCCESS;
}
This is the server code:
#include <ros/ros.h>
#include <std_srvs/Empty.h>
bool serviceCallback(std_srvs::Empty::Request& req, std_srvs::Empty::Response& res) {
// Does nothing, returns true.
ROS_INFO("Empty service callback.");
return true;
}
int main(int argc, char** argv) {
ros::init(argc, argv, "LeakyClientNode");
ros::NodeHandle nh;
// Create a service callback
ros::ServiceServer serviceServer = nh.advertiseService("EmptyService", &serviceCallback);
ros::spin();
ROS_INFO("SHUTTING DOWN.");
return EXIT_SUCCESS;
}
Relevant section of client valgrind output:
==22603== 8,280 bytes in 3 blocks are possibly lost in loss record 50 of 51
==22603== at 0x4C2CC70: calloc (in /usr/lib/valgrind/vgpreload_memcheck-amd64-linux.so)
==22603== by 0x5E0E687: getifaddrs_internal (ifaddrs.c:402)
==22603== by 0x5E0F1EF: getifaddrs (ifaddrs.c:825)
==22603== by 0x4F0D945: ros::Transport::Transport() (in /opt/ros/indigo/lib/libroscpp.so)
==22603== by 0x4F1592F: ros::TransportTCP::TransportTCP(ros::PollSet*, int) (in /opt/ros/indigo/lib/libroscpp.so)
==22603== by 0x4F22CA5: ros::ServiceManager::createServiceServerLink(std::string const&, bool, std::string const&, std::string const&, std::map<std::string, std::string, std::less<std::string>, std::allocator<std::pair<std::string const, std::string> > > const&) (in /opt/ros/indigo/lib/libroscpp.so)
==22603== by 0x4F02E6E: ros::ServiceClient::call(ros::SerializedMessage const&, ros::SerializedMessage&, std::string const&) (in /opt/ros/indigo/lib/libroscpp.so)
==22603== by 0x40234D: main (service_client.h:102)
==22603==
==22603== 17,746,800 bytes in 6,430 blocks are definitely lost in loss record 51 of 51
==22603== at 0x4C2CC70: calloc (in /usr/lib/valgrind/vgpreload_memcheck-amd64-linux.so)
==22603== by 0x5E0E687: getifaddrs_internal (ifaddrs.c:402)
==22603== by 0x5E0F1EF: getifaddrs (ifaddrs.c:825)
==22603== by 0x4F0D945: ros::Transport::Transport() (in /opt/ros/indigo/lib/libroscpp.so)
==22603== by 0x4F1592F: ros::TransportTCP::TransportTCP(ros::PollSet*, int) (in /opt/ros/indigo/lib/libroscpp.so)
==22603== by 0x4F22CA5: ros::ServiceManager::createServiceServerLink(std::string const&, bool, std::string const&, std::string const&, std::map<std::string, std::string, std::less<std::string>, std::allocator<std::pair<std::string const, std::string> > > const&) (in /opt/ros/indigo/lib/libroscpp.so)
==22603== by 0x4F02E6E: ros::ServiceClient::call(ros::SerializedMessage const&, ros::SerializedMessage&, std::string const&) (in /opt/ros/indigo/lib/libroscpp.so)
==22603== by 0x40234D: main (service_client.h:102)
==22603==
==22603== LEAK SUMMARY:
==22603== definitely lost: 17,755,080 bytes in 6,433 blocks
==22603== indirectly lost: 0 bytes in 0 blocks
==22603== possibly lost: 8,991 bytes in 16 blocks
==22603== still reachable: 2,544 bytes in 33 blocks
==22603== suppressed: 0 bytes in 0 blocks
==22603==
==22603== For counts of detected and suppressed errors, rerun with: -v
==22603== ERROR SUMMARY: 18 errors from 18 contexts (suppressed: 0 from 0)
Relevant section of server valgrind output:
==22592== 8,280 bytes in 3 blocks are possibly lost in loss record 51 of 52
==22592== at 0x4C2CC70: calloc (in /usr/lib/valgrind/vgpreload_memcheck-amd64-linux.so)
==22592== by 0x5BE4687: getifaddrs_internal (ifaddrs.c:402)
==22592== by 0x5BE51EF: getifaddrs (ifaddrs.c:825)
==22592== by 0x4F0D945: ros::Transport::Transport() (in /opt/ros/indigo/lib/libroscpp.so)
==22592== by 0x4F1592F: ros::TransportTCP::TransportTCP(ros::PollSet*, int) (in /opt/ros/indigo/lib/libroscpp.so)
==22592== by 0x4F17FC9: ros::TransportTCP::accept() (in /opt/ros/indigo/lib/libroscpp.so)
==22592== by 0x4F1882A: ros::TransportTCP::socketUpdate(int) (in /opt/ros/indigo/lib/libroscpp.so)
==22592== by 0x4F44EFD: ros::PollSet::update(int) (in /opt/ros/indigo/lib/libroscpp.so)
==22592== by 0x4EE9904: ros::PollManager::threadFunc() (in /opt/ros/indigo/lib/libroscpp.so)
==22592== by 0x66F5A49: ??? (in /usr/lib/x86_64-linux-gnu/libboost_thread.so.1.54.0)
==22592== by 0x6908181: start_thread (pthread_create.c:312)
==22592== by 0x5BCB00C: clone (clone.S:111)
==22592==
==22592== 17,749,560 bytes in 6,431 blocks are definitely lost in loss record 52 of 52
==22592== at 0x4C2CC70: calloc (in /usr/lib/valgrind/vgpreload_memcheck-amd64-linux.so)
==22592== by 0x5BE4687: getifaddrs_internal (ifaddrs.c:402)
==22592== by 0x5BE51EF: getifaddrs (ifaddrs.c:825)
==22592== by 0x4F0D945: ros::Transport::Transport() (in /opt/ros/indigo/lib/libroscpp.so)
==22592== by 0x4F1592F: ros::TransportTCP::TransportTCP(ros::PollSet*, int) (in /opt/ros/indigo/lib/libroscpp.so)
==22592== by 0x4F17FC9: ros::TransportTCP::accept() (in /opt/ros/indigo/lib/libroscpp.so)
==22592== by 0x4F1882A: ros::TransportTCP::socketUpdate(int) (in /opt/ros/indigo/lib/libroscpp.so)
==22592== by 0x4F44EFD: ros::PollSet::update(int) (in /opt/ros/indigo/lib/libroscpp.so)
==22592== by 0x4EE9904: ros::PollManager::threadFunc() (in /opt/ros/indigo/lib/libroscpp.so)
==22592== by 0x66F5A49: ??? (in /usr/lib/x86_64-linux-gnu/libboost_thread.so.1.54.0)
==22592== by 0x6908181: start_thread (pthread_create.c:312)
==22592== by 0x5BCB00C: clone (clone.S:111)
==22592==
==22592== LEAK SUMMARY:
==22592== definitely lost: 17,755,080 bytes in 6,433 blocks
==22592== indirectly lost: 0 bytes in 0 blocks
==22592== possibly lost: 8,991 bytes in 16 blocks
==22592== still reachable: 3,008 bytes in 35 blocks
==22592== suppressed: 0 bytes in 0 blocks
==22592==
==22592== For counts of detected and suppressed errors, rerun with: -v
==22592== ERROR SUMMARY: 17 errors from 17 contexts (suppressed: 0 from 0)