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
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_example')
00025 import rospy
00026 import time
00027 import math
00028
00029 from std_msgs.msg import Float64
00030
00031
00032
00033 controller_type = "_mixed_position_velocity_controller"
00034
00035
00036
00037 def talker():
00038 """
00039 The Publisher publishes two commands to move joint FFJ0 and RFJ0
00040
00041 """
00042 joint1 = 'ffj0'
00043 joint2 = 'rfj0'
00044
00045
00046 rospy.init_node('shadowhand_command_publisher_python')
00047
00048 pub1 = rospy.Publisher('sh_'+ joint1 + controller_type + '/command', Float64, latch=True)
00049 pub2 = rospy.Publisher('sh_'+ joint2 + controller_type + '/command', Float64, latch=True)
00050
00051
00052
00053
00054 new_target_1 = math.radians(0.0)
00055 new_target_2 = math.radians(0.0)
00056
00057 time.sleep(1)
00058 print "publishing"
00059
00060
00061 pub1.publish(new_target_1)
00062
00063
00064 pub2.publish(new_target_2)
00065
00066
00067 if __name__ == '__main__':
00068 try:
00069 talker()
00070 except rospy.ROSInterruptException: pass