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

[ROS2][service][topic]service and topic cooperate

asked 2020-01-19 20:36:32 -0500

lin404 gravatar image

updated 2020-01-27 19:03:32 -0500

The existing system has topics cmd_vel,light_sensors and a service motor_power. I created a node that it will take the msg from light_sensors, then publish msg into cmd_vel. While, I wanna call service motor_power to turn on/off the motor when the msg from light_sensors meets some conditions.

I found many examples that executes topics and services separately, but there is no example that combine the service and topic. Also, I found an article about actions, but I am not quite sure if it is what I want.

What is the right way/design to do so? Calling a service from the callback function of a subscriber? Or there is more proper way? I have tried this, but it did not work for me, and the post is in 2018, a bit old?


#!/usr/bin/env python3
import sys
import rclpy
from rclpy.node import Node
from std_msgs.msg import String
from std_srvs.srv import SetBool

class SubscriberClientAsync(Node):

    def __init__(self):
        super().__init__('sub_client_node')
        self.client = self.create_client(SetBool, 'motor_power')
        self.sub = self.create_subscription(String, 'topic', self.topic_cb)

    def topic_cb(self, msg):
        // How should I implement here to just spin once self.client ?
        if msg.data == 'stop':
            req = SetBool.Request()
            req.data = False
            self.future = self.client.call_async(req)

if __name__ == '__main__':
    rclpy.init()
    node = SubscriberClientAsync()
    try:
        rclpy.spin(node)
    except KeyboardInterrupt:
        pass

    node.destroy_node()
edit retag flag offensive close merge delete

Comments

I simply added self.client.call_async(...) in the subscriber's callback function, and it worked. However, since it is in the loop of topic, I can see the service is called many times till the node is destroyed, instead of spin_once(). As the background of service, the service should only be called once when it is needed. Therefore, I am wondering if it is the proper way to call service inside the callback of subscriber like this? Or is there a way I can combine using spin_once() for calling service inside of a spin() for continuously updating topic?

lin404 gravatar image lin404  ( 2020-01-19 23:49:43 -0500 )edit

1 Answer

Sort by ยป oldest newest most voted
1

answered 2020-01-24 13:35:01 -0500

tfoote gravatar image

You should not try to prevent the service from being called by slowing or inhibiting spinning. Trying to prevent the system from turning over with limiting how much the executor turns over with spin_once is just going to starve your system of callbacks including things like your subscriptions.

If you invoke the service call in every callback it's going to be executed for every incoming message, that's what you're programming it to do. It you only want it to happen on change(aka only called when it's needed) you should be keeping track of the state of the system and then only invoking the service when the conditions are right. This is your logic and it's your responsibility as the developer to know when it's needed. The system doesn't know when "it's needed".

edit flag offensive delete link more

Comments

@tfoote (you should be keeping track of the state of the system and then only invoking the service when the conditions are right. This is your logic and it's your responsibility as the developer to know when it's needed.) --> If you read my post carefully, you would know It is what I am trying to do, I just do not know how to do it. That is why and what I am asking here. I am not sure if the actions is the right design that I am looking for. I am still trying it out.

lin404 gravatar image lin404  ( 2020-01-26 18:00:50 -0500 )edit

You asked "What is the right way/design to do so?" and I've answered how to design the system to do what you've explained what you want to do. If you don't know how to implement that design that's a separate question that you should ask. And you will have to provide a much more thorough description of your system or much better would be to put together a simplified representative example of your situation which can then be more easily reasoned about. This sort of logic is more generic programming than ROS related so likely another forum is more appropriate. https://wiki.ros.org/Support

Actions are tangential to the problem you have described.

tfoote gravatar image tfoote  ( 2020-01-27 14:23:49 -0500 )edit

Thanks for the updated content.

A simple method to do this would be to record the last command sent and if the new command is different than the last command, then send the message.

tfoote gravatar image tfoote  ( 2020-01-27 20:35:26 -0500 )edit

Question Tools

2 followers

Stats

Asked: 2020-01-19 20:36:32 -0500

Seen: 532 times

Last updated: Jan 27 '20