$search
00001 #!/usr/bin/env python 00002 import roslib; roslib.load_manifest('sr_utilities') 00003 import rospy 00004 from sensor_msgs.msg import JointState 00005 from sr_utilities.srv import getJointState 00006 import thread 00007 00008 RATE=100 00009 00010 class GetJointState: 00011 def __init__(self): 00012 rospy.init_node('get_joint_state_service', anonymous=True) 00013 00014 self.subs_1 = rospy.Subscriber("/joint_states", JointState, self.callback1) 00015 self.serv = rospy.Service('/getJointState', getJointState, self.getJointStateCB) 00016 00017 # self.pub = rospy.Publisher("/joint_states", JointState) 00018 00019 self.joint_state_msg = JointState() 00020 00021 self.mutex = thread.allocate_lock() 00022 00023 r = rospy.Rate( RATE ) 00024 while not rospy.is_shutdown(): 00025 #self.publish() 00026 r.sleep() 00027 00028 def callback1(self, data): 00029 self.joint_state_msg = data 00030 00031 def getJointStateCB(self,req): 00032 res=self.joint_state_msg 00033 return res 00034 00035 if __name__ == '__main__': 00036 service = GetJointState()