How to call a service inside a python node?
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()