MATLAB File Help: HebiKinematics/getJacobian
HebiKinematics/getJacobian
  getJacobian calculates the matrix that relates input joint
  velocities to body velocities.
 
    This method calculates the partial derivatives of the
    kinematics equation, which relates the joint velocities to
    the linear and angular velocities of each body in the
    kinematic chain.
 
    More background on Jacobians and kinematics can be found at:
    http://docs.hebi.us/core_concepts.html#kinematics
 
    The Jacobian is returned as a [6 x numDoF x numBodies] set
    of matrices.  Rows 1:3 of the Jacobian correspond to linear
    velocities [m/s] along the X-Y-Z axes in the world frame,
    while rows 4:6 correspond to rotational velocities [rad/s]
    about the X-Y-Z axes in the world frame.
 
    'FrameType' Argument
        'OutputFrame'      calculates the transforms to the output
                           of each body (also: 'out', 'output')
 
        'CoMFrame'         calculates the transforms to the center
                           of mass of each body (also: 'com')
 
        'EndEffectorFrame' calculates the transform to only the
                           output frame of the last body, e.g.,
                           a gripper (also: 'endeffector')
 
    'Position' Argument
        A [1 x numDoF] vector that specifies the position
        of each degree of freedom. Rotational positions are
        specified in [rad].  Translational positions are
        specified in [m].
 
    'FixedFrame' Argument
        A number that specifies which rigid body of the Jacobian is 
        assumed to be fixed, and returns the Jacobian in this frame.  
        This parameter is optional, and the default if not specified is 
        the world frame, which would be the same as ['fixedframe', 0]. 
 
        This parameter uses negative indexing to specify the end-effector
        as -1 regardless of the number of links in kinenamitic chain.  
        Note that if you want the frame at the usual origin of the chain
        to be returned in the Jacobian, you will need to add a body there 
        in the HRDF file or kinematic definition code, as the base frame 
        of the chain is normally omitted from forward kinematics and 
        Jacobian calculations.
 
     Examples
        % End-Effector Jacobian using group feedback
        fbk = group.getNextFeedback();
        J = kin.getJacobian('endEffector', fbk.position);
 
        % Jacobian assuming the end-effector is fixed, using group 
        % feedback. For example, if the kinematic chain were a
        % leg and the end-effector (the foot) is fixed to the ground.
        fbk = group.getNextFeedback();
        J = kin.getJacobian('output', fbk.position, 'fixedframe', -1);
See also
Method Details
Access public
Sealed false
Static false