ROS Resources: Documentation | Support | Discussion Forum | Index | Service Status | ros @ Robotics Stack Exchange
Ask Your Question
1

ROS Service/Client Memory leak?

asked 2014-12-18 08:37:31 -0600

JohnDoe2991 gravatar image

Hi everybody,

i'm pretty new to ROS and programming, and I hope someone can help me with this problem:

Everytime I use a service in one of my nodes, the memory usage of the service node and the client node start rising limitless. First I thought I had a bug in one of my nodes or in my custom service, but I tried a modified tutorial and got the same problem. I only commented the ROS_INFO out, made two constant ints and added a loop to the client.

Service:

#include "ros/ros.h"
#include "lidar_sim/AddTwoInts.h"

bool add(lidar_sim::AddTwoInts::Request  &req,
         lidar_sim::AddTwoInts::Response &res)
{
  res.sum = req.a + req.b;
 // ROS_INFO("request: x=%ld, y=%ld", (long int)req.a, (long int)req.b);
 // ROS_INFO("sending back response: [%ld]", (long int)res.sum);
  return true;
}

int main(int argc, char **argv)
{
  ros::init(argc, argv, "add_two_ints_server");
  ros::NodeHandle n;

  ros::ServiceServer service = n.advertiseService("add_two_ints", add);
  ROS_INFO("Ready to add two ints.");
  ros::spin();

  return 0;
}

Client:

#include "ros/ros.h"
#include "lidar_sim/AddTwoInts.h"
#include <cstdlib>

int main(int argc, char **argv)
{
  ros::init(argc, argv, "add_two_ints_client");

  ros::NodeHandle n;
  ros::ServiceClient client = n.serviceClient<lidar_sim::AddTwoInts>("add_two_ints");
  lidar_sim::AddTwoInts srv;
  srv.request.a = 1;
  srv.request.b = 2;
  ros::Rate loop_rate(20);
  while(ros::ok())
  {
  if (client.call(srv))
  {
    //ROS_INFO("Sum: %ld", (long int)srv.response.sum);
  }
  else
  {
    //ROS_ERROR("Failed to call service add_two_ints");
  }

    loop_rate.sleep();
  }
}

After an hour, client and service use, according to gnome-system-monitor, 800MB memory.

I'm using Ubuntu 14.04 64bit and ROS indigo. Valgrind also doesn't show any memory leak.

Thanks for any help!

BTW: lidar_sim is just a package I use to test various nodes in.

edit retag flag offensive close merge delete

Comments

Does this problem occurr for client and subscriber? I noted your client does not call into spinOnce(); Maybe some cleaning up is done there??

Wolf gravatar image Wolf  ( 2014-12-18 09:44:09 -0600 )edit

@Wolf: I thought spinOnce() is only for publisher/subscriber not service/client? I tested it, but it doesn't make any difference. @gvdhoorn: Thank you! It seems that the persistent mode works! I'm just curious why the non persistent mode piles up memory usage and how to get rid of it.

JohnDoe2991 gravatar image JohnDoe2991  ( 2014-12-19 00:58:40 -0600 )edit

I only asked about persistent mode to see if that would change the behaviour you're seeing. You might want to report this to the roscpp issue tracker. However, without valgrind results backing you up, I expect you'll encounter some scepticism.

gvdhoorn gravatar image gvdhoorn  ( 2014-12-19 02:27:47 -0600 )edit
tfoote gravatar image tfoote  ( 2014-12-24 11:15:46 -0600 )edit

3 Answers

Sort by ยป oldest newest most voted
4

answered 2015-02-25 16:47:37 -0600

imcmahon gravatar image

updated 2015-03-16 13:05:10 -0600

Yes, there was a memory leak in roscpp's base Transport class for ROS Indigo. You can see a full explanation in the pull request to fix the issue (which has now been merged): https://github.com/ros/ros_comm/pull/570

The short version is that the Linux function getifaddrs() requires a freeifaddrs() call once the list of network interface structures are no longer needed. Since this issue is present inside roscpp's base class, Transport, every new connection loses a few Kb in memory. This means ROS Service servers then devour memory if left alive for long enough. Fortunately, the fix was a one-liner.

As for debugging ROS with Valgrind, if you attempt to run
valgrind --tool=memcheck --leak-check=yes rosrun package_foo executable_bar,
you will not get useful memory stats. I believe this is due to rosrun spawning your node in a separate process. To get around this, you can call your executable directly:
(from the root of your catkin workspace)
valgrind --tool=memcheck --leak-check=yes ./devel/lib/package_foo/executable_bar
Alternatively, you could write your own launchfile with Valgrind in the launch-prefix.

edit flag offensive delete link more

Comments

This should probably be the accepted answer. My answer provides only a (not too nice) workaround.

gvdhoorn gravatar image gvdhoorn  ( 2015-02-26 01:29:13 -0600 )edit
1

answered 2014-12-18 09:18:48 -0600

gvdhoorn gravatar image

updated 2014-12-27 05:58:17 -0600

If valgrind doesn't show anything, I'd be hesitant to believe there is a leak. Could you try making the service connection persistant and see if that changes anything? See roscpp/Overview/Services - Persistent Connections.

edit flag offensive delete link more

Comments

Was this actually the answer? Was there a leak, or is the reported behaviour by-design?

gvdhoorn gravatar image gvdhoorn  ( 2014-12-27 06:02:44 -0600 )edit

Maybe not the answer, but it solves my problem.

JohnDoe2991 gravatar image JohnDoe2991  ( 2014-12-28 02:53:19 -0600 )edit

Was it actually a problem? Linux aggressively caches everything it can, so even though gnome system monitor may be showing 800MB, that might actually be by-design. Defaulting to persistent connections is not really a solution, as it might cause other issues. Especially on shaky network connections.

gvdhoorn gravatar image gvdhoorn  ( 2014-12-28 03:14:01 -0600 )edit
0

answered 2015-02-25 12:59:50 -0600

grieneis gravatar image

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 ...
(more)
edit flag offensive delete link more

Comments

It would be really appreciated if you could put this in a repository somewhere (github?) and report this issue to the ros_comm issue tracker.

gvdhoorn gravatar image gvdhoorn  ( 2015-02-25 13:30:17 -0600 )edit

I made an issue: https://github.com/ros/ros_comm/issue... . I didn't think of uploading my package to github, but wjwwood made one with my nodes: https://github.com/wjwwood/test_ros_c... .

grieneis gravatar image grieneis  ( 2015-02-25 15:24:40 -0600 )edit

Question Tools

2 followers

Stats

Asked: 2014-12-18 08:37:31 -0600

Seen: 3,702 times

Last updated: Mar 16 '15