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

How to call a service inside a python node?

asked 2020-01-20 09:17:32 -0500

ehsan_amp gravatar image

I want to subscribe a data in a python node and for different values of subscribed values, call a predefined service from another package and make it True or False. As it is explained for this question or in this link, I have tried call_service function but get this error.

[ERROR] [1579531979.101601]: bad callback: <function callback_receive at 0x7efd5a15dd70>
Traceback (most recent call last):
File "/opt/ros/kinetic/lib/python2.7/dist-packages/rospy/topics.py", line 750, in _invoke_callback
cb(msg)
File "/home/ehsan/catkin_ws/src/fsr_sensor/scripts/subscriber_node.py", line 16, in callback_receive
rosservice.call_service('/joint2_controller/torque_enable',False)
File "/opt/ros/kinetic/lib/python2.7/dist-packages/rosservice/__init__.py", line 411, in call_service
rospy.init_node('rosservice', anonymous=True)
File "/opt/ros/kinetic/lib/python2.7/dist-packages/rospy/client.py", line 274, in init_node
raise rospy.exceptions.ROSException("rospy.init_node() has already been called with different arguments: 
"+str(_init_node_args))
ROSException: rospy.init_node() has already been called with different arguments: ('subscriber_node', 
['/home/ehsan/catkin_ws/src/fsr_sensor/scripts/subscriber_node.py'], False, None, False, False)

I attached my python node below. Thanks in advance.

#!/usr/bin/env python

import rospy
import time
from std_msgs.msg import Bool
from std_msgs.msg import Int32
import rosservice

def callback_receive(msg):
   if msg.data == 1:
      rosservice.call_service('/joint2_controller/torque_enable',True)
      rosservice.call_service('/joint1_controller/torque_enable',True)
   else:
      rosservice.call_service('/joint2_controller/torque_enable',False)
      rosservice.call_service('/joint1_controller/torque_enable',False)

if __name__ == '__main__':
    rospy.init_node('subscriber_node')
    rospy.Subscriber("/X",Int32,callback_receive)

 rospy.spin()
edit retag flag offensive close merge delete

2 Answers

Sort by ยป oldest newest most voted
1

answered 2020-01-21 08:08:29 -0500

ehsan_amp gravatar image

updated 2020-01-21 08:18:13 -0500

As far as I know rosservice.call_service doesn't work for this usage. I attached the code that I used.

#!/usr/bin/env python

import rospy
import time
from std_msgs.msg import Bool
from std_msgs.msg import Int32
from dynamixel_controllers.srv import TorqueEnable
import sys

def callback_receive(msg):
     rospy.wait_for_service('joint2_controller/torque_enable')
     rospy.wait_for_service('joint1_controller/torque_enable')
if msg.data == 1:
    joint2 = rospy.ServiceProxy('joint2_controller/torque_enable', TorqueEnable)
    joint1 = rospy.ServiceProxy('joint1_controller/torque_enable', TorqueEnable)
    joint_2=joint2(True)
    joint_1=joint1(True)

elif msg.data == 0:
    joint2 = rospy.ServiceProxy('joint2_controller/torque_enable', TorqueEnable)
    joint1 = rospy.ServiceProxy('joint1_controller/torque_enable', TorqueEnable)
    joint_2=joint2(False)
    joint_1=joint1(False)


if __name__ == '__main__':
    rospy.init_node('subscriber_node')
    rospy.Subscriber("/X",Int32,callback_receive)



rospy.spin()
edit flag offensive delete link more
4

answered 2020-01-21 05:23:54 -0500

marguedas gravatar image

You can look at this tutorial to see how to create a client to call a given service. More details are available in the rospy service documentation

To call a service you need to create a service proxy. Each time you invoke that service proxy, it will send a request to the server and block until it gets a response. In your case you'll need two different service proxies, one for joint1_controller/torque_enable and one for joint2_controller/torque_enable.


rosservice is a utility to interact with services from the command line e.g.:

rosservice call [...]

This should not be used inside scripts that already have ros running.

edit flag offensive delete link more

Comments

Thanks for your answer. I tried that and it worked! I will write it down as an answer.

ehsan_amp gravatar image ehsan_amp  ( 2020-01-21 08:05:39 -0500 )edit

Question Tools

1 follower

Stats

Asked: 2020-01-20 09:17:32 -0500

Seen: 4,596 times

Last updated: Jan 21 '20