Manipulability measure
M = maniplty(R, Q, OPTIONS) [M,CI] = maniplty(R, Q, OPTIONS)
robot object
matrix or vector, joint configuration.
'key',value pair or 'key'
manipulability for transational motion only (default)
manipulability for rotational motion only
manipulability for all motions
D is a vector (1x6) with non-zero elements if the
use Yoshikawa algorithm (default)
use Asada algorithm
M = maniplty(R, Q, OPTIONS) is the manipulability index measure for the robot at the joint configuration Q. It indicates dexterity, that is, how isotropic the robot's motion is with respect to the 6 degrees of Cartesian motion. The measure is high when the manipulator is capable of equal motion in all directions and low when the manipulator is close to a singularity.
If Q is a matrix (MxN) then M (Mx1) is a vector of manipulability indices for each pose specified by a row of Q.
[M,CI] = R.maniplty(R, Q, OPTIONS) as above, but for the case of the Asada measure returns the Cartesian inertia matrix CI.
Two measures can be selected:
By default the measure includes rotational and translational dexterity, but this involves adding different units. It can be more useful to look at the translational and rotational manipulability separately.
[1] Analysis and control of robot manipulators with redundancy, T. Yoshikawa, Robotics Research: The First International Symposium (M. Brady and R. Paul, eds.), pp. 735-747, The MIT press, 1984.
[2] A geometrical representation of manipulator dynamics and its application to arm design, H. Asada, Journal of Dynamic Systems, Measurement, and Control, vol. 105, p. 131, 1983.