diff --git a/talos_bringup/config/joy_teleop.yaml b/talos_bringup/config/joy_teleop.yaml
index 25e2e6bec15a98c4d327be6fca19a4b5c8fe3fac..0a61c936a8118bbfdc8e15407ec81acf5dd3c5c4 100644
--- a/talos_bringup/config/joy_teleop.yaml
+++ b/talos_bringup/config/joy_teleop.yaml
@@ -35,7 +35,7 @@ teleop:
     type: action
     action_name: play_motion
     action_goal:
-      motion_name: hands_walk
+      motion_name: walk_pose
     buttons: [8, 2]
 
   # documented motions, with right upper button and right trigger
@@ -58,19 +58,13 @@ teleop:
     type: action
     action_name: play_motion
     action_goal:
-      motion_name: open_arms
+      motion_name: wave_both_arms
     buttons: [5, 3]
 
   shake_hand:
     type: action
     action_name: play_motion
     action_goal:
-      motion_name: shake_right
+      motion_name: lift_weights
     buttons: [5, 2]
 
-  point_front_left:
-    type: action
-    action_name: play_motion
-    action_goal:
-      motion_name: point_front_left
-    buttons: [7, 0]
diff --git a/talos_bringup/config/talos_motions.yaml b/talos_bringup/config/talos_motions.yaml
index 23ffc7e2ca2287adf276ee135a3c5f3f4dfabe05..f3fcd88862093aefe5fe4658abaec5dd8102989a 100644
--- a/talos_bringup/config/talos_motions.yaml
+++ b/talos_bringup/config/talos_motions.yaml
@@ -24,9 +24,9 @@ play_motion:
         arm_right_4_joint, arm_right_5_joint, arm_right_6_joint, arm_right_7_joint,
         gripper_left_joint, gripper_right_joint]
       points:
-      - positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.15, 0.0, 0.0, 0.0, 0.0, 0.0, 
-                                        0.0, -0.15, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0]
-        time_from_start: 4.0
+      - positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.25, 0.0, 0.0, 0.0, 0.0, 0.0, 
+                                        0.0, -0.25, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0]
+        time_from_start: 0.0
       meta:
         name: Home
         usage: posture
@@ -39,6 +39,20 @@ play_motion:
       points:
       - positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0]
         time_from_start: 0.0
+    walk_pose: 
+      joints: [torso_1_joint, torso_2_joint, head_1_joint, head_2_joint, arm_left_1_joint,
+        arm_left_2_joint, arm_left_3_joint, arm_left_4_joint, arm_left_5_joint, arm_left_6_joint,
+        arm_left_7_joint, arm_right_1_joint, arm_right_2_joint, arm_right_3_joint,
+        arm_right_4_joint, arm_right_5_joint, arm_right_6_joint, arm_right_7_joint,
+        gripper_left_joint, gripper_right_joint]
+      points:
+      - positions: [0.0, 0.0, 0.0, 0.0, 0.31, 0.32, -0.3, -0.80, 0.0, 0.0, 0.0, 
+                                        -0.31, -0.32, 0.3, -0.80, 0.0, 0.0, 0.0, 0.0, 0.0]
+        time_from_start: 0.0
+      meta:
+        name: Home
+        usage: posture
+        description: Both arms down and completely stretched.
     interact:
       joints: [torso_1_joint, torso_2_joint, head_1_joint, head_2_joint, arm_left_1_joint,
         arm_left_2_joint, arm_left_3_joint, arm_left_4_joint, arm_left_5_joint, arm_left_6_joint,
@@ -79,7 +93,7 @@ play_motion:
     wave:
       joints: [torso_1_joint, torso_2_joint, arm_right_1_joint, arm_right_2_joint, arm_right_3_joint, arm_right_4_joint, arm_right_5_joint, arm_right_6_joint, arm_right_7_joint, arm_left_1_joint, arm_left_2_joint, arm_left_3_joint, arm_left_4_joint, arm_left_5_joint, arm_left_6_joint, arm_left_7_joint, gripper_right_joint, gripper_left_joint]
       points:
-      - positions: [-0.0, -0.001, 0.0, -0.148, -0.0, 0.0, 0.0, 0.001, -0.0, -0.0, 0.15, 0.0, 0.0, -0.0, -0.0, -0.0, 0.0, 0.0]
+      - positions: [0.0, 0.0, 0.0, -0.25, -0.0, 0.0, 0.0, 0.00, -0.0, -0.0, 0.25, 0.0, 0.0, -0.0, -0.0, -0.0, 0.0, 0.0]
         time_from_start: 0.0
       - positions: [0.0, -0.001, -0.314, -1.175, -0.927, -2.214, -0.0, 0.002, -0.001, -0.0, 0.15, 0.0, 0.0, -0.0, -0.0, -0.0, 0.0, 0.0]
         time_from_start: 3.0
@@ -87,7 +101,7 @@ play_motion:
         time_from_start: 4.0
       - positions: [0.0, -0.001, -0.314, -1.175, -0.927, -2.214, -0.0, 0.002, -0.001, -0.0, 0.15, 0.0, 0.0, -0.0, -0.0, -0.0, 0.0, 0.0]
         time_from_start: 5.0
-      - positions: [-0.0, -0.001, 0.0, -0.148, -0.0, 0.0, 0.0, 0.001, -0.0, -0.0, 0.15, 0.0, 0.0, -0.0, -0.0, -0.0, 0.0, 0.0]
+      - positions: [0.0, 0.0, 0.0, -0.25, -0.0, 0.0, 0.0, 0.0, -0.0, -0.0, 0.25, 0.0, 0.0, -0.0, -0.0, -0.0, 0.0, 0.0]
         time_from_start: 8.0
     lift_weights:
       joints: [head_1_joint, head_2_joint, torso_1_joint, torso_2_joint, arm_right_1_joint, arm_right_2_joint, arm_right_3_joint, arm_right_4_joint, arm_right_5_joint, arm_right_6_joint, arm_right_7_joint, arm_left_1_joint, arm_left_2_joint, arm_left_3_joint, arm_left_4_joint, arm_left_5_joint, arm_left_6_joint, arm_left_7_joint, gripper_right_joint, gripper_left_joint]
@@ -102,6 +116,8 @@ play_motion:
         time_from_start: 6.0
       - positions: [-0.0, -0.0, 0.0, 0.002, -0.0, -0.252, 0.286, -1.588, -1.57, -0.003, 0.001, -0.0, 0.252, -0.286, -1.588, 1.57, 0.003, 0.001, -0.7, -0.7]
         time_from_start: 8.0
+      - positions: [0.0, 0.0, 0.0, -0.25, -0.0, 0.0, 0.0, 0.0, -0.0, -0.0, 0.25, 0.0, 0.0, -0.0, -0.0, -0.0, 0.0, 0.0]
+        time_from_start: 10.0
     close_right_gripper:
       joints: [gripper_right_joint]
       points: