MATLAB File Help: HebiKinematics/getForwardKinematics
  getForwardKinematics (getFK) calculates the poses of all the
  bodies in the configured kinematic chain, setup by using 
  HebiKinematics() and addBody()
    This method computes the poses of the chain of bodies in 
    the world frame, using specified values for the joint 
    parameters and specified base frame.
    Poses are returned as a set of [4 x 4 x numBodies] 
    homogeneous transforms, specified in the world frame of the
    kinematic configuration.  Units of XYZ translation are in 
    'FrameType' Argument
       'OutputFrame'      calculates the transforms to the output
                          of each body ('out')
                          Size: [4 x 4 x numBodies]
       'CoMFrame'         calculates the transforms to the center
                          of mass of each body
                          Size: [4 x 4 x numBodies]
       'EndEffectorFrame' calculates the transform to only the
                          output frame of the last body in the
                          chain (e.g. a gripper or tool tip)
                          Size: [4 x 4]
    'Position' Argument
       A [1 x numDoF] vector that specifies the position of 
       each degree of freedom.  Rotational positions are 
       specified in [rad].  Linear positions are in [m].
       % Forward kinematics for all the bodies in an arm
       % using group feedback.
       fbk = group.getNextFeedback();
       frames = kin.getFK('output', fbk.position);
       % Forward kinematics for just the endeffector of an arm
       % using commanded positions.
       fbk = group.getNextFeedback();
       frames = kin.getFK('endeffector', fbk.positionCmd);
See also
Method Details
Access public
Sealed false
Static false