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

Can ROS Service be used in Real-time Application or Hardware Control?

asked 2017-07-16 11:37:01 -0500

Winston gravatar image

I have 3 related questions about ROS service:

  • Is it a good idea to put a ROS service client in my robot hardware code?
  • Will it increase the time-delay of the hardware node and make my robot unable to work correctly?
  • Does PR2 robot use ROS service in its hardware node?
  • When should I use ROS service compared with ROS messages?)
edit retag flag offensive close merge delete

1 Answer

Sort by ยป oldest newest most voted
3

answered 2017-07-16 15:10:01 -0500

ahendrix gravatar image

ROS does not provide any guarantees about request latency, scheduling delay, processing time or response latency when using services (or topics for that matter). For two nodes running on the same computer these delays are typically between a few milliseconds and a few hundred milliseconds.

Unlike topics, services are synchronous and the client must wait for the transport delay in both the request and the response.

Service clients can be persistent or non-persistent. Persistent clients only have to establish the TCP session once; non-persistent clients create a new TCP session for every request. Setting up the TCP session can add latency, but it increases the client's robustness to changes in the server's address (such as when the server node is stopped and restarted).

With those facts about services in mind, I can help you find answers to some of your questions:

  • Is it a good idea to put a ROS service client in my robot hardware code?
    • This depends on your requirements and how you plan to use the service client. If you are using services in the feedback loop they may work if your system has a lot of inertial or a slow time-constant, but they're clearly not appropriate for systems that need to run at 1kHz or more. If you're just using services for occasional updates and with a good threading model they're probably fine in any system.
  • Will it increase the time-delay of the hardware node and make my robot unable to work correctly?
    • This is completely dependent on how you write you code.
  • Does PR2 robot use ROS service in its hardware node?
    • The PR2 uses services, topics, non-blocking queues, and a few other real-time software techniques in the node that runs the real-time control loops. The PR2 needs to run the control loop at 1kHz, so it also runs the real-time thread with increased priority on a linux kernel with the rt-preempt patches. The combination of these tools is far more important than their presence.
  • When should I use ROS service compared with ROS messages?
edit flag offensive delete link more

Comments

Thank you so much for your reply. I know you are one of the designers of PR2 robot, and I am lucky to have coded on PR2 before. Sorry I have a technical mistake here; I use a ROS service server (not client) in my ROS hadware node. And in another node, I call this service at 66Hz.

Winston gravatar image Winston  ( 2017-07-16 21:54:40 -0500 )edit

My hardware uses EtherCAT and I have tested that when the time latency is more than 18 ms, the EtherCAT will report an error and all the motors are free of torque. So I just wonder the problem is in my frequent (66Hz) call of service to the hardware node. What do you think?

Winston gravatar image Winston  ( 2017-07-16 21:58:10 -0500 )edit

When dealing with real-time systems, do not guess. Measure. If you think your service isn't getting called frequently enough, measure it. You may also want to measure the latency between when the client makes service calls and when they're processed by the server.

ahendrix gravatar image ahendrix  ( 2017-07-17 02:08:38 -0500 )edit

Thank you for your suggestion. I will measure the latency. What I mean is the call of service is actually too frequent, making the service server in hardware node busy with responding to every call. This may lead to interruption of the normal process of the hardware node and cause free of torque.

Winston gravatar image Winston  ( 2017-07-17 02:45:38 -0500 )edit
1

The PR2 solved this by running the realtime communication task in a separate thread from the ROS callbacks, and using non-blocking queues to move data from ROS callbacks into the realtime thread.

ahendrix gravatar image ahendrix  ( 2017-07-17 13:27:05 -0500 )edit

Thank you for this comment. Could you provide me with the related code so that I know how to write this for our own robot?

Winston gravatar image Winston  ( 2017-07-17 19:52:41 -0500 )edit

The PR2 had modular controllers and supported loading new controllers as plugins, so it was complex. Controllers implemented the https://github.com/PR2/pr2_mechanism/... , like https://github.com/PR2/pr2_controller...

ahendrix gravatar image ahendrix  ( 2017-07-17 22:55:28 -0500 )edit

Controllers relied heavily on the classes from the realtime_tools package.

ahendrix gravatar image ahendrix  ( 2017-07-17 22:57:16 -0500 )edit

Question Tools

1 follower

Stats

Asked: 2017-07-16 11:37:01 -0500

Seen: 2,768 times

Last updated: Jul 16 '17