00001
00002
00003
00004 import roslib
00005 roslib.load_manifest('pr2_simple_interface')
00006 from pr2_simple_interface import *
00007 start()
00008
00009
00010 gripper = Gripper()
00011 arm = RobotArm()
00012 head = Head()
00013 torso = Torso()
00014 sound = Sound()
00015
00016
00017 sound.say("I'm Kiko.")
00018
00019
00020 for i in range(2):
00021 head.look_at(1.0, 0.0, 0.5)
00022 head.wait_for()
00023 head.look_at(1.0, 0.0, 1.5)
00024 head.wait_for()
00025
00026
00027 head.look_at(1.0, 0.0, 1.0)
00028 head.wait_for()
00029
00030
00031 arm.move_to([-80, 40, 30, -110, 0, 0, -5], RIGHT)
00032 arm.mirror(RIGHT)
00033 arm.wait_for(BOTH)
00034
00035
00036 gripper.release(BOTH)
00037 gripper.wait_for(BOTH)
00038
00039
00040 arm.move_to([-20, -15, -20, -50, 30, -30, -180], RIGHT)
00041 arm.move_to([20, -15, 20, -50, -30, -30, 180], LEFT)
00042
00043
00044 sound.say("Double high fives.")
00045
00046
00047 arm.wait_for(BOTH)
00048
00049
00050 gripper.wait_for_slap(BOTH)
00051
00052
00053 head.look_at(1.0, 0.0, 1.5)
00054 head.wait_for()
00055 head.look_at(1.0, 0.0, 1.0)
00056 head.wait_for()
00057
00058 sound.say("Slap one hand.")
00059
00060 if (gripper.determine_slap() == LEFT):
00061 head.look_at(1.0, 1.0, 0.5)
00062 head.wait_for()
00063 else:
00064 head.look_at(1.0, -1.0, 0.0)
00065 head.wait_for()
00066
00067
00068 arm.move_to([70, 50, 40, -120, 100, -20, 20], LEFT)
00069 arm.move_to([-70, 50, -40, -120, -100, -20, -20], RIGHT)
00070 arm.wait_for(BOTH)
00071
00072 gripper.close(BOTH)
00073 gripper.wait_for(BOTH)
00074
00075 head.look_at(1.0, 0.0, 1.0)
00076 head.wait_for()
00077
00078 sound.say("Goodbye.")