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 00019 # This example can be tested with the simulated hand (or simulated hand and arm) 00020 # by using the following command in a separate terminal 00021 # roslaunch sr_hand gazebo_arm_and_hand.launch 00022 # or 00023 # roslaunch sr_hand gazebo_hand.launch 00024 # and then 00025 # rosrun sr_example link_joints.py 00026 # rosrun rqt_gui rqt_gui 00027 00028 # in the rqt_gui go to plugins->ShadowRobot->joint slider and select EtherCAT hand 00029 # If you move the joint slider for FFJ3, then MFJ3 will move as well. 00030 00031 import roslib; roslib.load_manifest('sr_example') 00032 import rospy 00033 from std_msgs.msg import Float64 00034 from control_msgs.msg import JointControllerState 00035 00036 parent_name = "ffj3" 00037 child_name = "mfj3" 00038 00039 # type of controller that is running 00040 controller_type = "_position_controller" 00041 00042 pub = rospy.Publisher('sh_' + child_name + controller_type + '/command', Float64) 00043 00044 def callback(data): 00045 """ 00046 The callback function: called each time a message is received on the 00047 topic parent joint controller state topic 00048 00049 @param data: the message 00050 """ 00051 # publish the message to the child joint controller command topic. 00052 # here we insert the joint name into the topic name 00053 pub.publish(data.set_point) 00054 00055 00056 def listener(): 00057 """ 00058 The main function 00059 """ 00060 # init the ros node 00061 rospy.init_node('joints_link_test', anonymous=True) 00062 00063 # init the subscriber: subscribe to the 00064 # parent joint controller topic, using the callback function 00065 # callback() 00066 rospy.Subscriber('sh_'+parent_name + controller_type + '/state', JointControllerState, callback) 00067 # subscribe until interrupted 00068 rospy.spin() 00069 00070 00071 if __name__ == '__main__': 00072 listener()