00001
00002
00003
00004
00005
00006
00007
00008
00009
00010
00011
00012
00013
00014
00015
00016
00017
00018
00019
00020
00021
00022
00023
00024
00025
00026 import rospy
00027
00028 import time
00029 import math
00030 from std_msgs.msg import Float64
00031
00032
00033 class SexyExampleLatching(object):
00034
00035
00036 controller_type = "_position_controller"
00037
00038 def __init__(self):
00039
00040 self.hand_publishers = self.create_hand_publishers()
00041
00042 self.sleep_time = 3.0
00043
00044 def run(self):
00045 """
00046 Runs the hand through different predefined position in a given order.
00047 """
00048 start = {"FFJ0":0, "FFJ3":0, "FFJ4":0,
00049 "MFJ0":0, "MFJ3":0, "MFJ4":0,
00050 "RFJ0":0, "RFJ3":0, "RFJ4":0,
00051 "LFJ0":0, "LFJ3":0, "LFJ4":0, "LFJ5":0,
00052 "THJ1":0, "THJ2":0, "THJ3":0, "THJ4":0, "THJ5":0,
00053 "WRJ1":0, "WRJ2":0 }
00054
00055 fist = {"FFJ0":180, "FFJ3":90, "FFJ4":0,
00056 "MFJ0":180, "MFJ3":90, "MFJ4":0,
00057 "RFJ0":180, "RFJ3":90, "RFJ4":0,
00058 "LFJ0":180, "LFJ3":90, "LFJ4":0, "LFJ5":0,
00059 "THJ1":0, "THJ2":0, "THJ3":0, "THJ4":50, "THJ5":-50,
00060 "WRJ1":0, "WRJ2":0 }
00061
00062 victory = {"FFJ0":0, "FFJ3":0, "FFJ4":-20,
00063 "MFJ0":0, "MFJ3":0, "MFJ4":20,
00064 "RFJ0":180, "RFJ3":90, "RFJ4":-10,
00065 "LFJ0":180, "LFJ3":90, "LFJ4":-10, "LFJ5":0,
00066 "THJ1":40, "THJ2":20, "THJ3":0, "THJ4":50, "THJ5":35,
00067 "WRJ1":0, "WRJ2":0 }
00068
00069 wave_1 = {"WRJ2":-20}
00070 wave_2 = {"WRJ2":5}
00071
00072 self.publish_pose(start)
00073 time.sleep(self.sleep_time)
00074
00075 self.publish_pose(fist)
00076 time.sleep(self.sleep_time)
00077
00078 self.publish_pose(start)
00079 time.sleep(self.sleep_time)
00080
00081 self.publish_pose(victory)
00082 time.sleep(self.sleep_time)
00083
00084 self.publish_pose(start)
00085 time.sleep(self.sleep_time)
00086
00087 for _ in range(4):
00088 self.publish_pose(wave_1)
00089 time.sleep(self.sleep_time)
00090 self.publish_pose(wave_2)
00091 time.sleep(self.sleep_time)
00092
00093 def publish_pose(self, pose):
00094 """
00095 Publish a given pose.
00096 """
00097 for joint, pos in pose.iteritems():
00098 self.hand_publishers[joint].publish(math.radians(pos))
00099
00100 def create_hand_publishers(self):
00101 """
00102 Creates a dictionary of publishers to send the targets to the controllers
00103 on /sh_??j?_mixed_position_velocity_controller/command
00104 or /sh_??j?_position_controller/command
00105 """
00106 hand_pub = {}
00107
00108 for joint in ["FFJ0", "FFJ3", "FFJ4",
00109 "MFJ0", "MFJ3", "MFJ4",
00110 "RFJ0", "RFJ3", "RFJ4",
00111 "LFJ0", "LFJ3", "LFJ4", "LFJ5",
00112 "THJ1", "THJ2", "THJ3", "THJ4", "THJ5",
00113 "WRJ1", "WRJ2" ]:
00114
00115
00116
00117
00118 hand_pub[joint] = rospy.Publisher('sh_'+joint.lower() + self.controller_type + '/command', Float64, latch=True)
00119
00120 return hand_pub
00121
00122 def main():
00123 rospy.init_node('sexy_example_latching', anonymous = True)
00124 sexy_example = SexyExampleLatching()
00125 sexy_example.run()
00126
00127 if __name__ == '__main__':
00128 main()