Main Content

manipulabilityIndex

Calculate manipulability index of robot at specified joint configuration

Since R2024b

    Description

    manipIndex = manipulabilityIndex(robot,configuration) calculates the manipulability index of the specified robot at the specified joint configuration. This syntax uses last rigid body in the robot model as the end effector.

    manipIndex = manipulabilityIndex(robot,configuration,eeName) specifies the rigid body to use as the end effector for manipulability calculations.

    example

    manipIndex = manipulabilityIndex(___,Name=Value) specifies options using one or more name-value arguments in addition to any combination of input arguments from previous syntaxes. For example, IndexType="asada" uses the Asada approach for manipulability calculations.

    Examples

    collapse all

    Load the robot model for the ABB IRB 120 manipulator, and use an analytical inverse kinematics solver to generate an IK solver for the robot.

    robot = loadrobot("abbIrb120",DataFormat="row");
    eeName = "tool0";
    aik = analyticalInverseKinematics(robot);
    generateIKFunction(aik,"robotIK");

    Use the IK solver to find joint configurations in which the end effector of the manipulator reaches the xyz-position (0.2, 0.5, 0.5). The solver finds multiple configurations that satisfy this condition.

    eePosition = [0.2 0.5 0.5];
    eePose = trvec2tform(eePosition);
    ikConfig = robotIK(eePose)
    ikConfig = 8×6
    
       -1.8214   -1.4863   -0.7791    1.7650    1.4114    0.6790
       -1.8214   -0.8824   -1.9070    1.6589    1.3359    1.2082
        1.3202    0.8824   -0.7791   -1.5972    1.3215    1.6774
        1.3202    1.4863   -1.9070   -1.4666    1.3424    1.1382
       -1.8214   -1.4863   -0.7791   -1.3766   -1.4114    3.8206
       -1.8214   -0.8824   -1.9070   -1.4827   -1.3359    4.3498
        1.3202    0.8824   -0.7791    1.5444   -1.3215   -1.4641
        1.3202    1.4863   -1.9070    1.6750   -1.3424    4.2798
    
    

    Calculate the manipulability index for each of the joint configuration solutions.

    mValues = manipulabilityIndex(robot,ikConfig,eeName)
    mValues = 8×1
    
        0.0228
        0.0225
        0.0224
        0.0225
        0.0228
        0.0225
        0.0224
        0.0225
    
    

    Find the highest manipulability index, and get the corresponding joint configuration.

    [~,argMax] = max(mValues);
    highManipConfig = ikConfig(argMax,:)
    highManipConfig = 1×6
    
       -1.8214   -1.4863   -0.7791   -1.3766   -1.4114    3.8206
    
    

    Input Arguments

    collapse all

    Robot model, specified as a rigidBodyTree object.

    Robot configuration, specified as an N-element vector, or an M-by-N matrix, where each row is a configuration. N is the number of nonfixed joints in the robot model and M is the number of joint configurations. You can generate a configuration using homeConfiguration(robot), randomConfiguration(robot), or by specifying your own joint positions as a vector.

    Name of the end effector, specified as a string scalar or character vector. A body with this name must be on the robot model specified by robot.

    By default, the last body of robot is the end effector.

    Data Types: char | string

    Name-Value Arguments

    Specify optional pairs of arguments as Name1=Value1,...,NameN=ValueN, where Name is the argument name and Value is the corresponding value. Name-value arguments must appear after other arguments, but the order of the pairs does not matter.

    Example: manipulabilityIndex(robot,config,IndexType="yoshikawa",MotionComponent="linear") specifies to use the Yoshikawa approach for manipulability calculations, and consider only linear motion.

    Manipulability index type to calculate, specified as one of these options:

    • "yoshikawa" — Use the volume of the velocity ellipsoid at each configuration as the measure of manipulability [1]. High Yoshikawa manipulability index values indicate that the robot has good dexterity and can move in multiple directions from the corresponding configurations. Low manipulability index values indicate that corresponding configurations are less dexterous and more susceptible to singularities.

    • "asada" — Use the geometric representation of the manipulator as the measure of manipulability [2]. A high Asada manipulability index indicates that a configuration is efficient for transmitting forces and velocities from the actuators to the end effector. Low Asada index values imply that the configuration is less efficient at force and velocity transmission, potentially hindering the ability of the robot to perform tasks requiring precise force application or rapid movements.

    • "inverse-condition" — Use the inverse of condition number of the robot's Jacobian matrix as the measure of manipulability [3]. High inverse condition index values indicate a low condition number, suggesting that the configuration is stable and capable of moving well in many directions, indicating uniform manipulability. Low inverse condition index values signify a high condition number, meaning the configuration is poorly conditioned, leading to sensitivity to input variations and potentially unstable or unpredictable movement, especially near singularities.

    Example: manipulabilityIndex(robot,config,IndexType="asada")

    Type of motion to consider for manipulability index calculation, specified as one of these options:

    • "combined" — Consider both linear and angular motions on the xyz-axes.

    • "linear" — Consider only linear motion along the xyz-axes.

    • "angular" — Consider only angular motion about the xyz-axes.

    • six-element vector of logical values — Consider motion components specified by a logical vector in the form [rx ry rz x y z]. Each element in the vector corresponds to a motion component along or about the xyz-axes, where a value of 0 (false) ignores the corresponding motion component, and 1 (true) considers the corresponding motion component for manipulability index calculation. For example, [0 0 1 1 1 0] specifies that the function only considers the z angular motion, along with the x and y linear motions, for the manipulability index calculation.

    Example: manipulabilityIndex(robot,config,MotionComponent="angular")

    Example: manipulabilityIndex(robot,config,MotionComponent=[1 1 0 0 0 1])

    Output Arguments

    collapse all

    Manipulability index, returned as a numeric scalar or M-element vector. M is the number of specified joint configurations.

    References

    [1] Yoshikawa, T. "Analysis and Control of Robot Manipulators with Redundancy." In Robotics Research: The First International Symposium, 735–47. Cambridge: MIT Press, 1984.

    [2] Asada, Haruhiko. “A Geometrical Representation of Manipulator Dynamics and Its Application to Arm Design.” Journal of Dynamic Systems, Measurement, and Control 105, no. 3, (September 1, 1983): 131–42. https://doi.org/10.1115/1.3140644.

    [3] Togai, Masaki. “An Application of the Singular Value Decomposition to Manipulability and Sensitivity of Industrial Robots.” SIAM Journal on Algebraic Discrete Methods 7, no. 2, (April 1986): 315–20. https://doi.org/10.1137/0607034.

    Extended Capabilities

    C/C++ Code Generation
    Generate C and C++ code using MATLAB® Coder™.

    Version History

    Introduced in R2024b