$search
00001 #!/usr/bin/env python 00002 # 00003 # Copyright 2011 Shadow Robot Company Ltd. 00004 # 00005 # This program is free software: you can redistribute it and/or modify it 00006 # under the terms of the GNU General Public License as published by the Free 00007 # Software Foundation, either version 2 of the License, or (at your option) 00008 # any later version. 00009 # 00010 # This program is distributed in the hope that it will be useful, but WITHOUT 00011 # ANY WARRANTY; without even the implied warranty of MERCHANTABILITY or 00012 # FITNESS FOR A PARTICULAR PURPOSE. See the GNU General Public License for 00013 # more details. 00014 # 00015 # You should have received a copy of the GNU General Public License along 00016 # with this program. If not, see <http://www.gnu.org/licenses/>. 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 # loop on the joints in the message 00038 for joint_data in data.joints_list: 00039 # if its the parent joint, read the target and send it to the child 00040 if joint_data.joint_name == parent_name: 00041 message.append(joint(joint_name=child_name, joint_target=joint_data.joint_target)) 00042 00043 # publish the message to the /srh/sendupdate topic. 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 # init the ros node 00053 rospy.init_node('joints_link_test', anonymous=True) 00054 00055 # init the subscriber: subscribe to the topic 00056 # /srh/shadowhand_data, using the callback function 00057 # callback() 00058 rospy.Subscriber("srh/shadowhand_data", joints_data, callback) 00059 00060 # subscribe until interrupted 00061 rospy.spin() 00062 00063 00064 if __name__ == '__main__': 00065 listener() 00066