00001
00002
00003
00004
00005
00006
00007
00008
00009
00010
00011
00012
00013
00014
00015
00016
00017
00018
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
00027 from sr_robot_msgs.msg import joint, sendupdate, contrlr
00028
00029 def talker():
00030 """
00031 The Publisher publishes to the different topics on which the sr_subscriber subscribes. It sends commands to
00032 the hand.
00033
00034 Please set the message you want to test.
00035 """
00036 test_what = "sendupdate"
00037
00038 """
00039 Test the sendupdate command
00040 """
00041 if test_what == "sendupdate":
00042 pub1 = rospy.Publisher('srh/sendupdate', sendupdate)
00043 rospy.init_node('shadowhand_command_publisher_python')
00044
00045 new_target = 0
00046
00047 data_to_send = [ joint(joint_name="FFJ0", joint_target=new_target),
00048 joint(joint_name="FFJ3", joint_target=new_target) ]
00049
00050 pub1.publish(sendupdate(len(data_to_send), data_to_send))
00051
00052 """
00053 Tests the contrlr command
00054 """
00055 if test_what == "contrlr":
00056 pub2 = rospy.Publisher('contrlr', contrlr)
00057
00058 data_to_send = ["p:0","i:0"]
00059
00060 pub2.publish( contrlr( contrlr_name="smart_motor_ff2" ,
00061 list_of_parameters = data_to_send,
00062 length_of_list = len(data_to_send) ) )
00063
00064
00065
00066 if __name__ == '__main__':
00067 try:
00068 talker()
00069 except rospy.ROSInterruptException: pass