$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 # -*- coding: utf-8 -*- 00019 """ 00020 This is an example showing how to publish command messages to the hand. 00021 """ 00022 00023 00024 import roslib; roslib.load_manifest('sr_hand') 00025 import rospy 00026 import time 00027 00028 from sr_robot_msgs.msg import joint, sendupdate, contrlr 00029 00030 def talker(): 00031 """ 00032 The Publisher publishes to the different topics on which the sr_subscriber subscribes. It sends commands to 00033 the hand. 00034 00035 Please set the message you want to test. 00036 """ 00037 test_what = "sendupdate" # choose sendupdate or contrlr 00038 00039 """ 00040 Test the sendupdate command 00041 """ 00042 if test_what == "sendupdate": 00043 pub1 = rospy.Publisher('srh/sendupdate', sendupdate) 00044 rospy.init_node('shadowhand_command_publisher_python') 00045 00046 new_target = 0 00047 00048 time.sleep(1) 00049 print "publishing" 00050 data_to_send = [ joint(joint_name="FFJ0", joint_target=new_target), 00051 joint(joint_name="FFJ3", joint_target=new_target) ] 00052 00053 pub1.publish(sendupdate(len(data_to_send), data_to_send)) 00054 00055 """ 00056 Tests the contrlr command 00057 """ 00058 if test_what == "contrlr": 00059 pub2 = rospy.Publisher('contrlr', contrlr) 00060 00061 data_to_send = ["p:0","i:0"] 00062 00063 pub2.publish( contrlr( contrlr_name="smart_motor_ff2" , 00064 list_of_parameters = data_to_send, 00065 length_of_list = len(data_to_send) ) ) 00066 00067 00068 00069 if __name__ == '__main__': 00070 try: 00071 talker() 00072 except rospy.ROSInterruptException: pass