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

Service server and client in python following tutorial does not work

asked 2019-04-29 10:41:20 -0500

kump gravatar image

updated 2019-04-30 01:00:50 -0500

I'm trying to make a service that I could call to change a pose of a robotic arm using MoveIt!. I follow this tutorial, but I get an error:

Traceback (most recent call last):
  File "/home/linux/catkin_ws/src/robotic_arm_algorithms/scripts/set_joint_states_client.py", line 24, in <module>
    set_joint_states(joint_states)
  File "/home/linux/catkin_ws/src/robotic_arm_algorithms/scripts/set_joint_states_client.py", line 17, in set_joint_states
    resp = set_joint_states(msg)
  File "/opt/ros/kinetic/lib/python2.7/dist-packages/rospy/impl/tcpros_service.py", line 435, in __call__
    return self.call(*args, **kwds)
  File "/opt/ros/kinetic/lib/python2.7/dist-packages/rospy/impl/tcpros_service.py", line 495, in call
    service_uri = self._get_service_uri(request)
  File "/opt/ros/kinetic/lib/python2.7/dist-packages/rospy/impl/tcpros_service.py", line 444, in _get_service_uri
    raise TypeError("request object is not a valid request message instance")
TypeError: request object is not a valid request message instance

This seems as a problem purely in the client code, so I show the client code and the service definition bellow. I have defined the servise as 4 float numbers each with a specific name. So when I pass the client four numbers (via terminal arguments), I expect to be able to simply assign those values to the service message as shown below. But something is not right. Can you point out the mistake for me?

srv/SetJointStates.srv:

std_msgs/Float32 forearm_0
std_msgs/Float32 forearm_1
std_msgs/Float32 arm_0
std_msgs/Float32 arm_1
---

script/set_joint_states_client.py:

#!/usr/bin/env python

import sys
import rospy
from robotic_arm_algorithms.srv import SetJointStates

def set_joint_states(joint_states):
    rospy.wait_for_service('set_joint_states')
    try:
        set_joint_states = rospy.ServiceProxy('set_joint_states', SetJointStates)
        msg = SetJointStates()
        msg.forearm_0 = joint_states[0]
        msg.forearm_1 = joint_states[1]
        msg.arm_0 = joint_states[2]
        msg.arm_1 = joint_states[3]

        resp = set_joint_states(msg)
    except rospy.ServiceException, e:
        print "Service call failed: %s"%e

if __name__ == "__main__":
    if len(sys.argv) == 5:
        joint_states = [float(sys.argv[1]), float(sys.argv[2]), float(sys.argv[3]), float(sys.argv[4])]
        set_joint_states(joint_states)
    else:
        print("not enaugh arguments. Four arguments required: forearm 0, forearm 1, arm 0, arm 1")
        sys.exit(1)

EDIT 1

When I put print (dir(SetJointStates)) into set_joint_states method of the client source code, following strings prints on terminal:

['__class__', '__delattr__', '__dict__', '__doc__', '__format__', '__getattribute__', '__hash__', '__init__', '__module__', '__new__', '__reduce__', '__reduce_ex__', '__repr__', '__setattr__', '__sizeof__', '__str__', '__subclasshook__', '__weakref__', '_md5sum', '_request_class', '_response_class', '_type']
edit retag flag offensive close merge delete

1 Answer

Sort by ยป oldest newest most voted
3

answered 2019-04-29 11:20:30 -0500

gvdhoorn gravatar image

updated 2019-04-30 02:46:09 -0500

[..]
from robotic_arm_algorithms.srv import SetJointStates

def set_joint_states(joint_states):
    rospy.wait_for_service('set_joint_states')
    try:
        set_joint_states = rospy.ServiceProxy('set_joint_states', SetJointStates)
        msg = SetJointStates()
        [..]

Can you point out the mistake for me?

Services have a Request and a Response type. SetJointStates is most likely a module containing both the Request and Response types, but isn't a service request or response itself (note how the tutorial you link to imports *, not AddTwoInts).

If you'd do a print (dir(SetJointStates)) we should be able to verify that.

In any case: you'll probably want to use the SetJointStatesRequest, or just use the ServiceProxy directly.

Another problem with the code is that you've named your ServiceProxy variable set_joint_states, while you already have a method called set_joint_states. That is not going to work.


Edit:

When I put print (dir(SetJointStates)) into set_joint_states method of the client source code, following strings prints on terminal:

['__class__', '__delattr__', '__dict__', '__doc__', '__format__', '__getattribute__', '__hash__', '__init__', '__module__', '__new__', '__reduce__', '__reduce_ex__', '__repr__', '__setattr__', '__sizeof__', '__str__', '__subclasshook__', '__weakref__', '_md5sum', '_request_class', '_response_class', '_type']

As you see, there is a _request_class and a _response_class field present.

That would seem to confirm what I wrote above (ie: SetJointStates is not a request or a response class itself, but the composite one encapsulating both.

As I wrote in my earlier answer, you'll want to use the SetJointStatesRequest class instead. Be sure to import that.


Edit 2: we should try to avoid duplicating these Q&As but I can't find one quickly, so here is an example of some code that will probably work:

[..]

from robotic_arm_algorithms.srv import *

def set_joint_states(joint_states):
    rospy.wait_for_service('set_joint_states')
    try:
        # bind our local service proxy
        svc_set_joint_states = rospy.ServiceProxy('set_joint_states', SetJointStates)

        # create the service request
        req = SetJointStatesRequest()

        # populate the fields of the request
        req.forearm_0 = joint_states[0]
        req.forearm_1 = joint_states[1]
        req.arm_0 = joint_states[2]
        req.arm_1 = joint_states[3]

        # invoke the service, passing it the request
        resp = scv_set_joint_states(req)

        # 'resp' is here of type 'SetJointStatesReponse'

        # perhaps do something with the response

    except rospy.ServiceException, e:
        print "Service call failed: %s"%e

[..]

Note that in addition to using the Request class, I've also renamed the service proxy variable to svc_set_joint_states to avoid shadowing your set_joint_states(..) method.

edit flag offensive delete link more

Comments

@gvdhoorn I added the output of print (dir(SetJointStates)) into the question. I don't know what is it telling me.

kump gravatar image kump  ( 2019-04-30 01:23:45 -0500 )edit

@gvdhoorn Could you level down your explanation? I don't understand what are you saying. What is SetJointStatesRequest? There is no mention about such class on the internet. What am I supposed to do with it?

kump gravatar image kump  ( 2019-04-30 02:00:11 -0500 )edit

What is SetJointStatesRequest? There is no mention about such class on the internet.

SetJointStates is the name of your service. You defined it yourself in srv/SetJointStates.srv.

See wiki/rospy/Overview/Services: Service definitions, request messages, and response messages for more info on how rospy generates the respective classes for your .srv.

gvdhoorn gravatar image gvdhoorn  ( 2019-04-30 02:06:16 -0500 )edit

Question Tools

1 follower

Stats

Asked: 2019-04-29 10:41:20 -0500

Seen: 1,408 times

Last updated: Apr 30 '19