{ "cells": [ { "cell_type": "code", "execution_count": 4, "metadata": { "collapsed": false }, "outputs": [ { "name": "stderr", "output_type": "stream", "text": [ "WARNING:pypot.robot.config:Limits of 'head_z' changed from (-150.0, 0.15) to [-180, 0]\n", "WARNING:pypot.robot.config:Limits of 'l_wrist_x' changed from (-150.0, 150.0) to [-180, 180]\n", "WARNING:pypot.robot.config:Limits of 'r_wrist_x' changed from (-150.0, 150.0) to [-180, 180]\n" ] } ], "source": [ "import time \n", "from pypot.robot import from_json\n", "poppy = from_json(\"/home/poppy/poppy_torso2.json\")" ] }, { "cell_type": "code", "execution_count": 5, "metadata": { "collapsed": true }, "outputs": [], "source": [ "# Pour bloquer Poppy\n", "for m in poppy.motors:\n", " m.compliant=False" ] }, { "cell_type": "code", "execution_count": null, "metadata": { "collapsed": false }, "outputs": [], "source": [ "# Pour libérer Poppy\n", "# /!\\ il faut tenir Poppy pour éviter que ses bras tombent et se congnent contre la table\n", "for m in poppy.motors : \n", " m.compliant=True" ] }, { "cell_type": "code", "execution_count": 6, "metadata": { "collapsed": false }, "outputs": [], "source": [ "#position de base\n", "poppy.r_arm_z.goto_position(-30,1)\n", "poppy.l_arm_z.goto_position(7,1,wait=True)\n", "poppy.l_elbow_y.goto_position(45,1,wait=True)\n", "poppy.r_elbow_y.goto_position(45,1)\n", "poppy.l_shoulder_y.goto_position(22,1)\n", "poppy.l_shoulder_x.goto_position(-2,1)\n", "poppy.l_wrist_x.goto_position(0,1)\n", "poppy.l_hand_z.goto_position(65,1)\n", "poppy.r_shoulder_y.goto_position(22,1)\n", "poppy.r_shoulder_x.goto_position(0,1)\n", "poppy.r_wrist_x.goto_position(0,1)\n", "poppy.r_hand_z.goto_position(0,1)\n", "poppy.abs_z.goto_position(0,1)\n", "poppy.bust_x.goto_position(0,1)\n", "poppy.bust_y.goto_position(0,1)\n", "poppy.head_y.goto_position(20,1)\n", "poppy.head_z.goto_position(0,1)\n", "poppy.r_arm_z.goto_position(0,1)" ] }, { "cell_type": "code", "execution_count": null, "metadata": { "collapsed": false }, "outputs": [], "source": [ "poppy.l_arm_z.goto_position(20,1)" ] }, { "cell_type": "code", "execution_count": null, "metadata": { "collapsed": false }, "outputs": [], "source": [ "#position de base\n", "poppy.r_arm_z.goto_position(0,1)\n", "poppy.l_arm_z.goto_position(7,1,wait=True)\n", "poppy.l_elbow_y.goto_position(45,1,wait=True)\n", "poppy.r_elbow_y.goto_position(45,1)\n", "poppy.l_shoulder_y.goto_position(22,1)\n", "poppy.l_shoulder_x.goto_position(-2,1)\n", "poppy.l_wrist_x.goto_position(0,1)\n", "poppy.l_hand_z.goto_position(65,1)\n", "poppy.r_shoulder_y.goto_position(22,1)\n", "poppy.r_shoulder_x.goto_position(0,1)\n", "poppy.r_wrist_x.goto_position(0,1)\n", "poppy.r_hand_z.goto_position(0,1)\n", "poppy.abs_z.goto_position(0,1)\n", "poppy.bust_x.goto_position(0,1)\n", "poppy.bust_y.goto_position(0,1)\n", "poppy.head_y.goto_position(20,1)\n", "poppy.head_z.goto_position(0,1)" ] }, { "cell_type": "code", "execution_count": null, "metadata": { "collapsed": false }, "outputs": [], "source": [ "#Position du cylindre\n", "poppy.r_wrist_x.goto_position(150,0.5,wait=True)\n", "poppy.abs_z.goto_position(-20,0.5)\n", "poppy.r_arm_z.goto_position(-2,0.5)\n", "poppy.r_shoulder_x.goto_position(-35,0.5,wait=True)\n", "poppy.abs_z.goto_position(6,1)\n", "poppy.r_shoulder_y.goto_position(-3,1)\n", "poppy.head_y.goto_position(20,1)\n", "poppy.head_z.goto_position(-45,1)\n", "poppy.r_elbow_y.goto_position(-17,1,wait=True)\n", "poppy.r_hand_z.goto_position(65.3,1,wait=True)\n", "\n", "#dépose cylindre\n", "\n", "poppy.r_shoulder_y.goto_position(-2.68,1)\n", "poppy.r_shoulder_x.goto_position(-83,1)\n", "poppy.r_arm_z.goto_position(-2,1)\n", "poppy.r_elbow_y.goto_position(8,1)\n", "poppy.r_wrist_x.goto_position(101,1,wait=True)\n", "poppy.abs_z.goto_position(34,1,wait=True)\n", "poppy.r_hand_z.goto_position(0,1)" ] }, { "cell_type": "code", "execution_count": null, "metadata": { "collapsed": true }, "outputs": [], "source": [ "# dépose triangle\n", "poppy.l_wrist_x.goto_position(150,0.5)\n", "poppy.l_arm_z.goto_position(10,0.5)\n", "poppy.l_shoulder_x.goto_position(25,0.5)\n", "poppy.l_shoulder_y.goto_position(0,1)\n", "poppy.abs_z.goto_position(20,0.5,wait=True)\n", "poppy.abs_z.goto_position(-2.5,0.5)\n", "poppy.head_y.goto_position(20,1)\n", "poppy.l_elbow_y.goto_position(-10,1,wait=True)\n", "poppy.l_hand_z.goto_position(65,1,wait=True)\n", "poppy.l_hand_z.goto_position(0,1,wait=True)\n", "poppy.head_z.goto_position(35,1)\n", "\n", "poppy.l_shoulder_y.goto_position(-78,2,wait=True)\n", "poppy.l_shoulder_x.goto_position(50,2)\n", "poppy.l_arm_z.goto_position(-69,1)\n", "poppy.l_elbow_y.goto_position(-4,1)\n", "poppy.l_wrist_x.goto_position(101,1,wait=True)\n", "poppy.head_z.goto_position(0,1)\n", "poppy.abs_z.goto_position(-7,1,wait=True)\n", "poppy.l_hand_z.goto_position(65,1,wait=True)\n" ] }, { "cell_type": "code", "execution_count": null, "metadata": { "collapsed": true }, "outputs": [], "source": [ "#dépose croix\n", "poppy.r_hand_z.goto_position(0,1,wait=True)\n", "poppy.r_wrist_x.goto_position(150,0.5,wait=True)\n", "poppy.r_arm_z.goto_position(-0.66,0.5)\n", "poppy.r_shoulder_x.goto_position(-48.65,0.5,wait=True)\n", "poppy.abs_z.goto_position(18,1)\n", "poppy.r_shoulder_y.goto_position(-22,1)\n", "poppy.r_elbow_y.goto_position(-17,1,wait=True)\n", "poppy.r_arm_z.goto_position(10,0.5)\n", "poppy.r_elbow_y.goto_position(-22.9,1)\n", "poppy.bust_x.goto_position(12,1,wait=True)\n", "poppy.r_hand_z.goto_position(65,1,wait=True)\n", "\n", "poppy.r_arm_z.goto_position(-5,0.5,wait=True)\n", "poppy.bust_y.goto_position(0.5,1)\n", "poppy.r_shoulder_y.goto_position(-8,0.5)\n", "poppy.r_shoulder_x.goto_position(-80,0.5)\n", "poppy.r_elbow_y.goto_position(-5,0.5)\n", "poppy.r_wrist_x.goto_position(101,1,wait=True)\n", "poppy.r_shoulder_x.goto_position(-102,0.5)\n", "poppy.abs_z.goto_position(43,1,wait=True)\n", "poppy.r_arm_z.goto_position(1,1,wait=True)\n", "#poppy.r_hand_z.goto_position(0,1)" ] }, { "cell_type": "code", "execution_count": null, "metadata": { "collapsed": true }, "outputs": [], "source": [ "poppy.r_hand_z.goto_position(0,1)" ] }, { "cell_type": "code", "execution_count": null, "metadata": { "collapsed": true }, "outputs": [], "source": [ "# dépose carré\n", "poppy.l_wrist_x.goto_position(150,0.5)\n", "\n", "poppy.l_arm_z.goto_position(50,0.5)\n", "poppy.head_y.goto_position(20,1)\n", "poppy.head_z.goto_position(45,1)\n", "poppy.l_shoulder_x.goto_position(41,0.5)\n", "poppy.l_shoulder_y.goto_position(-3,0.5)\n", "poppy.l_arm_z.goto_position(15,0.5)\n", "poppy.l_elbow_y.goto_position(-8,0.5,wait=True)\n", "poppy.bust_x.goto_position(-7,1,wait=True)\n", "poppy.abs_z.goto_position(-25,0.5,wait=True)\n", "poppy.l_elbow_y.goto_position(-15,0.5,wait=True)\n", "poppy.l_hand_z.goto_position(0,1,wait=True)\n", "\n", "poppy.l_shoulder_x.goto_position(90,1)\n", "poppy.bust_x.goto_position(0,1)\n", "poppy.l_wrist_x.goto_position(100,1,wait=True)\n", "poppy.abs_z.goto_position(-44,1)\n", "poppy.l_elbow_y.goto_position(-5,1,wait=True)\n", "poppy.l_arm_z.goto_position(4,1,wait=True)\n", "poppy.l_hand_z.goto_position(65,1)\n" ] }, { "cell_type": "code", "execution_count": null, "metadata": { "collapsed": true }, "outputs": [], "source": [ "\n", "poppy.abs_z.goto_position(-44,1)" ] }, { "cell_type": "code", "execution_count": null, "metadata": { "collapsed": true }, "outputs": [], "source": [ "#dépose étoile\n", "poppy.l_wrist_x.goto_position(150,1)\n", "poppy.l_shoulder_y.goto_position(-14,1)\n", "poppy.l_shoulder_x.goto_position(30,1)\n", "poppy.l_arm_z.goto_position(-20,1,wait=True)\n", "poppy.l_arm_z.goto_position(-50,1)\n", "poppy.l_elbow_y.goto_position(2,1,wait=True)\n", "poppy.l_hand_z.goto_position(0,1,wait=True)\n", "poppy.l_elbow_y.goto_position(20,1,wait=True)\n", "poppy.l_shoulder_y.goto_position(-60,1)\n", "poppy.l_elbow_y.goto_position(10,1)\n", "poppy.l_wrist_x.goto_position(117,1,wait=True)\n", "poppy.l_elbow_y.goto_position(-37,1)\n", "poppy.l_shoulder_y.goto_position(-87.5,1)\n", "poppy.l_shoulder_x.goto_position(13,1)\n", "poppy.abs_z.goto_position(2,1)\n", "poppy.l_arm_z.goto_position(-64,1,wait=True)\n", "poppy.l_arm_z.goto_position(-76,1,wait=True)\n", "poppy.l_hand_z.goto_position(65,1)" ] }, { "cell_type": "code", "execution_count": null, "metadata": { "collapsed": false }, "outputs": [], "source": [ "#position de base\n", "poppy.r_arm_z.goto_position(0,1)\n", "poppy.l_arm_z.goto_position(7,1,wait=True)\n", "poppy.l_elbow_y.goto_position(45,1,wait=True)\n", "poppy.r_elbow_y.goto_position(45,1)\n", "poppy.l_shoulder_y.goto_position(22,1)\n", "poppy.l_shoulder_x.goto_position(-2,1)\n", "poppy.l_wrist_x.goto_position(0,1)\n", "poppy.l_hand_z.goto_position(65,1)\n", "poppy.r_shoulder_y.goto_position(22,1)\n", "poppy.r_shoulder_x.goto_position(0,1)\n", "poppy.r_wrist_x.goto_position(0,1)\n", "poppy.r_hand_z.goto_position(0,1)\n", "poppy.abs_z.goto_position(0,1)\n", "poppy.bust_x.goto_position(0,1)\n", "poppy.bust_y.goto_position(0,1)\n", "poppy.head_y.goto_position(20,1)\n", "poppy.head_z.goto_position(0,1)\n", "\n", "#Position du cylindre\n", "poppy.r_wrist_x.goto_position(150,0.5,wait=True)\n", "poppy.abs_z.goto_position(-20,0.5)\n", "poppy.r_arm_z.goto_position(-2,0.5)\n", "poppy.r_shoulder_x.goto_position(-35,0.5,wait=True)\n", "poppy.abs_z.goto_position(6,1)\n", "poppy.r_shoulder_y.goto_position(-3,1)\n", "poppy.head_y.goto_position(20,1)\n", "poppy.head_z.goto_position(-45,1)\n", "poppy.r_elbow_y.goto_position(-17,1,wait=True)\n", "poppy.r_hand_z.goto_position(65.3,1,wait=True)\n", "\n", "poppy.r_shoulder_y.goto_position(-2.68,1)\n", "poppy.r_shoulder_x.goto_position(-83,1)\n", "poppy.r_arm_z.goto_position(-2,1)\n", "poppy.r_elbow_y.goto_position(8,1)\n", "poppy.r_wrist_x.goto_position(101,1,wait=True)\n", "poppy.abs_z.goto_position(34,1,wait=True)\n", "poppy.r_hand_z.goto_position(0,1,wait=True)\n", "\n", "#position de base\n", "poppy.r_arm_z.goto_position(-30,1)\n", "poppy.l_arm_z.goto_position(7,1,wait=True)\n", "poppy.l_elbow_y.goto_position(45,1,wait=True)\n", "poppy.r_elbow_y.goto_position(45,1)\n", "poppy.l_shoulder_y.goto_position(22,1)\n", "poppy.l_shoulder_x.goto_position(-2,1)\n", "poppy.l_wrist_x.goto_position(0,1)\n", "poppy.l_hand_z.goto_position(65,1)\n", "poppy.r_shoulder_y.goto_position(22,1)\n", "poppy.r_shoulder_x.goto_position(0,1)\n", "poppy.r_wrist_x.goto_position(0,1)\n", "poppy.r_hand_z.goto_position(0,1)\n", "poppy.abs_z.goto_position(0,1)\n", "poppy.bust_x.goto_position(0,1)\n", "poppy.bust_y.goto_position(0,1)\n", "poppy.head_y.goto_position(20,1)\n", "poppy.head_z.goto_position(0,1)\n", "poppy.r_arm_z.goto_position(0,1)\n", "\n", "\n", "# dépose triangle\n", "poppy.l_wrist_x.goto_position(150,0.5)\n", "poppy.l_arm_z.goto_position(10,0.5)\n", "poppy.l_shoulder_x.goto_position(25,0.5)\n", "poppy.l_shoulder_y.goto_position(0,1)\n", "poppy.abs_z.goto_position(20,0.5,wait=True)\n", "poppy.abs_z.goto_position(-2.5,0.5)\n", "poppy.head_y.goto_position(20,1)\n", "poppy.l_elbow_y.goto_position(-10,1,wait=True)\n", "poppy.l_hand_z.goto_position(65,1,wait=True)\n", "poppy.l_hand_z.goto_position(0,1,wait=True)\n", "poppy.head_z.goto_position(35,1)\n", "\n", "poppy.l_shoulder_y.goto_position(-78,2,wait=True)\n", "poppy.l_shoulder_x.goto_position(50,2)\n", "poppy.l_arm_z.goto_position(-69,1)\n", "poppy.l_elbow_y.goto_position(-4,1)\n", "poppy.l_wrist_x.goto_position(101,1,wait=True)\n", "poppy.head_z.goto_position(0,1)\n", "poppy.abs_z.goto_position(-7,1,wait=True)\n", "poppy.l_hand_z.goto_position(65,1,wait=True)\n", "\n", "#position de base\n", "poppy.r_arm_z.goto_position(0,1)\n", "poppy.l_arm_z.goto_position(7,1,wait=True)\n", "poppy.l_elbow_y.goto_position(45,1,wait=True)\n", "poppy.r_elbow_y.goto_position(45,1)\n", "poppy.l_shoulder_y.goto_position(22,1)\n", "poppy.l_shoulder_x.goto_position(-2,1)\n", "poppy.l_wrist_x.goto_position(0,1)\n", "poppy.l_hand_z.goto_position(65,1)\n", "poppy.r_shoulder_y.goto_position(22,1)\n", "poppy.r_shoulder_x.goto_position(0,1)\n", "poppy.r_wrist_x.goto_position(0,1)\n", "poppy.r_hand_z.goto_position(0,1)\n", "poppy.abs_z.goto_position(0,1)\n", "poppy.bust_x.goto_position(0,1)\n", "poppy.bust_y.goto_position(0,1)\n", "poppy.head_y.goto_position(20,1)\n", "poppy.head_z.goto_position(0,1)\n", "\n", "#dépose croix\n", "poppy.r_hand_z.goto_position(0,1,wait=True)\n", "poppy.r_wrist_x.goto_position(150,0.5,wait=True)\n", "poppy.r_arm_z.goto_position(-0.66,0.5)\n", "poppy.head_y.goto_position(20,1)\n", "poppy.head_z.goto_position(-45,1)\n", "poppy.r_shoulder_x.goto_position(-48.65,0.5,wait=True)\n", "poppy.abs_z.goto_position(18,1)\n", "poppy.r_shoulder_y.goto_position(-22,1)\n", "poppy.r_elbow_y.goto_position(-17,1,wait=True)\n", "poppy.r_arm_z.goto_position(10,0.5)\n", "poppy.r_elbow_y.goto_position(-22.9,1)\n", "poppy.bust_x.goto_position(12,1,wait=True)\n", "poppy.r_hand_z.goto_position(65,1,wait=True)\n", "\n", "poppy.r_arm_z.goto_position(-5,0.5,wait=True)\n", "poppy.bust_y.goto_position(0.5,1)\n", "poppy.r_shoulder_y.goto_position(-8,1)\n", "poppy.r_shoulder_x.goto_position(-102,1)\n", "poppy.r_elbow_y.goto_position(-5,0.5)\n", "poppy.r_wrist_x.goto_position(101,1,wait=True)\n", "poppy.abs_z.goto_position(43,1,wait=True)\n", "poppy.r_arm_z.goto_position(1,1,wait=True)\n", "poppy.r_hand_z.goto_position(0,1,wait=True)\n", "\n", "#position de base\n", "poppy.r_arm_z.goto_position(-30,1)\n", "poppy.l_arm_z.goto_position(7,1,wait=True)\n", "poppy.l_elbow_y.goto_position(45,1,wait=True)\n", "poppy.r_elbow_y.goto_position(45,1)\n", "poppy.l_shoulder_y.goto_position(22,1)\n", "poppy.l_shoulder_x.goto_position(-2,1)\n", "poppy.l_wrist_x.goto_position(0,1)\n", "poppy.l_hand_z.goto_position(65,1)\n", "poppy.r_shoulder_y.goto_position(22,1)\n", "poppy.r_shoulder_x.goto_position(0,1)\n", "poppy.r_wrist_x.goto_position(0,1)\n", "poppy.r_hand_z.goto_position(0,1)\n", "poppy.abs_z.goto_position(0,1)\n", "poppy.bust_x.goto_position(0,1)\n", "poppy.bust_y.goto_position(0,1)\n", "poppy.head_y.goto_position(20,1)\n", "poppy.head_z.goto_position(0,1)\n", "poppy.r_arm_z.goto_position(0,1)\n", "\n", "# dépose carré\n", "poppy.l_wrist_x.goto_position(150,0.5)\n", "\n", "poppy.l_arm_z.goto_position(50,1)\n", "poppy.head_y.goto_position(20,1)\n", "poppy.head_z.goto_position(45,1)\n", "poppy.l_shoulder_x.goto_position(41,1)\n", "poppy.l_shoulder_y.goto_position(-3,1)\n", "poppy.l_arm_z.goto_position(15,1)\n", "poppy.l_elbow_y.goto_position(-8,1.5,wait=True)\n", "poppy.bust_x.goto_position(-7,1.5,wait=True)\n", "poppy.abs_z.goto_position(-25,1.5,wait=True)\n", "poppy.l_elbow_y.goto_position(-15,1,wait=True)\n", "poppy.l_hand_z.goto_position(0,1,wait=True)\n", "\n", "poppy.l_shoulder_x.goto_position(90,1)\n", "poppy.bust_x.goto_position(0,1)\n", "poppy.l_wrist_x.goto_position(100,1,wait=True)\n", "poppy.abs_z.goto_position(-47,1)\n", "poppy.l_elbow_y.goto_position(-5,1,wait=True)\n", "poppy.l_arm_z.goto_position(4,1,wait=True)\n", "poppy.l_hand_z.goto_position(65,1)\n", "\n", "#position de base\n", "poppy.r_arm_z.goto_position(0,1)\n", "poppy.l_arm_z.goto_position(7,1,wait=True)\n", "poppy.l_elbow_y.goto_position(45,1,wait=True)\n", "poppy.r_elbow_y.goto_position(45,1)\n", "poppy.l_shoulder_y.goto_position(22,1)\n", "poppy.l_shoulder_x.goto_position(-2,1)\n", "poppy.l_wrist_x.goto_position(0,1)\n", "poppy.l_hand_z.goto_position(65,1)\n", "poppy.r_shoulder_y.goto_position(22,1)\n", "poppy.r_shoulder_x.goto_position(0,1)\n", "poppy.r_wrist_x.goto_position(0,1)\n", "poppy.r_hand_z.goto_position(0,1)\n", "poppy.abs_z.goto_position(0,1)\n", "poppy.bust_x.goto_position(0,1)\n", "poppy.bust_y.goto_position(0,1)\n", "poppy.head_y.goto_position(20,1)\n", "poppy.head_z.goto_position(0,1,wait=True)\n", "\n", "#dépose étoile\n", "poppy.l_wrist_x.goto_position(150,1)\n", "poppy.l_shoulder_y.goto_position(-14,1)\n", "poppy.l_shoulder_x.goto_position(30,1)\n", "poppy.l_arm_z.goto_position(-20,1,wait=True)\n", "poppy.l_arm_z.goto_position(-50,1)\n", "poppy.l_elbow_y.goto_position(2,1,wait=True)\n", "poppy.l_hand_z.goto_position(0,1,wait=True)\n", "poppy.l_elbow_y.goto_position(20,1,wait=True)\n", "poppy.l_shoulder_y.goto_position(-60,1)\n", "poppy.l_elbow_y.goto_position(10,1)\n", "poppy.l_wrist_x.goto_position(117,1,wait=True)\n", "poppy.l_elbow_y.goto_position(-37,1)\n", "poppy.l_shoulder_y.goto_position(-87.5,1)\n", "poppy.l_shoulder_x.goto_position(13,1)\n", "poppy.abs_z.goto_position(2,1)\n", "poppy.l_arm_z.goto_position(-64,1,wait=True)\n", "poppy.l_arm_z.goto_position(-76,1,wait=True)\n", "poppy.l_hand_z.goto_position(65,1,wait=True)\n", "\n", "#position de base\n", "poppy.r_arm_z.goto_position(0,1)\n", "poppy.l_arm_z.goto_position(7,1,wait=True)\n", "poppy.l_elbow_y.goto_position(45,1,wait=True)\n", "poppy.r_elbow_y.goto_position(45,1)\n", "poppy.l_shoulder_y.goto_position(22,1)\n", "poppy.l_shoulder_x.goto_position(-2,1)\n", "poppy.l_wrist_x.goto_position(0,1)\n", "poppy.l_hand_z.goto_position(65,1)\n", "poppy.r_shoulder_y.goto_position(22,1)\n", "poppy.r_shoulder_x.goto_position(0,1)\n", "poppy.r_wrist_x.goto_position(0,1)\n", "poppy.r_hand_z.goto_position(0,1)\n", "poppy.abs_z.goto_position(0,1)\n", "poppy.bust_x.goto_position(0,1)\n", "poppy.bust_y.goto_position(0,1)\n", "poppy.head_y.goto_position(20,1)\n", "poppy.head_z.goto_position(0,1,wait=True)\n", "\n", "poppy.l_shoulder_y.goto_position(-33,3)\n", "poppy.l_shoulder_x.goto_position(-15,3)\n", "poppy.l_arm_z.goto_position(-25,3)\n", "poppy.l_elbow_y.goto_position(44,3)\n", "poppy.l_wrist_x.goto_position(25,3)\n", "poppy.l_hand_z.goto_position(0,3)\n", "poppy.r_shoulder_y.goto_position(-33,3)\n", "poppy.r_shoulder_x.goto_position(20,3)\n", "poppy.r_arm_z.goto_position(25,3)\n", "poppy.r_elbow_y.goto_position(35,3)\n", "poppy.r_wrist_x.goto_position(33,3)\n", "poppy.r_hand_z.goto_position(60,3,wait=True)\n", "poppy.l_hand_z.goto_position(60,0.5)\n", "poppy.l_wrist_x.goto_position(90,1)\n", "poppy.r_wrist_x.goto_position(90,1)\n", "poppy.r_hand_z.goto_position(0,0.5,wait=True)\n", "poppy.l_hand_z.goto_position(0,0.5)\n", "poppy.l_wrist_x.goto_position(-90,1)\n", "poppy.r_wrist_x.goto_position(-90,1)\n", "poppy.r_hand_z.goto_position(60,0.5,wait=True)\n", "poppy.l_hand_z.goto_position(60,0.5)\n", "poppy.l_wrist_x.goto_position(90,1)\n", "poppy.r_wrist_x.goto_position(90,1)\n", "poppy.r_hand_z.goto_position(0,0.5,wait=True)\n", "poppy.l_hand_z.goto_position(0,0.5)\n", "poppy.l_wrist_x.goto_position(90,1)\n", "poppy.r_wrist_x.goto_position(90,1)\n", "poppy.r_hand_z.goto_position(60,0.5,wait=True)\n", "poppy.l_hand_z.goto_position(60,0.5)\n", "poppy.l_wrist_x.goto_position(-90,1)\n", "poppy.r_wrist_x.goto_position(-90,1)\n", "poppy.r_hand_z.goto_position(0,0.5,wait=True)\n", "poppy.l_hand_z.goto_position(0,0.5)\n", "poppy.l_wrist_x.goto_position(90,1)\n", "poppy.r_wrist_x.goto_position(90,1)\n", "poppy.r_hand_z.goto_position(60,0.5,wait=True)\n", "poppy.l_hand_z.goto_position(0,0.5)\n", "poppy.l_wrist_x.goto_position(-90,1)\n", "poppy.r_wrist_x.goto_position(-90,1)\n", "poppy.r_hand_z.goto_position(60,0.5,wait=True)\n", "poppy.l_hand_z.goto_position(60,0.5)\n", "poppy.l_wrist_x.goto_position(90,1)\n", "poppy.r_wrist_x.goto_position(90,1)\n", "poppy.r_hand_z.goto_position(0,0.5,wait=True)\n", "poppy.l_hand_z.goto_position(0,0.5)\n", "poppy.l_wrist_x.goto_position(-90,1)\n", "poppy.r_wrist_x.goto_position(-90,1)\n", "poppy.r_hand_z.goto_position(60,0.5,wait=True)\n" ] }, { "cell_type": "code", "execution_count": null, "metadata": { "collapsed": false }, "outputs": [], "source": [ "poppy.abs_z.goto_position(-42,1)" ] }, { "cell_type": "code", "execution_count": null, "metadata": { "collapsed": true }, "outputs": [], "source": [ "poppy.l_shoulder_y.goto_position(-33,3)\n", "poppy.l_shoulder_x.goto_position(-15,3)\n", "poppy.l_arm_z.goto_position(-25,3)\n", "poppy.l_elbow_y.goto_position(44,3)\n", "poppy.l_wrist_x.goto_position(25,3)\n", "poppy.l_hand_z.goto_position(0,3)\n", "poppy.r_shoulder_y.goto_position(-33,3)\n", "poppy.r_shoulder_x.goto_position(20,3)\n", "poppy.r_arm_z.goto_position(25,3)\n", "poppy.r_elbow_y.goto_position(35,3)\n", "poppy.r_wrist_x.goto_position(33,3)\n", "poppy.r_hand_z.goto_position(60,3,wait=True)\n", "poppy.l_hand_z.goto_position(60,0.5)\n", "poppy.l_wrist_x.goto_position(90,1)\n", "poppy.r_wrist_x.goto_position(90,1)\n", "poppy.r_hand_z.goto_position(0,0.5,wait=True)\n", "poppy.l_hand_z.goto_position(0,0.5)\n", "poppy.l_wrist_x.goto_position(-90,1)\n", "poppy.r_wrist_x.goto_position(-90,1)\n", "poppy.r_hand_z.goto_position(60,0.5,wait=True)\n", "poppy.l_hand_z.goto_position(60,0.5)\n", "poppy.l_wrist_x.goto_position(90,1)\n", "poppy.r_wrist_x.goto_position(90,1)\n", "poppy.r_hand_z.goto_position(0,0.5,wait=True)\n", "poppy.l_hand_z.goto_position(0,0.5)\n", "poppy.l_wrist_x.goto_position(90,1)\n", "poppy.r_wrist_x.goto_position(90,1)\n", "poppy.r_hand_z.goto_position(60,0.5,wait=True)\n", "poppy.l_hand_z.goto_position(60,0.5)\n", "poppy.l_wrist_x.goto_position(-90,1)\n", "poppy.r_wrist_x.goto_position(-90,1)\n", "poppy.r_hand_z.goto_position(0,0.5,wait=True)\n", "poppy.l_hand_z.goto_position(0,0.5)\n", "poppy.l_wrist_x.goto_position(90,1)\n", "poppy.r_wrist_x.goto_position(90,1)\n", "poppy.r_hand_z.goto_position(60,0.5,wait=True)\n", "poppy.l_hand_z.goto_position(0,0.5)\n", "poppy.l_wrist_x.goto_position(-90,1)\n", "poppy.r_wrist_x.goto_position(-90,1)\n", "poppy.r_hand_z.goto_position(60,0.5,wait=True)\n", "poppy.l_hand_z.goto_position(60,0.5)\n", "poppy.l_wrist_x.goto_position(90,1)\n", "poppy.r_wrist_x.goto_position(90,1)\n", "poppy.r_hand_z.goto_position(0,0.5,wait=True)\n", "poppy.l_hand_z.goto_position(0,0.5)\n", "poppy.l_wrist_x.goto_position(-90,1)\n", "poppy.r_wrist_x.goto_position(-90,1)\n", "poppy.r_hand_z.goto_position(60,0.5,wait=True)\n" ] }, { "cell_type": "code", "execution_count": null, "metadata": { "collapsed": true }, "outputs": [], "source": [] } ], "metadata": { "kernelspec": { "display_name": "Python 2", "language": "python", "name": "python2" } }, "nbformat": 4, "nbformat_minor": 0 }