Go to the documentation of this file.00001
00002
00003
00004
00005
00006
00007
00008
00009
00010
00011
00012
00013
00014
00015
00016
00017
00018 import roslib; roslib.load_manifest('sr_hand')
00019 import rospy
00020 from sr_robot_msgs.msg import sendupdate, joint, joints_data
00021 from sensor_msgs.msg import *
00022
00023 parent_name = "FFJ3"
00024 child_name = "MFJ3"
00025
00026
00027 def callback(data):
00028 """
00029 The callback function: called each time a message is received on the
00030 topic /srh/shadowhand_data
00031
00032 @param data: the message
00033 """
00034 message=[]
00035 if data.joints_list_length == 0:
00036 return
00037
00038 for joint_data in data.joints_list:
00039
00040 if joint_data.joint_name == parent_name:
00041 message.append(joint(joint_name=child_name, joint_target=joint_data.joint_target))
00042
00043
00044 pub = rospy.Publisher('srh/sendupdate', sendupdate)
00045 pub.publish(sendupdate(len(message), message))
00046
00047
00048 def listener():
00049 """
00050 The main function
00051 """
00052
00053 rospy.init_node('joints_link_test', anonymous=True)
00054
00055
00056
00057
00058 rospy.Subscriber("srh/shadowhand_data", joints_data, callback)
00059
00060
00061 rospy.spin()
00062
00063
00064 if __name__ == '__main__':
00065 listener()
00066