Skip to content
Peter Corke edited this page Jul 21, 2015 · 3 revisions

Frequently asked questions

[TOC]

I can't unpack the zip file

If the zip archive won't unpack and/or reports errors, it is most likely corrupt. This can occur if you have a very slow internet connection, and the transfer times out. Try to download the file again.

What is a MEX-file?

MEX-files are written in C or C++ and compiled into a binary module that is dynamically linked by MATLAB at run time. MEX-files can be much faster than the equivalent M-files but the disadvantage is that they are not portable, they must be compiled for the particular platform that you are using.

MEX-files have names that are of the form:

  • function.mexw32 for a 32-bit Windows platform
  • function.mexglx for a GNU-Linux platform (implicitly x86 based)
  • function.mexmaci64 for an Apple Mac with a 64-bit Intel processor

To learn more about MEX files and how to create them have a look at this online documentation. For 32-bit Windows MATLAB comes with a simple compiler called lcc but for 64-bit Windows you need to provide your own compiler.

I distribute MEX-files for 64-bit Mac, Linux and 32-bit Windows only.

How do I build the MEX files?

For either toolbox change into its mex folder, that is rvctools/robot/mex or rvctools/vision/mex and execute

>> make

which will invoke the appropriate compiler. If there are errors then either the mex compiler is not setup correctly, so have a look at the relevant Mathworks documentation.

If you're a command line kind of person just cd into the mex directory and run make from the command line. This assumes that the mex compiler is in your path, it's located in the bin subdirectory of your MATLAB install.

% mex -v

shows current mex settings,

% mex -help

shows various options, and

% mex -setup

allows configuration. On a *nix or MacOS system these settings are kept in the top-level hidden directory ~/.matlab.

MEX file won't compile

If you get errors like

>> make
** building MEX files for MVTB
closest.c: En la función ‘mexFunction’:
closest.c:98:25: error: expected expression before ‘/’ token
closest.c:102:13: error: expected expression before ‘/’ token
closest.c:108:21: error: expected expression before ‘/’ token
closest.c:159:25: error: expected expression before ‘/’ token
closest.c:163:13: error: expected expression before ‘/’ token
closest.c:169:21: error: expected expression before ‘/’ token

it's because your compiler isn't recognizing the C++ style // comments. Change the line in the makefile from

CFLAGS="-std=gnu99"

to

CFLAGS=-std=c99

This tells the compiler to use C99 standard syntax which allows the C++ style comments.

Compiling MEX files for Windows

If you get errors like

No supported SDK or compiler was found on this computer. 
For a list of supported compilers, see  
http://www.mathworks.com/support/compilers/R2013a/win64.html  
 
Error using mex (line 206)
Unable to complete successfully.

then you don't have a C compiler setup properly.

Follow the instructions here.

ilabel.m is just comments

There is no mechanism for a binary MEX file to have documentation comments, these are the block of comments at the top of each MATLAB M-file that is given (without the % characters) in response to the help command.

The MATLAB convention is that a MEX-file has a corresponding M-file which contains the help documentation for that file. If you don't have the MEX-file for your platform then MATLAB will attempt to execute the documentation file (with the .m extension) which it thinks is a script not a function, and this leads to the error message.

The specifed superclass 'NNNNN' is invalid or contains a parse error

where NNNNN is the name of some class. The problem is that the file defining the superclass is not in fact a class definition. Typically this occurs if you create a function with the same name as the superclass NNNNN. The easiest way to test for this is

>> which NNNNN

which should show a file within the RVC install directory. If not, you have a name clash, so remove that file or move it to some place not on your MATLAB search path.

Function not defined

Undefined function 'vgg_XXXXX' for input arguments of type 'double'

Download the contributed code zip file from the MVTB download area.

Undefined function 'Open Surf' for input arguments of type 'struct'

Please install contrib2. zip from the MVTB download page.

Errors using isift or isurf

Please install contrib2. zip from the MVTB download page.

Errors using igraphseg, imser, vl_kmeans, EPnP

Please install contrib. zip from the MVTB download page.

Errors using isift or isurf

Please install contrib2. zip from the MVTB download page.

Python version of the toolbox

The Python version of the toolbox is currently not maintained and advice is that it's broken. It implemented a subset of RTB, specifically those functions that deal with arm-type robots.

Given the power of Python, it price (free) and great numeric (numpy, scipy) support, and great 2D and 3D graphics (matplotlib) and interactive environment (ipython) it's a logical replacement for MATLAB.

So Python makes a lot of sense but to get this moving again would require some tangible user interest and even better willingness to help.

You can get the code as it stands from google.code the SVN repository.

Will the toolbox work with my version of MATLAB?

The Toolbox should work with all version of MATLAB from 2010a onwards. I'm developing with 2014a right now. The older version of MATLAB you use the more problems you will likely encounter, and the problem is more acute with Simulink. A list of MATLAB versions is here.

Will the toolboxes work with Octave?

A subset of the RTB will work with Octave, specifically those functions that deal with arm-type robots. To enable this functionality go into the folder rvctools/Octave and follow the instructions in the README.txt file.

There are a lot of minor differences between MATLAB and Octave, though less than there used to be. The big stumbling block right now is that Octave handles classes in a very different way (actually the way that MATLAB used to). The Octave folk are working on adding MATLAB-style classes but it's not there yet. Once that happens I suspect a broader port of RTB and MVTB will be possible.

rne() is really slow

Yes it is! It might be that you are using the M-file rather than the MEX-file version.
To check use the which command

>> which rne
.../rvc/robot/@SerialLink/rne.mexmaci64  % SerialLink method

which in this case suggests that the MEX-file is being used. Sorry, this is as fast as you can go.

However if the result is like

>> which rne
.../rvc/robot/@SerialLink/rne.m  % SerialLink method

then you are currently using the m-file and there is scope to improve.
Change (cd) into the folder rvctools/robot/mex and follow the instructions in the README.txt file. If it's all working well, the first time you run rne() it will display a banner indicating the fast MEX-file version is being used, for example

>> p560.rne(qz,qz,qz)
Fast RNE: (c) Peter Corke 2002-2012

ans =

         0   37.4837    0.2489         0         0         0

If you have a MEX-file in the @SerialLink folder but it's not being seen then try

>> clear functions

to clear MATLAB's cache.

Slow RNE with RTB9.9

The mechanism for handling MEX files has changed with this release. By default RTB looks for a MEX file and if it's found it will be indicated when the SerialLink object is displayed, in parentheses above the DH parameter table

>> mdl_puma560
>> p560
 
p560 = 
 
Puma 560 (6 axis, RRRRRR, stdDH, fastRNE)            
 viscous friction; params of 8/95;                   
+---+-----------+-----------+-----------+-----------+
| j |     theta |         d |         a |     alpha |
+---+-----------+-----------+-----------+-----------+
|  1|         q1|          0|          0|      1.571|
|  2|         q2|          0|     0.4318|          0|
|  3|         q3|       0.15|     0.0203|     -1.571|
|  4|         q4|     0.4318|          0|      1.571|
|  5|         q5|          0|          0|     -1.571|
|  6|         q6|          0|          0|          0|
+---+-----------+-----------+-----------+-----------+
                                                     
grav =    0  base = 1  0  0  0   tool =  1  0  0  0  
          0         0  1  0  0           0  1  0  0  
       9.81         0  0  1  0           0  0  1  0  
                    0  0  0  1           0  0  0  1  

Note fastRNE in this example.

If this flag is not set, then RTB couldn't find the MEX file, use the instructions above to build it.

If you really don't want to use the MEX file you have a couple of options

  1. use the 'nofast' option when you create the SerialLink object
  2. change the flag in the SerialLink object
>> p560.fast=false
 
p560 = 
 
Puma 560 (6 axis, RRRRRR, stdDH, slowRNE)            
 viscous friction; params of 8/95;                   
+---+-----------+-----------+-----------+-----------+
| j |     theta |         d |         a |     alpha |
+---+-----------+-----------+-----------+-----------+
|  1|         q1|          0|          0|      1.571|
|  2|         q2|          0|     0.4318|          0|
|  3|         q3|       0.15|     0.0203|     -1.571|
|  4|         q4|     0.4318|          0|      1.571|
|  5|         q5|          0|          0|     -1.571|
|  6|         q6|          0|          0|          0|
+---+-----------+-----------+-----------+-----------+
                                                     
grav =    0  base = 1  0  0  0   tool =  1  0  0  0  
          0         0  1  0  0           0  1  0  0  
       9.81         0  0  1  0           0  0  1  0  
                    0  0  0  1           0  0  0  1  

My robot arm dynamics simulation in Simulink is really slow

There are two common causes of this:

  1. You are not using the MEX version of RNE, see above.
  2. You have non-linear friction, specifically Coulomb friction in your model. This is a very harsh non-linearity and the integrator in Simulink adopts very small step sizes to cope with it.

The default Puma 560 model includes Coulomb friction. You can make a friction free version of that robot model by

>> p560_ff = p560.nofriction();

The viscous (linear) friction is retained.

How does the gear ratio work?

The torque model is perhaps not ideal, it's kind of evolved. I can't vouch for whether the Scilab port is the same or not.

The basis of all dynamics code is the RNE function which gives the torque required to achieve a particular qd and qdd for a certain q. All quantities are referred to the link/load. This torque includes link dynamic effects (inertia, coriolis, gravity) as well as motor inertia, motor viscous and Coloumb friction (given in motor frame but transferred according to gear ratio).

Bottom line:

  • torques are always link/load referenced
  • q and its derivatives are link/load referernced
  • frictions and motor inertia are motor referenced.

Torque/force components

The function rne() gives the torque required to achieve a particular qdd for a certain value of q and qd, ie. if you apply that torque at that joint angle and speed you will achieve the acceleration.

The toolbox also allows you to compute torque components:

  • inertial torque is
 I = robot.accel(q) ** qdd
  • Coriolis/centripetal torque is
C = robot.coriolis(q, qd) ** qd'
  • gravity torque is
G = robot.gravload(q)
  • friction torque is
 F = robot.friction(qd)

The total torque balance is

 I+C+G-F = tau

and note the negative sign on friction.

I'm having problems with inverse kinematics

Inverse kinematics is probably one of the troublesome areas for those starting out with RTB. It's really important to understand the fundamentals so check out a textbook if this topic is unfamiliar to you, for example Robotics, Vision & Control (chaps 7 and 8.4), Spong etal, or Siciliano etal.

ikine6s()

If your robot has 6 links and a spherical wrist then then the ikine6s() might be appropriate. To test whether your robot has a spherical wrist

>> p560.isspherical

ans =

     1

which in this case is true, the Puma 560 does indeed have a spherical wrist. The solution in ikine6s() is based on the paper by Paul & Zhang and is quite specific to the Puma 560 kinematics. Other solutions for an anthropomorphic arm manipulator are included in the books by Spong etal and Siciliano etal. The Paul & Zhang solution assumes that the upper and lower arm lengths are given by the DH parameters a2 and d4, whereas Spong and Siciliano assume these are the parameters a2 and a3.

The Puma model is complicated because the shoulder and wrist are offset from the waist rotation axis (by different amounts) which means it can have the lefty and righty configurations. This complexity is not included in the Spong or Siciliano solutions.

Bottom line to use ikine6s() the kinematic model must be Puma-like, with the upper and lower arm lengths given by a2 and d4 and the elbow having a twist (alpha) of -90deg.

ikine()

This method provides a numerical solution and has several advantages:

  • the robot can have an arbitrary number of axes, including under- and over-actuated
  • the robot can be at a singularity

The disadvantages are that it is an iterative algorithm which means that it can be slow and may not converge, and you cannot control which configuration.

Some tips to make it work well:

  • try to choose a good initial set of joint angles, that is, as close as possible to the desired solution
  • if the initial joint angles result in a singularity the search will not converge quickly. This is not catastrophic but something to be aware of.
  • the option 'pinv' often leads to faster convergence. Without this option the operation is as described in Robotics, Vision & Control section 8.4, but the pseudo-inverse approach is faster.

If your robot is Puma-like you are much better off using the ikine6s() method.

Can the Toolbox handle parallel manipulators?

No, it cannot.

Can I perform symbolic calculations?

Yes. For example:

>> syms r p y
>> rpy2r(r, p, y)
 
ans =
 
[                        cos(p)*cos(y),                       -cos(p)*sin(y),         sin(p)]
[ cos(r)*sin(y) + cos(y)*sin(p)*sin(r), cos(r)*cos(y) - sin(p)*sin(r)*sin(y), -cos(p)*sin(r)]
[ sin(r)*sin(y) - cos(r)*cos(y)*sin(p), cos(y)*sin(r) + cos(r)*sin(p)*sin(y),  cos(p)*cos(r)]
 

For a robot manipulator

>> mdl_twolink
>> syms q1 q2
>> twolink.fkine([q2](q1))
 
ans =
 
[ cos(q1 + q2), -sin(q1 + q2), 0, cos(q1 + q2) + cos(q1)]
[ sin(q1 + q2),  cos(q1 + q2), 0, sin(q1 + q2) + sin(q1)]
[            0,             0, 1,                      0]
[            0,             0, 0,                      1]

Other functions like rne(), inertia(), gravload() andcoriolis() work as well however they require that you are using the MATLAB version of rne() not the MEX version.
To check use the which command

>> which rne
.../rvc/robot/@SerialLink/rne.m  % SerialLink method

and if the return result is the m-file all is good. If the result is a MEX file, then remove it or temporarily move it aside.

How do I get started with the symbolics and code generation functionality?

An example to get started with symbolics and generation of m-code as well as real-time capable Simulink blocks is given in rtsymcgendemo.m. To run the demo type the following on the command line:

>> rtsymcgendemo

or start it from the Robotics Toolbox demos in the help browser.

What code can be generated using the code generator module?

By default the code generation module produces robot specific and ready to use m-functions as well as Simulink blocks. The Simulink blocks are real-time compatible. The automated generation of robot specific C-code and C-MEX functions is a new feature of release 9.9.

plot doesn't work for robot with prismatic joint(s)

The plot() method uses a simple heuristic to figure out how big to make the axes that can hold the robot for every joint angle configuration. For a prismatic joint this fails because there is no knowledge of the minimum and maximum extension of the joint(s).

The workaround is that you have to provide the information about the size of the workspace, using the 'workspace' option.

Documentation about the Toolboxes

The RVC book and the online documentation are the definitive sources of information about usage. Online documentation includes:

  • help information available from inside MATLAB
>> help tr2eul
  • documentation information from inside MATLAB, with more formatting and cross linking
>> doc tr2eul
  • the online HTML documentation
  • the 200 something page PDF manual available as rvctools/robot/robot.pdf or rvctools/vision/vision.pdf

All of this documentation comes from the one source, the comments at the beginning of each m-file. They are written in a very simple markup language inspired by reSt and pydoc. A bunch of Python scripts turn that raw information into HTML and PDF format documentation. This means that the documentation is fairly dry and concise. More explanation with figures and examples is provided in the RVC book.

Citing the Toolbox

Please cite the RVC book if you want to acknowledge the Toolboxes in your work:

P. I. Corke, Robotics, Vision & Control: Fundamental Algorithms in MATLAB. Springer, 2011. ISBN 978-3-642 20143-1.

@book{Corke11a,
	Author = {Peter I. Corke},
	Date-Added = {2011-01-12 08:19:32 +1000},
	Date-Modified = {2012-07-29 20:07:27 +1000},
	Note = {ISBN 978-3-642-20143-1  <a href="javascript:" cref="CitaviPicker978-3-642-20143-1"><img style="border: 0px none;height: 16px;width: 16px;display: inline;" src="data:image/png;base64,iVBORw0KGgoAAAANSUhEUgAAABAAAAAQCAYAAAAf8/9hAAAAGXRFWHRTb2Z0d2FyZQBBZG9iZSBJbWFnZVJlYWR5ccllPAAAAsZJREFUeNpkU11IFVEQ/s7u5k/d0jL603wKLBMDpRuIFEQ+BkVGGUgEReBLRSEa+BD0EgVJP74kCElppVbqQxAUFBgJUiISUaQ+iGB2Re/evXd/zplmz+rtoYU55+yZMzPffDMjEi1Xd8GyOlVy+ZDKpAGlQOBPRKLP/JEQLOFBQaZs+LMzb9z5+Sb8ab782f02SUqprEgptQSBJD8IyPMDcj2fXNejTMYjJ+3S3MALGtm7Y8RSi4nqNWV7okgrC5Feo53oP+EYsA7WYVlR3JJ2yowwEvzxr3DfvQVME7nH6yG2l0AxXOfZE7gT4zB3lyP/7HmQYSDgVF2CaYGkjhRMTyF5/Roo7bBRCk5PNzY8H4Ld0Y4Un1UY+XU/0pMTKLh1j1EoKObEiEhi5WIia6wcB/7Cbzh9vQj4XhuzSH6ZGnoFb24WTJEm2QgXTglmZRVyLzTBKCsHFRVBSQn/10+svdKK3NONMCoqQTl52ok3Mw2ppK6KEaWvKUNOfQNind1Yd+eBhkgFGyFKShBru4nC3kHkHDsBFRoUbmIEMkIQellllrjGxLtaWtKQzX1V+l7K6D5YTgJbt0HsLIUMVIRAN4h2oPRj7gQ4gwNcgWJYh+sYqtK6IJlE+tNH5J08w2kIXYXQ1gpJ1HBXiMp8eA9n+CXWd3SBuEjaKesTbc2gzVuQ13BOw9cI2NbSKYQw+ZHz9DFSD+8idvs+zHgNE8lta9tItFxCYCdR2P4IintAcQW4SzUHHIK9hdFdF/6P74h190EUl2ZTcr6MwqiOo+BUIxMospx4jCIk1JKpJFckMKVhIb/1RgQ5jBw65UfWgVoY+2vAY6HTDOvv+h4cRuZzF1rezNTYQn9v3DhyVCsjYxXt6t9ZV4f1vgzgZDJIDPcwB2JUjFUU71pU1GUrqvX02FJ2nDU/QkTznP1fHXHBQ4OLfwUYALhaDRT0WgkEAAAAAElFTkSuQmCC" title='Titel anhand dieser ISBN in Citavi-Projekt übernehmen'/></a> },
	Publisher = {Springer},
	Title = {Robotics, Vision \& Control: Fundamental Algorithms in {MATLAB}},
	Year = {2011}}

A robotics toolbox for MATLAB (1996)

This paper was published in 1996 in the IEEE Robotics & Automation magazine. It provided a tutorial approach to solving arm robot problems using v4 of the toolbox. The names and syntax have changed dramatically since then, so if you try those examples with the current toolbox you will have problems.

Please consider this article an historic artefact not a reference. The RVC book and the online documentation are the definitive sources of information about usage.

Maniplty() gives a different answer to the book

The value returned for the example on page 180 of the RVC book is different to what RTB returns. This is a change to the default argument for the function maniplty().

Manipulability has two components: rotational and translational. Rotation has units of radians, ie. numbers in the range 0-3, whereas translation has numbers in the range that depends on the size of the robot and the units you use, they might be very big numbers in the range 0-1000 (in mm) or small 0-0.5 (in m). So it makes no sense to add them which is what maniplty() used to do. Now the default is to return manipulability for just the translational motion

>> p560.maniplty(qn, 'yoshikawa')
ans =
    0.1112

not 0.0786 as per the book.

You can also specify explicitly the translational manipulability

>> p560.maniplty(qn, 'yoshikawa', 'T')
ans =
    0.1112

or you can ask for the rotational manipulability, how easily the tool orientation can change

>> p560.maniplty(qn, 'yoshikawa', 'R')
ans =
    2.4495

or the old behaviour

>> p560.maniplty(qn, 'yoshikawa', 'all')
ans =
    0.0786

What is MVTB contributed code?

A small number of MVTB functions depend on third party code which is included in contrib. zip or contrib2.zip. These zip files contain snapshots of these code projects that I know work with MVTB.

Since I didn't author these files, and they have their own licence conditions, the cleanest approach is to distribute as separate zip files. In some cases I provide wrappers within MVTB to make these packages consistent in look and feel with the rest of MVTB. Please note and respect the licence conditions associated with these packages.

contrib.zip supports:

  • igraphseg
  • imser
  • vl_kmeans, for bag of words example, Sec 14.7
  • EPnP, for the CentralCamera.estpose() method, Sec 11.2.3

contrib2.zip supports:

  • isift
  • isurf

How to plot 3D solid models of robots?

This is new capability that comes with RTB 9.9, or available now from the SVN repository. To use this you will need ASCII STL models of the links of your robot, named link0.stl, link1.stl and so on. A great source of such models is ARTE.

How to configure ARTE with RTB?

  1. Download ARTE: A ROBOTICS TOOLBOX FOR EDUCATION from here.
  2. unzip it
  3. move the ARTE folder into rvctools/contrib/arte, ie. if it was in a folder called arte3.2.3 change it to just plain arte.
  4. create an empty file called arte.m in that folder. RTB uses this to automatically determine where ARTE is installed.
  5. rerun startup_rvc and the banner should now list ARTE

Within the arte folder, the solid models live in a well organised hierarchy: arte/robots/MANUF/NAME/link*.stl. To tell RTB where to find the particular model, you need to update a property of the SerialLink object. Say your SerialLink robot object is called arm, then

arm.model3d = 'MANUF/NAME'

where MANUF and NAME describe the model in the ARTE hierarchy.

Clone this wiki locally