no way to compare when less than two revisions

Differences

This shows you the differences between two versions of the page.


tutorials:demo:fetch_and_place [2019/08/15 19:16] – [VirtualBox Setup] arthur
Line 1: Line 1:
 +====== Zero prerequisites demo tutorial: Simple fetch and place ======
  
 +This tutorial is from the "Demo Tutorials" category, which assumes no prior knowledge of Ubuntu, ROS, Emacs, Lisp or robotics.
 +
 +===== Setting Up =====
 +
 +You will need a virtual machine to run this tutorial. We use VirtualBox to run the VM that contains all the preinstalled requisites needed. First, download and install VirtualBox on your computer, then download and configure the VM.
 +
 +====Install====
 +Here are some hints on how to install VirtualBox on Ubuntu, Arch, Windows and MacOS
 +
 +**Ubuntu 14.04-18.04.2**
 +
 +You can install VirtualBox via the Ubuntu Software center. If you prefer the bash console VirtualBox can be installed from the multiverse repositories like so:
 +<code bash>
 +sudo add-apt-repository multiverse
 +sudo apt update
 +sudo apt install virtualbox
 +</code>
 +
 +**Arch-Linux**
 +
 +Follow [[https://linuxhint.com/install-virtualbox-arch-linux/|this tutorial]] for the install via pacman.
 +
 +**Windows**
 +
 +Download [[https://download.virtualbox.org/virtualbox/5.2.32/VirtualBox-5.2.32-132073-Win.exe | version 5.2.32 for Windows Systems]], execute the .exe file and follow the installation instructions.
 +
 +The CPU needs to support virtualization to run a VM on Windows. The virtualization can be enabled in the BIOS. To get into the BIOS settings restart your machine, hit the settings button while booting (try F2, F8 and F10) and go into the CPU settings. There is something like 'Intel Virtual Technology' or 'CPU Virtualization' which needs to be enabled.
 +
 +**MacOS**
 +
 +Download [[https://download.virtualbox.org/virtualbox/5.2.32/VirtualBox-5.2.32-132073-OSX.dmg | the .dmg installer for OS X systems]], execute the file and follow the instructions.
 +
 +
 +====VirtualBox Setup====
 +
 +  * Get the Virtual Disk Image [[https://seafile.zfn.uni-bremen.de/d/60fda63a3a4047aaa59b/|cram_vm.vdi here]]. You need to enter your Uni-Bremen credentials to access the ZfN file-sharing platform. It contains an Ubuntu 16.04 with ROS kinetic and CRAM v7.0 pre-installed. 
 +  * Launch VirtualBox.
 +
 +First we want to create a new virtual machine. Click on the 'New' button:
 +{{ :tutorials:demo:vm1new.png?direct |}}
 +
 +Usually the simplified menu will open. Change to expert mode, it won't get too complicated.
 +{{ :tutorials:demo:vm2expert.png?direct |}}
 +
 +In this view the VM gets
 +  * the name 'cram-vm' 
 +  * the OS as 'Linux'
 +  * the version as 'Ubuntu (64-bit)'
 +Choose the VMs memory size (RAM), depending on your machines capacity, but less than 4GB could cause some performance issues.
 +
 +{{ :tutorials:demo:vm3setup.png?direct |}}
 +
 +The Virtual Disc Image downloaded before can now be used. Instead of creating a new one, the VM is set to 'Use an existing virtual hard disk file'. Over the button at the right the program opens a file explorer, where the cram-vm.vdi needs to be found (usually in Downloads) and selected. Finally 'Create' the VM.
 +
 +===Settings (optional)===
 +For better performance the VM could use some of the CPU's power. Choose the newly created VM and hit 'Settings'. Go to 'System' and 'Processor' and choose how many processor cores you want to give the VM.
 +{{ :tutorials:demo:vm4proc.png?direct |}}
 +
 +Everything is set up. The VM can now be started. The Ubuntu 16.04 system should start and automatically log into the only account, with the username and password 'cram'.
 +===== Crash Course on Ubuntu, ROS, Emacs, Lisp and Robotics :D =====
 +
 +==== Launching the terminal ====
 +To launch the terminal press the Super Key (The windows key on the keyboard) to launch search and type in "terminal" and launch the program. The keyboard shortcut is "''Ctrl + Alt + T''"
 +
 +
 +===== Simple Fetch and Place =====
 +
 +==== Environment setup ====
 +For this tutorial we need to set up the environment similar to how it is done for the real system: we will need an occupancy map which helps with navigation, an Inverse Kinematics solver for which deals with the mathematics related to manipulation, a map of the static parts of the environment with the furniture, etc.
 +
 +Let's load all these into memory and running by running a script called the launch file. Open a new terminal and run the following command.
 +<code>
 +$ roslaunch cram_bullet_world_tutorial world.launch
 +</code>
 +Do not close this terminal instance throughout this tutorial.
 +
 +==== REPL Setup ====
 +
 +Create a new instance of the terminal and start the LISP REPL from the terminal by typing:
 +<code>
 +$ roslisp_repl
 +</code>
 +
 +An emacs window with the REPL will have launched. Now let's load the package which holds the pick and place tutorial. Type in the following two commands into the REPL :
 +
 +''**Note**'' - ''"CL-USER>"'' is a part of your prompt and should not be typed in
 +
 +<code lisp>
 +CL-USER> (ros-load:load-system "cram_bullet_world_tutorial" :cram-bullet-world-tutorial)
 +CL-USER> (in-package :cram-bullet-world-tutorial)
 +</code>
 +
 +Your prompt will now change to ''BTW-TUT>'' which indicates that you have loaded and are now working inside the package called "cram_bullet_world_tutorial".
 +
 +==== Launching the Bullet World ====
 +
 +Now to launch a simulation of the map and the robot, type the following command into the REPL:
 +<code lisp>
 +BTW-TUT> (roslisp-utilities:startup-ros)
 +</code>
 +
 +You will get a pop-up window which will load a kitchen environment with a robot inside, called the Bullet world. This robot is a simulation of a robot called PR2, and we're going to use it to perform various tasks inside the bullet world.
 +
 +
 +At any point during the tutorial, if you want to clean/reset the bullet world, enter the following command into the REPL:
 +<code lisp>
 +BTW-TUT> (init-projection)
 +</code>
 +
 +Now, Let's define a method to spawn a bottle into the world and apply the physics using the Bullet physics engine and simulate the world for 10 seconds:
 +<code lisp>
 +BTW-TUT>
 +(defun spawn-bottle (spawn-pose)
 +  (unless (assoc :bottle btr::*mesh-files*)
 +    (add-objects-to-mesh-list))
 +  (btr-utils:spawn-object 'bottle-1 :bottle :color '(1 0 0) :pose spawn-pose)
 +  (btr:simulate btr:*current-bullet-world* 10))
 +</code>
 +
 +Now let's run the method in the REPL with some arguments and see what happens.
 +<code lisp>
 +BTW-TUT> (spawn-bottle '((-1.6 -0.9 0.82) (0 0 0 1)))
 +</code>
 +
 +
 +<code lisp>
 +BTW-TUT>
 +(defparameter *final-object-destination*
 +  (cl-transforms-stamped:make-pose-stamped
 +   "map" 0.0
 +   (cl-transforms:make-3d-vector -0.8 2 0.9)
 +   (cl-transforms:make-identity-rotation)))
 +
 +(defparameter *base-pose-near-table*
 +  (cl-transforms-stamped:make-pose-stamped
 +   "map" 0.0
 +   (cl-transforms:make-3d-vector -1.447d0 -0.150d0 0.0d0)
 +   (cl-transforms:axis-angle->quaternion (cl-transforms:make-3d-vector 0 0 1) (/ pi -2))))
 +   
 +(defparameter *downward-look-coordinate*
 +  (cl-transforms-stamped:make-pose-stamped
 +   "base_footprint" 0.0
 +   (cl-transforms:make-3d-vector 0.65335d0 0.076d0 0.758d0)
 +   (cl-transforms:make-identity-rotation)))
 +
 +(defparameter *base-pose-near-counter*
 +  (cl-transforms-stamped:make-pose-stamped
 +   "base_footprint" 0.0
 +   (cl-transforms:make-3d-vector -0.150d0 2.0d0 0.0d0)
 +   (cl-transforms:make-quaternion 0.0d0 0.0d0 -1.0d0 0.0d0)))
 +</code>
 +
 +<code lisp>
 +(defun move-bottle (bottle-spawn-pose)
 +  (spawn-bottle bottle-spawn-pose)
 +  (pr2-proj:with-simulated-robot
 +    (let ((?navigation-goal *base-pose-near-table*))
 +      (cpl:par
 +        (exe:perform (desig:a motion 
 +                              (type moving-torso)
 +                              (joint-angle 0.3)))
 +        (pp-plans::park-arms)
 +        ;; Moving the robot near the table.
 +        (exe:perform (desig:a motion
 +                              (type going)
 +                              (target (desig:a location 
 +                                               (pose ?navigation-goal)))))))
 +    ;; Looking towards the bottle before perceiving.
 +    (let ((?looking-direction *downward-look-coordinate*))
 +      (exe:perform (desig:a motion 
 +                            (type looking)
 +                            (target (desig:a location 
 +                                             (pose ?looking-direction))))))
 +    ;; Detect the bottle on the table.
 +    (let ((?grasping-arm :right)
 +          (?perceived-bottle (exe:perform (desig:a motion
 +                                                   (type detecting)
 +                                                   (object (desig:an object 
 +                                                                     (type :bottle)))))))
 +      ;; Pick up the bottle
 +      (exe:perform (desig:an action
 +                             (type picking-up)
 +                             (arm ?grasping-arm)
 +                             (grasp left-side)
 +                             (object ?perceived-bottle)))
 +      (pp-plans::park-arms :arm ?grasping-arm)
 +      ;; Moving the robot near the counter.
 +      (let ((?nav-goal *base-pose-near-counter*))
 +        (exe:perform (desig:a motion
 +                              (type going)
 +                              (target (desig:a location 
 +                                               (pose ?nav-goal))))))
 +      (coe:on-event (make-instance 'cpoe:robot-state-changed))
 +      ;; Setting the bottle down on the counter
 +      (let ((?drop-pose *final-object-destination*))
 +        (exe:perform (desig:an action
 +                               (type placing)
 +                               (arm ?grasping-arm)
 +                               (object ?perceived-bottle)
 +                               (target (desig:a location 
 +                                                (pose ?drop-pose))))))
 +      (pp-plans::park-arms :arm ?grasping-arm))))
 +</code>
 +Move bottle accepts the position the bottle will spawn in and then move it to the final destination, which is the counter.
 +Now run ''move-bottle'' with the arguments we initially used to spawn the bottle.
 +<code lisp>
 +BTW-TUT> (move-bottle '((-1.6 -0.9 0.82) (0 0 0 1)))
 +</code>
 +You will see that the robot successfully picks the bottle and places it on the counter.
 +
 +===== Recovering from Failures =====
 +
 +The previous example worked perfectly, because we knew the exact coordinates to look for the bottle. This is hardly true for the real life scenario, especially since we are dealing with a kitchen environment, far from being precise compared to a factory floor. What would happen if the bottle was moved a little bit to the right of its previous spawn position? For this, let's change the arguments to reflect this on our method, and let's see what happens.
 +
 +<code lisp>
 +BTW-TUT> (move-bottle '((-2 -0.9 0.860) (0 0 0 1)))
 +</code>
 +And the output will look like this.
 +<code lisp>
 +BTW-TUT>
 +; Evaluation aborted on #<CRAM-COMMON-FAILURES:PERCEPTION-OBJECT-NOT-FOUND {1013AC5B93}>.
 +</code>
 +
 +{{:tutorials:intermediate:btw-tut-cant-see-bottle.png?800|}}
 +
 +Clearly the robot cannot find the object anymore because even though the robot is near the bottle, it is out of the field of vision of the robot due to the predefined base and object pose in our code. Let's try fixing this issue. 
 +
 +To understand the syntax and get a refresher on failure handling, you can refer to [[tutorials:beginner:failure_handling|Failure Handling]].
 +We're going to add some code into fixing perception in our case, so that the robot would still be able to find the bottle. Let's list down a plan of action for this.
 +  - Tilt the head of the robot downwards
 +  - Try to detect the bottle
 +  - If, 
 +       * successful in finding the bottle - continue with the rest of the code.
 +       * failed to find the bottle - turn the head to a different configuration (eg., left/right) and try detecting again.
 +   - When all possible directions fail, error out.
 +
 +Let's define some additional parameters to aid us:
 +<code lisp>
 +BTW-TUT>
 +(defparameter *left-downward-look-coordinate*
 +  (cl-transforms-stamped:make-pose-stamped
 +   "base_footprint" 0.0
 +   (cl-transforms:make-3d-vector 0.65335d0 0.76d0 0.758d0)
 +   (cl-transforms:make-identity-rotation)))
 +
 +(defparameter *right-downward-look-coordinate*
 +  (cl-transforms-stamped:make-pose-stamped
 +   "base_footprint" 0.0
 +   (cl-transforms:make-3d-vector 0.65335d0 -0.76d0 0.758d0)
 +   (cl-transforms:make-identity-rotation)))
 +   
 +</code>
 +We defined two coordinates ''*left-downward-look-coordinate*'' and ''*right-downward-look-coordinate*'' with respective to our robot base footprint as alternative directions to look for when downward look fails.
 +
 +Now we define a method ''find-object'' which encapsulates our plan with failure handling :
 +<code lisp>
 +(defun get-preferred-arm-for-direction (direction-looked)
 +  (let ((preferred-arm :RIGHT))
 +    (when (eq direction-looked *left-downward-look-coordinate*)
 +      (setf preferred-arm :LEFT))
 +    preferred-arm))
 +    
 +(defun find-object (?object-type)
 +  (let* ((possible-look-directions `(,*downward-look-coordinate*
 +                                     ,*left-downward-look-coordinate*
 +                                     ,*right-downward-look-coordinate*))
 +         (?looking-direction (first possible-look-directions)))
 +    (setf possible-look-directions (cdr possible-look-directions))
 +    (exe:perform (desig:a motion 
 +                          (type looking)
 +                          (target (desig:a location 
 +                                           (pose ?looking-direction)))))
 + 
 +    (cpl:with-failure-handling
 +        ((cram-common-failures:perception-object-not-found (e)
 +           ;; Try different look directions until there is none left.
 +           (when possible-look-directions
 +             (roslisp:ros-warn (perception-failure) "~a~%Turning head." e)
 +             (exe:perform (desig:a motion 
 +                                   (type looking) 
 +                                   (direction forward)))
 +             (setf ?looking-direction (first possible-look-directions))
 +             (setf possible-look-directions (cdr possible-look-directions))
 +             (exe:perform (desig:a motion 
 +                                   (type looking)
 +                                   (target (desig:a location
 +                                                    (pose ?looking-direction)))))
 +             (cpl:retry))
 +           (cpl:fail 'common-fail:looking-high-level-failure)))
 + 
 +      (let ((?perceived-bottle
 +              (exe:perform (desig:a motion
 +                                    (type detecting)
 +                                    (object (desig:an object 
 +                                                      (type ?object-type)))))))
 +        (values ?perceived-bottle (get-preferred-arm-for-direction ?looking-direction))))))
 +        </code>
 +Let's see what this method does. The ''with-failure-handling'' clause here deals with ''cram-common-failures:perception-object-not-found'' which if you remember, was the error raised when the robot couldn't find the bottle. So instead of only looking downwards, the code will now iterate between downwards, left and right, and only upon a failure in all these, will an error be bubbled up - thus increasing our effective field of view. 
 +Also note that the ''find-object'' suggests an arm to use, depending on the direction it looked.
 +Let us also update our ''move-bottle'' to use this method.
 +<code lisp>
 +(defun move-bottle (bottle-spawn-pose)
 +  (spawn-bottle bottle-spawn-pose)
 +  (pr2-proj:with-simulated-robot
 +    (let ((?navigation-goal *base-pose-near-table*))
 +      (cpl:par
 +        (exe:perform (desig:a motion 
 +                              (type moving-torso)
 +                              (joint-angle 0.3)))
 +        (pp-plans::park-arms)
 +        ;; Moving the robot near the table.
 +        (exe:perform (desig:a motion
 +                              (type going)
 +                              (target (desig:a location 
 +                                               (pose ?navigation-goal)))))))
 +    ;; Find and detect the bottle on the table.
 +    (multiple-value-bind (?perceived-bottle ?grasping-arm) 
 +        (find-object :bottle)
 +      (exe:perform (desig:an action
 +                             (type picking-up)
 +                             (arm ?grasping-arm)
 +                             (grasp left-side)
 +                             (object ?perceived-bottle)))
 +      (pp-plans::park-arms :arm ?grasping-arm)
 +      ;; Moving the robot near the counter.
 +      (let ((?nav-goal *base-pose-near-counter*))
 +        (exe:perform (desig:a motion
 +                              (type going)
 +                              (target (desig:a location 
 +                                               (pose ?nav-goal))))))
 +
 +      (coe:on-event (make-instance 'cpoe:robot-state-changed))
 +      ;; Setting the object down on the counter
 +      (let ((?drop-pose *final-object-destination*))
 +        (exe:perform (desig:an action
 +                               (type placing)
 +                               (arm ?grasping-arm)
 +                               (object ?perceived-bottle)
 +                               (target (desig:a location 
 +                                                (pose ?drop-pose))))))
 +      (pp-plans::park-arms :arm ?grasping-arm))))
 +</code>
 +
 +Run ''move-bottle'' again, and this time, you'll find that the robot succeeds in transporting the bottle.
 +{{:tutorials:intermediate:btw-tut-found-bottle-again.png?800|}}
 +
 +===== Expanding Failure Management Capabilities =====
 +Everything is good so far, but let's call this a lucky coincidence. For the robot, knowing which arm to use to pick up the bottle is not always enough. There are many positions with which we can grasp objects - from the object's front, back, left, right, etc. One might think that since the bottle is a rotationally symmetric object, it doesn't matter which side you approach from. But consider the bottle as an object model, which has a specific front, back and sides according to its orientation with respect to the bullet world. In which case, the side with which the arm approaches the bottle greatly matters, accounting for the configuration of the joints the robot arm will make while trying to grasp - some poses may be unachievable, while others may result in the collision of the arm with the table.
 +
 +Let's try to visualize this issue, by spawning the bottle in yet another position:
 +<code lisp>
 +BTW-TUT> (spawn-bottle '((-1.1 -0.75 0.860) (0 0 0 1)))
 +</code>
 +Now clean up and run ''move-bottle'' once more, and the output should be something similar to as below:
 +<code lisp>
 +BTW-TUT> (move-bottle '((-1.1 -0.75 0.860) (0 0 0 1)))
 +[(PICK-PLACE PICK-UP) INFO] 1550502686.470: Opening gripper
 +[(PICK-PLACE PICK-UP) INFO] 1550502686.470: Reaching
 +[(PICK-PLACE MOVE-ARMS-IN-SEQUENCE) WARN] 1550502686.797: #<POSE-STAMPED 
 +   FRAME-ID: "torso_lift_link", STAMP: 0.0
 +   #<3D-VECTOR (0.6819813024319948d0 0.4206671881870251d0 -0.11278482277792945d0)>
 +   #<QUATERNION (-0.005172943672216379d0 0.0055962335340426494d0 -0.7845776913102387d0 0.6199836767360266d0)>> is unreachable for EE.
 +Ignoring.
 +[(PICK-PLACE MOVE-ARMS-IN-SEQUENCE) ERROR] 1550502687.092: #<POSE-STAMPED 
 +   FRAME-ID: "torso_lift_link", STAMP: 0.0
 +   #<3D-VECTOR (0.6797228574484719d0 0.4210222500057509d0 -0.2627674055849005d0)>
 +   #<QUATERNION (-0.005172943672216379d0 0.0055962335340426494d0 -0.7845776913102387d0 0.6199836767360266d0)>> is unreachable for EE.
 +Failing.
 +[(PP-PLANS PICK-UP) WARN] 1550502687.092: Manipulation messed up: #<POSE-STAMPED 
 +   FRAME-ID: "torso_lift_link", STAMP: 0.0
 +   #<3D-VECTOR (0.6797228574484719d0 0.4210222500057509d0 -0.2627674055849005d0)>
 +   #<QUATERNION (-0.005172943672216379d0 0.0055962335340426494d0 -0.7845776913102387d0 0.6199836767360266d0)>> is unreachable for EE.
 +Ignoring.
 +; Evaluation aborted on #<CRAM-COMMON-FAILURES:MANIPULATION-POSE-UNREACHABLE {10100E64C3}>.
 +</code>
 +
 +The robot has failed to grasp again, even though the bottle is well within perception and grasping range.
 +
 +So what went wrong? If you go back to definition of ''get-preferred-arm-for-direction'':
 +<code lisp>
 +(defun get-preferred-arm-for-direction (direction-looked)
 +  (let ((preferred-arm :RIGHT))
 +    ;; Always prefers right arm unless looking at the left side
 +    (when (eq direction-looked *left-downward-look-coordinate*)
 +      (setf preferred-arm :LEFT))
 +    preferred-arm))
 +</code>
 +And the part where we pick up the object:
 +<code lisp>
 +        (exe:perform (desig:an action
 +                               (type picking-up)
 +                               (arm ?grasping-arm)
 +                               (grasp left-side)
 +                               (object ?perceived-bottle)))
 +</code>
 +We see that the robot defaults the right arm when the object is in the center and will always try to grasp the left side of the bottle, even when the object is slightly favoring the left side under it (Refer the figure below). 
 +
 +Note: ''We have been using left-side here a lot. In the context of (grasp left-side), it refers to the left-side of the bottle. But what defines the "left-side"?''
 +
 +''Before we understand it, we have to acknowledge that every object spawned in the bullet world has its own coordinate axes - even rotationally symmetric objects like the bottle here. And the definition for left-side is the side of the -ve Y-axis in the bottle coordinate frame. Similarly right-side is +ve Y-axis, front is denoted by +ve X-axis and the back by -ve X-axis. ''
 +''With this the "left-side" grasp can change based on how the object is oriented in the world. But it remains the w.r.t the object coordinate frame.''
 +
 +''The file at <your workspace>/cram/cram_common/cram_object_knowledge/src/household.lisp holds some definitions for grasps supported by the household objects supporte in CRAM.''
 +
 +{{:tutorials:intermediate:btw-tut-grasp-config-fail.png?800|}}
 +
 +Once again, let's formulate a strategy like the previous case here. The plan we are going for will look something like this:
 +  - Choose the favored arm.
 +  - Get all possible grasp poses for the given type of the object and the arm.
 +  - Choose one grasp from the possible grasp list.
 +  - Try to grasp the object.
 +  - If,
 +     * Grasp succeeds - Continue with the rest of the code
 +     * Grasp Fails - Choose a different grasp pose from the list.
 +  - When no more possible grasp poses, try changing the arm used to grasp **Once** and try resuming from  Step (2)
 +  - When attempted with all arms and grasps, error out.
 +
 +Let's encapsulate all this in a method called ''pick-up-object'':
 +<code lisp>
 +(defun pick-up-object (?perceived-object ?object-type ?grasping-arm)
 +  (let ((?possible-arms '(:right :left)))
 +    ;;Retry by changing the arm
 +    (cpl:with-retry-counters ((arm-change-retry 1))
 +        (cpl:with-failure-handling
 +            ((common-fail:object-unreachable (e)
 +               (roslisp:ros-warn (arm-failure) "Manipulation failed: ~a~%" e)
 +               (cpl:do-retry arm-change-retry
 +                 (setf ?grasping-arm (car (remove ?grasping-arm ?possible-arms)))
 +                 (cpl:retry))
 +               (roslisp:ros-warn (arm-failures) "No more retries left")))
 +             
 +          ;; Retry by changing the grasp
 +          (let* ((?possible-grasp
 +                   (cram-object-interfaces:get-object-type-grasps ?object-type nil nil nil ?grasping-arm))
 +                 (?grasp (cut:lazy-car ?possible-grasp)))
 +            (cpl:with-retry-counters ((grasp-retries 3))
 +              (cpl:with-failure-handling
 +                  (((or cram-common-failures:manipulation-pose-unreachable
 +                        cram-common-failures:gripper-closed-completely) (e)
 +                     (roslisp:ros-warn (grasp-failure)
 +                                       "~a~%Failed to grasp from ~a using ~a arm "
 +                                       e ?grasp ?grasping-arm)
 +                     (cpl:do-retry grasp-retries
 +                       (when (cut:lazy-car ?possible-grasp)
 +                         (roslisp:ros-info (trying-new-grasp)
 +                                           "Trying to grasp from ~a using ~a arm"
 +                                         ?grasp ?grasping-arm)
 +                         (setf ?possible-grasp (cut:lazy-cdr ?possible-grasp))
 +                         (pp-plans::park-arms)
 +                         (setf ?grasp (cut:lazy-car ?possible-grasp))
 +                         (cpl:retry)))
 +                     (roslisp:ros-warn (grasp-failures) "No more retries left")
 +                     (cpl:fail 'common-fail:object-unreachable)))
 +                ;; Perform the grasp
 +                (exe:perform (desig:an action
 +                                       (type picking-up)
 +                                       (arm ?grasping-arm)
 +                                       (grasp ?grasp)
 +                                       (object ?perceived-object)))))))))
 +  ?grasping-arm)
 +</code>
 +With this, the ''pick-up-object'' can now iterate through all possible grasp configurations stored in ''?possible-grasp''. The ''cram-object-interaces:get-object-type-grasps'' is a useful method which will give these values as a lazy list, provided the grasping arm and the object type.
 + 
 +There are two nested failure-handling clauses here. The inner failure-handling part will take care of ''cram-common-failures:manipulation-pose-unreachable'' and ''cram-common-failures:gripper-closed-completely'' - both of which are errors which can occur during a failed grasp. The recovery method will iterate through all possible grasp configurations for a given arm. Upon failure of this, the outer failure handling clause will take care of the ''common-fail:object-unreachable'' error thrown by the inner part and change the arm it's trying to grasp the object with and then retry the entire procedure again.
 +
 +And only upon the failure of all these will the error be bubbled up. The method also returns the grasping arm it used to pick the object up so that the rest of the code is aware of the arm in which the bottle rests. Also, note that the arm we decided on earlier in ''find-object'' now acts as a bias to reduce the number of searches we do to find a successful configuration. We have also written appropriate warning statements to be informed about the actions the robot is taking.
 +
 +Also let's redefine ''move-bottle'' again to include these:
 +<code lisp>
 +(defun move-bottle (bottle-spawn-pose)
 +  (spawn-bottle bottle-spawn-pose)
 +  (pr2-proj:with-simulated-robot
 +    (let ((?navigation-goal *base-pose-near-table*))
 +      (cpl:par
 +        (exe:perform (desig:a motion 
 +                              (type moving-torso) 
 +                              (joint-angle 0.3)))
 +        (pp-plans::park-arms)
 +        ;; Moving the robot near the table.
 +        (exe:perform (desig:a motion
 +                              (type going)
 +                              (target (desig:a location 
 +                                               (pose ?navigation-goal)))))))
 +      
 +    (multiple-value-bind (?perceived-bottle ?grasping-arm) 
 +        (find-object :bottle)
 +      (setf ?grasping-arm (pick-up-object ?perceived-bottle :bottle ?grasping-arm))
 +      (pp-plans::park-arms :arm ?grasping-arm)
 +      ;; Moving the robot near the counter.
 +      (let ((?nav-goal *base-pose-near-counter*))
 +        (exe:perform (desig:a motion
 +                              (type going)
 +                              (target (desig:a location 
 +                                               (pose ?nav-goal))))))
 + 
 +      (coe:on-event (make-instance 'cpoe:robot-state-changed))
 +      ;; Setting the object down on the counter
 +      (let ((?drop-pose *final-object-destination*))
 +        (exe:perform (desig:an action
 +                               (type placing)
 +                               (arm ?grasping-arm)
 +                               (object ?perceived-bottle)
 +                               (target (desig:a location 
 +                                                (pose ?drop-pose))))))
 +      (pp-plans::park-arms :arm ?grasping-arm))))
 +</code>
 +You should see a result that looks like the one below. //[Some messages that would come up are suppressed here for readability.]//
 +<code lisp> 
 +BTW-TUT> (init-projection)
 +BTW-TUT> (move-bottle)
 +[(PICK-PLACE PICK-UP) INFO] 1550504321.279: Opening gripper
 +[(PICK-PLACE PICK-UP) INFO] 1550504321.279: Reaching
 +[(GRASP-FAILURE) WARN] Failed to grasp from LEFT-SIDE using RIGHT arm 
 +[(TRYING-NEW-GRASP) INFO] 1550504800.749: Trying to grasp from RIGHT-SIDE using RIGHT arm
 +[(PICK-PLACE PICK-UP) INFO] 1550504800.789: Opening gripper
 +[(PICK-PLACE PICK-UP) INFO] 1550504800.789: Reaching
 +[(GRASP-FAILURE) WARN] Failed to grasp from RIGHT-SIDE using RIGHT arm 
 +[(TRYING-NEW-GRASP) INFO] 1550504801.577: Trying to grasp from BACK using RIGHT arm
 +[(PICK-PLACE PICK-UP) INFO] 1550504801.601: Opening gripper
 +[(PICK-PLACE PICK-UP) INFO] 1550504801.602: Reaching
 +[(PICK-PLACE PICK-UP) INFO] 1550504801.939: Gripping
 +[(PICK-PLACE PICK-UP) INFO] 1550504801.973: Assert grasp into knowledge base
 +[(PICK-PLACE PICK-UP) INFO] 1550504801.974: Lifting
 +[(PICK-PLACE PLACE) INFO] 1550504802.356: Reaching
 +[(PICK-PLACE PLACE) INFO] 1550504802.508: Putting
 +[(PICK-PLACE PLACE) INFO] 1550504802.619: Opening gripper
 +[(PICK-PLACE PLACE) INFO] 1550504802.655: Retract grasp in knowledge base
 +[(PICK-PLACE PLACE) INFO] 1550504802.660: Retracting
 +</code>
 +{{:tutorials:intermediate:btw-tut-grasp-again.png?800|}}
 +
 +The robot has once again succeeded in grasping the object.