MATLAB File Help: HebiKinematics
HebiKinematics
  HebiKinematics provides basic kinematic methods for HEBI modules
 
    HebiKinematics loads HRDF files that describe the configuration of
    a robot and helps with calculating things like forward kinematics,
    inverse kinematics, Jacobians, as well as forces and torques to
    compensate for accelerations due to gravity or dynamic motions.
  
    More information and background on kinematics:
    http://docs.hebi.us/core_concepts.html#kinematics
 
    More information on the HEBI Robot Description Format (HRDF):
    http://docs.hebi.us/tools.html#robot-description-format
 
    This API currently only supports serial chains. If you are going to
    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 pose of the
    first body of the limb with respect to the chassis.
 
    HebiKinematics Methods (setup):
       kin = HebiKinematics('robot.hrdf') - where 'robot.hrdf' is the
                                            path to the file that
                                            describes the robot.
 
    HebiKinematics Methods (kinematics):
       getForwardKinematics  - calculates the pose of bodies in the 
                               kinematic chain, given a set of joint 
                               positions
       getInverseKinematics  - calculates the required joint positions to  
                               generate a desired end-effector pose
       getJacobian           - calculates the matrix that relates joint
                               velocities to body velocities
       getGravCompEfforts    - calculates the efforts that compensate
                               for gravitational accelerations, given
                               joint positions and gravity vector.
       getDynamicCompEfforts - calculates the efforts that compensate 
                               for dynamics of a desired motion, given
                               joint position/velocities/accelerations
       setBaseFrame          - set transform from world to first body
                               in the kinematic chain
       setPayload            - sets an additional mass at the end-effector
                               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
 
    HebiKinematics Methods (programmatic setup):
       addBody               - adds a body to the end of the chain.
                               THIS IS NO LONGER THE PREFERRED METHOD
                               OF DEFINING A ROBOT CONFIGURATION. It
                               is better to make and load an HRDF file.
                               
    Example
       % Load model from file (experimental support for hrdf v1.1)
       kin = HebiKinematics('robot.hrdf');
 
    Example
       % Calculate forward kinematics for some random joint positions
       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 joint  
  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