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" | ||
+ | |||
+ | ===== 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 | ||
+ | </ | ||
+ | |||
+ | **Arch-Linux** | ||
+ | |||
+ | Follow [[https:// | ||
+ | |||
+ | **Windows** | ||
+ | |||
+ | Download [[https:// | ||
+ | |||
+ | 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' | ||
+ | |||
+ | **MacOS** | ||
+ | |||
+ | Download [[https:// | ||
+ | |||
+ | |||
+ | ====VirtualBox Setup==== | ||
+ | |||
+ | * Get the Virtual Disk Image [[https:// | ||
+ | * Launch VirtualBox. | ||
+ | |||
+ | First we want to create a new virtual machine. Click on the ' | ||
+ | {{ : | ||
+ | |||
+ | Usually the simplified menu will open. Change to expert mode, it won't get too complicated. | ||
+ | {{ : | ||
+ | |||
+ | In this view the VM gets | ||
+ | * the name ' | ||
+ | * the OS as ' | ||
+ | * the version as ' | ||
+ | Choose the VMs memory size (RAM), depending on your machines capacity, but less than 4GB could cause some performance issues. | ||
+ | |||
+ | {{ : | ||
+ | |||
+ | 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 ' | ||
+ | |||
+ | ===Settings (optional)=== | ||
+ | For better performance the VM could use some of the CPU's power. Choose the newly created VM and hit ' | ||
+ | {{ : | ||
+ | |||
+ | 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 ' | ||
+ | ===== 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 " | ||
+ | |||
+ | |||
+ | ===== 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, | ||
+ | |||
+ | 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. | ||
+ | < | ||
+ | $ roslaunch cram_bullet_world_tutorial world.launch | ||
+ | </ | ||
+ | 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: | ||
+ | < | ||
+ | $ roslisp_repl | ||
+ | </ | ||
+ | |||
+ | 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 : | ||
+ | |||
+ | '' | ||
+ | |||
+ | <code lisp> | ||
+ | CL-USER> (ros-load: | ||
+ | CL-USER> (in-package : | ||
+ | </ | ||
+ | |||
+ | Your prompt will now change to '' | ||
+ | |||
+ | ==== 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: | ||
+ | </ | ||
+ | |||
+ | 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) | ||
+ | </ | ||
+ | |||
+ | 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:: | ||
+ | (add-objects-to-mesh-list)) | ||
+ | (btr-utils: | ||
+ | (btr: | ||
+ | </ | ||
+ | |||
+ | Now let's run the method in the REPL with some arguments and see what happens. | ||
+ | <code lisp> | ||
+ | BTW-TUT> (spawn-bottle ' | ||
+ | </ | ||
+ | |||
+ | |||
+ | <code lisp> | ||
+ | BTW-TUT> | ||
+ | (defparameter *final-object-destination* | ||
+ | (cl-transforms-stamped: | ||
+ | " | ||
+ | | ||
+ | | ||
+ | |||
+ | (defparameter *base-pose-near-table* | ||
+ | (cl-transforms-stamped: | ||
+ | " | ||
+ | | ||
+ | | ||
+ | |||
+ | (defparameter *downward-look-coordinate* | ||
+ | (cl-transforms-stamped: | ||
+ | " | ||
+ | | ||
+ | | ||
+ | |||
+ | (defparameter *base-pose-near-counter* | ||
+ | (cl-transforms-stamped: | ||
+ | " | ||
+ | | ||
+ | | ||
+ | </ | ||
+ | |||
+ | <code lisp> | ||
+ | (defun move-bottle (bottle-spawn-pose) | ||
+ | (spawn-bottle bottle-spawn-pose) | ||
+ | (pr2-proj: | ||
+ | (let ((? | ||
+ | (cpl:par | ||
+ | (exe: | ||
+ | (type moving-torso) | ||
+ | (joint-angle 0.3))) | ||
+ | (pp-plans:: | ||
+ | ;; Moving the robot near the table. | ||
+ | (exe: | ||
+ | (type going) | ||
+ | (target (desig:a location | ||
+ | (pose ? | ||
+ | ;; Looking towards the bottle before perceiving. | ||
+ | (let ((? | ||
+ | (exe: | ||
+ | (type looking) | ||
+ | (target (desig:a location | ||
+ | (pose ? | ||
+ | ;; Detect the bottle on the table. | ||
+ | (let ((? | ||
+ | (? | ||
+ | (type detecting) | ||
+ | | ||
+ | (type : | ||
+ | ;; Pick up the bottle | ||
+ | (exe: | ||
+ | (type picking-up) | ||
+ | (arm ? | ||
+ | | ||
+ | | ||
+ | (pp-plans:: | ||
+ | ;; Moving the robot near the counter. | ||
+ | (let ((?nav-goal *base-pose-near-counter*)) | ||
+ | (exe: | ||
+ | (type going) | ||
+ | (target (desig:a location | ||
+ | (pose ? | ||
+ | (coe: | ||
+ | ;; Setting the bottle down on the counter | ||
+ | (let ((? | ||
+ | (exe: | ||
+ | (type placing) | ||
+ | (arm ? | ||
+ | | ||
+ | | ||
+ | (pose ? | ||
+ | (pp-plans:: | ||
+ | </ | ||
+ | Move bottle accepts the position the bottle will spawn in and then move it to the final destination, | ||
+ | Now run '' | ||
+ | <code lisp> | ||
+ | BTW-TUT> (move-bottle ' | ||
+ | </ | ||
+ | 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, | ||
+ | |||
+ | <code lisp> | ||
+ | BTW-TUT> (move-bottle '((-2 -0.9 0.860) (0 0 0 1))) | ||
+ | </ | ||
+ | And the output will look like this. | ||
+ | <code lisp> | ||
+ | BTW-TUT> | ||
+ | ; Evaluation aborted on #< | ||
+ | </ | ||
+ | |||
+ | {{: | ||
+ | |||
+ | 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: | ||
+ | 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: | ||
+ | " | ||
+ | | ||
+ | | ||
+ | |||
+ | (defparameter *right-downward-look-coordinate* | ||
+ | (cl-transforms-stamped: | ||
+ | " | ||
+ | | ||
+ | | ||
+ | |||
+ | </ | ||
+ | We defined two coordinates '' | ||
+ | |||
+ | Now we define a method '' | ||
+ | <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 (? | ||
+ | (let* ((possible-look-directions `(, | ||
+ | , | ||
+ | , | ||
+ | | ||
+ | (setf possible-look-directions (cdr possible-look-directions)) | ||
+ | (exe: | ||
+ | (type looking) | ||
+ | (target (desig:a location | ||
+ | (pose ? | ||
+ | |||
+ | (cpl: | ||
+ | ((cram-common-failures: | ||
+ | ;; Try different look directions until there is none left. | ||
+ | (when possible-look-directions | ||
+ | | ||
+ | | ||
+ | (type looking) | ||
+ | | ||
+ | (setf ? | ||
+ | (setf possible-look-directions (cdr possible-look-directions)) | ||
+ | | ||
+ | (type looking) | ||
+ | | ||
+ | (pose ? | ||
+ | | ||
+ | | ||
+ | |||
+ | (let ((? | ||
+ | (exe: | ||
+ | (type detecting) | ||
+ | (object (desig:an object | ||
+ | (type ? | ||
+ | (values ? | ||
+ | </ | ||
+ | Let's see what this method does. The '' | ||
+ | Also note that the '' | ||
+ | Let us also update our '' | ||
+ | <code lisp> | ||
+ | (defun move-bottle (bottle-spawn-pose) | ||
+ | (spawn-bottle bottle-spawn-pose) | ||
+ | (pr2-proj: | ||
+ | (let ((? | ||
+ | (cpl:par | ||
+ | (exe: | ||
+ | (type moving-torso) | ||
+ | (joint-angle 0.3))) | ||
+ | (pp-plans:: | ||
+ | ;; Moving the robot near the table. | ||
+ | (exe: | ||
+ | (type going) | ||
+ | (target (desig:a location | ||
+ | (pose ? | ||
+ | ;; Find and detect the bottle on the table. | ||
+ | (multiple-value-bind (? | ||
+ | (find-object :bottle) | ||
+ | (exe: | ||
+ | (type picking-up) | ||
+ | (arm ? | ||
+ | | ||
+ | | ||
+ | (pp-plans:: | ||
+ | ;; Moving the robot near the counter. | ||
+ | (let ((?nav-goal *base-pose-near-counter*)) | ||
+ | (exe: | ||
+ | (type going) | ||
+ | (target (desig:a location | ||
+ | (pose ? | ||
+ | |||
+ | (coe: | ||
+ | ;; Setting the object down on the counter | ||
+ | (let ((? | ||
+ | (exe: | ||
+ | (type placing) | ||
+ | (arm ? | ||
+ | | ||
+ | | ||
+ | (pose ? | ||
+ | (pp-plans:: | ||
+ | </ | ||
+ | |||
+ | Run '' | ||
+ | {{: | ||
+ | |||
+ | ===== 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' | ||
+ | |||
+ | Let's try to visualize this issue, by spawning the bottle in yet another position: | ||
+ | <code lisp> | ||
+ | BTW-TUT> (spawn-bottle ' | ||
+ | </ | ||
+ | Now clean up and run '' | ||
+ | <code lisp> | ||
+ | BTW-TUT> (move-bottle ' | ||
+ | [(PICK-PLACE PICK-UP) INFO] 1550502686.470: | ||
+ | [(PICK-PLACE PICK-UP) INFO] 1550502686.470: | ||
+ | [(PICK-PLACE MOVE-ARMS-IN-SEQUENCE) WARN] 1550502686.797: | ||
+ | | ||
+ | #< | ||
+ | #< | ||
+ | Ignoring. | ||
+ | [(PICK-PLACE MOVE-ARMS-IN-SEQUENCE) ERROR] 1550502687.092: | ||
+ | | ||
+ | #< | ||
+ | #< | ||
+ | Failing. | ||
+ | [(PP-PLANS PICK-UP) WARN] 1550502687.092: | ||
+ | | ||
+ | #< | ||
+ | #< | ||
+ | Ignoring. | ||
+ | ; Evaluation aborted on #< | ||
+ | </ | ||
+ | |||
+ | 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 '' | ||
+ | <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)) | ||
+ | </ | ||
+ | And the part where we pick up the object: | ||
+ | <code lisp> | ||
+ | (exe: | ||
+ | (type picking-up) | ||
+ | (arm ? | ||
+ | | ||
+ | | ||
+ | </ | ||
+ | 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: '' | ||
+ | |||
+ | '' | ||
+ | '' | ||
+ | |||
+ | '' | ||
+ | |||
+ | {{: | ||
+ | |||
+ | 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 '' | ||
+ | <code lisp> | ||
+ | (defun pick-up-object (? | ||
+ | (let ((? | ||
+ | ;;Retry by changing the arm | ||
+ | (cpl: | ||
+ | (cpl: | ||
+ | ((common-fail: | ||
+ | | ||
+ | | ||
+ | (setf ? | ||
+ | | ||
+ | | ||
+ | |||
+ | ;; Retry by changing the grasp | ||
+ | (let* ((? | ||
+ | | ||
+ | | ||
+ | (cpl: | ||
+ | (cpl: | ||
+ | (((or cram-common-failures: | ||
+ | cram-common-failures: | ||
+ | | ||
+ | " | ||
+ | e ?grasp ? | ||
+ | | ||
+ | (when (cut: | ||
+ | | ||
+ | " | ||
+ | ? | ||
+ | (setf ? | ||
+ | | ||
+ | (setf ?grasp (cut: | ||
+ | | ||
+ | | ||
+ | | ||
+ | ;; Perform the grasp | ||
+ | (exe: | ||
+ | (type picking-up) | ||
+ | (arm ? | ||
+ | | ||
+ | | ||
+ | ? | ||
+ | </ | ||
+ | With this, the '' | ||
+ | |||
+ | There are two nested failure-handling clauses here. The inner failure-handling part will take care of '' | ||
+ | |||
+ | 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 '' | ||
+ | |||
+ | Also let's redefine '' | ||
+ | <code lisp> | ||
+ | (defun move-bottle (bottle-spawn-pose) | ||
+ | (spawn-bottle bottle-spawn-pose) | ||
+ | (pr2-proj: | ||
+ | (let ((? | ||
+ | (cpl:par | ||
+ | (exe: | ||
+ | (type moving-torso) | ||
+ | (joint-angle 0.3))) | ||
+ | (pp-plans:: | ||
+ | ;; Moving the robot near the table. | ||
+ | (exe: | ||
+ | (type going) | ||
+ | (target (desig:a location | ||
+ | (pose ? | ||
+ | | ||
+ | (multiple-value-bind (? | ||
+ | (find-object :bottle) | ||
+ | (setf ? | ||
+ | (pp-plans:: | ||
+ | ;; Moving the robot near the counter. | ||
+ | (let ((?nav-goal *base-pose-near-counter*)) | ||
+ | (exe: | ||
+ | (type going) | ||
+ | (target (desig:a location | ||
+ | (pose ? | ||
+ | |||
+ | (coe: | ||
+ | ;; Setting the object down on the counter | ||
+ | (let ((? | ||
+ | (exe: | ||
+ | (type placing) | ||
+ | (arm ? | ||
+ | | ||
+ | | ||
+ | (pose ? | ||
+ | (pp-plans:: | ||
+ | </ | ||
+ | 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: | ||
+ | [(PICK-PLACE PICK-UP) INFO] 1550504321.279: | ||
+ | [(GRASP-FAILURE) WARN] Failed to grasp from LEFT-SIDE using RIGHT arm | ||
+ | [(TRYING-NEW-GRASP) INFO] 1550504800.749: | ||
+ | [(PICK-PLACE PICK-UP) INFO] 1550504800.789: | ||
+ | [(PICK-PLACE PICK-UP) INFO] 1550504800.789: | ||
+ | [(GRASP-FAILURE) WARN] Failed to grasp from RIGHT-SIDE using RIGHT arm | ||
+ | [(TRYING-NEW-GRASP) INFO] 1550504801.577: | ||
+ | [(PICK-PLACE PICK-UP) INFO] 1550504801.601: | ||
+ | [(PICK-PLACE PICK-UP) INFO] 1550504801.602: | ||
+ | [(PICK-PLACE PICK-UP) INFO] 1550504801.939: | ||
+ | [(PICK-PLACE PICK-UP) INFO] 1550504801.973: | ||
+ | [(PICK-PLACE PICK-UP) INFO] 1550504801.974: | ||
+ | [(PICK-PLACE PLACE) INFO] 1550504802.356: | ||
+ | [(PICK-PLACE PLACE) INFO] 1550504802.508: | ||
+ | [(PICK-PLACE PLACE) INFO] 1550504802.619: | ||
+ | [(PICK-PLACE PLACE) INFO] 1550504802.655: | ||
+ | [(PICK-PLACE PLACE) INFO] 1550504802.660: | ||
+ | </ | ||
+ | {{: | ||
+ | |||
+ | The robot has once again succeeded in grasping the object. |