MATLAB File Help: HebiKinematics
HebiKinematics
  HebiKinematics provides basic kinematic methods for HEBI modules
 
    This Kinematics API helps with calculating forwards kinematics and
    inverse kinematics, Jacobians, as well as forces and torques to
    compensate for accelerations due to gravity or dynamic motions.
 
    Note that his API currently only supports serial chains. If you
    work with a robot that has multiple limbs, such as a hexapod, we
    recommend creating a cell array that contains a separate kinematic
    object for each limb. The base frames can be set to the location of
    the limb with respect to the chassis.
 
    HebiKinematics Methods (setup):
       addBody               -  adds a body to the end of the chain
       setBaseFrame          -  set transform from world to first body
 
    HebiKinematics Methods (kinematics):
       getForwardKinematics  -  calculates the configuration of bodies
       getJacobian           -  relates joint to body velocities
       getInverseKinematics  -  positions for a desired configuration
       getGravCompEfforts    -  compensates for gravitational accelerations
       getDynamicCompEfforts -  compensates for accelerations due to motions
       setPayload            -  sets a payload for effort compensation
 
    HebiKinematics Methods (information):
       getNumBodies          -  number of bodies
       getNumDoF             -  number of degrees of freedom
       getBodyMasses         -  a vector of all body masses [kg]
       getBodyInfo           -  a table of body related info
       getJointInfo          -  a table of joint related info
       getBaseFrame          -  get transform from world to first body
 
    Example
       % Setup a simple 3 dof arm made of X5 modules
       kin = HebiKinematics();
       kin.addBody('X5-9');
       kin.addBody('X5-LightBracket', 'mounting', 'right');
       kin.addBody('X5-4');
       kin.addBody('X5-Link', 'extension', 0.350, 'twist', pi/2);
       kin.addBody('X5-1');
 
    Example
       % Calculate forward kinematics with random inputs
       positions = rand(kin.getNumDoF, 1);
       frames = kin.getForwardKinematics('output', positions);
See also
Class Details
Sealed true
Construct on load false
Method Summary
  addBody adds a body to the end of the chain 
  getBaseFrame returns the relationship between the world 
  getBodyInfo returns a table of body info 
  getBodyMasses returns a vector of the masses of all links 
  getDynamicCompEfforts calculates joint efforts that  
  getFK is an abbreviation for getForwardKinematics 
  getForwardKinematics (getFK) calculates the poses of all the 
  getForwardKinematicsEndEffector is a convenience wrapper 
  getGravCompEfforts calculates joint efforts that compensate  
  getIK is an abbreviation for getInverseKinematics 
  getInverseKinematics (getIK) calculates positions for a  
  getJacobian calculates the matrix that relates input DoF  
  getJacobianEndEffector is a convenience wrapper 
  getJointInfo returns a table of joint info 
  getNumBodies returns the total number of bodies 
  getNumDoF returns the number of actuated degrees of freedom 
  setBaseFrame sets the relationship between the world and the 
  setPayload sets a payload used for effort compensation