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

win_ros service call problems. it's req/res speed is very slow.

asked 2013-11-10 22:19:01 -0500

Injun Park gravatar image

Hi, This is Injun Park from korea(sout)

I am not good at speaking English. I want you to understand my situation^^.

Anyway, since one month ago, I have been developed robot software with win_ros. I think almost of all items in win_ros are good. but only one thing is not.

in topic case(publish/subscription), speed performance is very good. it is over 100Hz.

but service server and client communication's speed is very slow. Req/Res frequency is lower than 10Hz.

To solve this problem, I tested some cases.

  1. I launched roscore on the windows and I launched service server on the windows system.

    -> windows CPP client(MSVC) is versy slow. (under 10hz)

    -> Linux CPP client is good (over 100Hz)

    -> windows Java client is good (Over 100Hz)

as a result, only cpp client version in windows(MSVC version) is too slow.

why the win_ros service/client speed is so slow..?

Has anyone had a similar problem or have any idea what I may be missing?

below code is my testing code of msvc service client.

#include "stdafx.h"
#include <ros/ros.h>
#include <custom_msgs\HelloDude.h>

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

  ros::spinOnce();
  ros::NodeHandle n;
  ros::ServiceClient client = n.serviceClient<custom_msgs::HelloDude>("dude_service");
  //ros::ServiceClient client2 = n.serviceClient<custom_msgs::HelloDude>(

  custom_msgs::HelloDude srv;
  srv.request.greeting = "my testing hello";


  //beginner_tutorials::AddTwoInts srv;
  ros::service::waitForService("dude_service");
  ros::Time begin, end;
  for(int i = 0; i < 50; i++) {
      begin = ros::Time::now();
      if (client.call(srv))
      {
          ROS_INFO("Sum: %s",srv.response.dude.Dude.c_str());
      }
      else
      {
        ROS_ERROR("Failed to call service add_two_ints");
        return 1;
      }
      end = ros::Time::now();
      ROS_INFO("ellapsed : %f\n", end.toSec() - begin.toSec());

  }

  return 0;
}

many thanks. Injun Park

edit retag flag offensive close merge delete

2 Answers

Sort by ยป oldest newest most voted
0

answered 2014-01-16 01:39:08 -0500

dannyknoll gravatar image

sorry I have no solution but I have the same Problem

I have compiled the win-ros source for 64bit with MSVC and Boost 1_55

I tested the "AddTwoInts"-Example in the beginner_tutorials directory and have timings ~110ms for each client.call(srv)

so you are not alone please let me know if you find a solution thanks DannyKnoll

edit flag offensive delete link more

Comments

I answered the question of yours just now ^&^

Injun Park gravatar image Injun Park  ( 2014-01-17 20:10:26 -0500 )edit
4

answered 2014-01-17 20:09:13 -0500

this post is marked as community wiki

This post is a wiki. Anyone with karma >75 is welcome to improve it.

hi, dannyknoll. I didn't solve the problem yet.

but, I know why the service call of win_ros is too slow.

it is why the persistent option of winros service client is not set.

let's see the case of above example what i wrote (HelloDude example),

you can see the follow sentence(code).

ros::ServiceClient client = n.serviceClient<custom_msgs::hellodude>("dude_service");

the root form of the ros::NodeHandle::serviceClient is that the bellow sentence.

NodeHandle::serviceClient (const std::string &service_name, bool persistent=false, const M_string &header_values=M_string())

the second parameter is the persistent option and the default value is "false".

if the persistent option is set false, the service client alwase try to re-connect to the server when the request function is called.

otherwise, the persistent option is set "true", the connection doesn't try to reconnect to the server,

but if any problem of network would be occurred, the connection would be broken(it is exception of program and cause of error).

if you want to know more details, you can refer to the document bellow. http://docs.ros.org/api/roscpp/html/classros_1_1NodeHandle.html

as a result, if you want to grow up the speed of service client, you should set the persistent parameter to "true" of the NodeHandle::serviceCleint() function, but you should overcome the network problem yourself. ros::ServiceClient client = n.serviceClient<custom_msgs::hellodude>("dude_service", true);

In my case, I set the persistent parameter set "true", and catch the network exceptions using the try{}catch{} code block.

I want the information what I wrote above to help you. good luck..

edit flag offensive delete link more

Comments

thanks a lot that solve the problem. Only one question. Wich exception did you catch? Is there one thrown by ros?

dannyknoll gravatar image dannyknoll  ( 2014-01-23 03:02:22 -0500 )edit

Question Tools

Stats

Asked: 2013-11-10 22:19:01 -0500

Seen: 1,260 times

Last updated: Jan 17 '14