ROS node as a service and publisher at the same time

asked 2017-05-09 00:22:21 -0500

msz1621 gravatar image

updated 2017-05-09 00:35:36 -0500

Hi,

I would like to implement a node which receives an input, do some processing, and finally publish the result in a topic. The response from the client of the service is not very important to me. So far, I have the following code of the node:

#!/usr/bin/env python
import rospy
from std_msgs.msg import String
from navigation.srv import *

pub = rospy.Publisher('motion_planning', String, queue_size=10)

def motion_planning_publisher():
    rate = rospy.Rate(10)
    while not rospy.is_shutdown():
        hello_str = "hello world %s" % rospy.get_time()
        rospy.loginfo(hello_str)
        pub.publish(hello_str)
        rate.sleep()

def handle_request(req):
    print "Processing a request..."
    motion_planning_publisher()
    return "It is working"

def server():
    s = rospy.Service('get_motion', GetMotion, handle_request)
    print "Ready..."
    rospy.spin()

if __name__ == '__main__':
    try:
        rospy.init_node('motion_planner', anonymous=True)
        server()
    except rospy.ROSInterruptException:
        pass

As you can notice, once a request is received, the handle_request function will start publishing some data. However, the client in this case will hang waiting for a response. My target is to have the client do the request (maybe receive an acknowledgment) and then proceed with other things. So, I am wondering if this is a good way to do it. Another thought is to use Actionlib where the server will publish data to a topic. I appreciate your input.

edit retag flag offensive close merge delete