HEBI C++ API  1.0.0-rc1
hebi::kinematics::Kinematics Class Referencefinal

Represents a kinematic chain or tree of bodies (links and joints and modules). More...

#include <kinematics.hpp>

Public Member Functions

 Kinematics ()
 Creates a kinematics object with no bodies and an identity base frame. More...
 
virtual ~Kinematics () noexcept
 Destructor cleans up kinematics object, including all managed bodies. More...
 
void setBaseFrame (const Eigen::Matrix4f &base_frame)
 Set the transform from a world coordinate system to the input of the root kinematic body in this kinematics object. Defaults to an identity 4x4 matrix. More...
 
Eigen::Matrix4f getBaseFrame () const
 Returns the transform from the world coordinate system to the root kinematic body, as set by the setBaseFrame function. More...
 
size_t getFrameCount (HebiFrameType frame_type) const
 Return the number of frames in the forward kinematics. More...
 
size_t getDoFCount () const
 Returns the number of settable degrees of freedom in the kinematic tree. (This is equal to the number of actuators added). More...
 
bool addBody (std::shared_ptr< KinematicBody > new_body)
 Add a body to a parent body connected to a kinematic tree object. More...
 
void getForwardKinematics (HebiFrameType, const Eigen::VectorXd &positions, Matrix4fVector &frames) const
 Generates the forward kinematics for the given kinematic tree. More...
 
void getFK (HebiFrameType, const Eigen::VectorXd &positions, Matrix4fVector &frames) const
 Generates the forward kinematics for the given kinematic tree. More...
 
void getEndEffector (HebiFrameType, const Eigen::VectorXd &positions, Eigen::Matrix4f &transform) const
 Generates the forward kinematics to the end effector (leaf node) frame(s). More...
 
void solveInverseKinematics (const Eigen::Vector3f &target_xyz, const Eigen::VectorXd &positions, Eigen::VectorXd &result) const
 Solves for an inverse kinematics solution that moves the end effector to a given point. More...
 
void solveIK (const Eigen::Vector3f &target_xyz, const Eigen::VectorXd &initial_positions, Eigen::VectorXd &result) const
 Solves for an inverse kinematics solution that moves the end effector to a given point. More...
 
void getJacobians (HebiFrameType, const Eigen::VectorXd &positions, MatrixXfVector &jacobians) const
 Generates the Jacobian for each frame in the given kinematic tree. More...
 
void getJ (HebiFrameType, const Eigen::VectorXd &positions, MatrixXfVector &jacobians) const
 Generates the Jacobian for each frame in the given kinematic tree. More...
 
void getJacobianEndEffector (HebiFrameType, const Eigen::VectorXd &positions, Eigen::MatrixXf &jacobian) const
 Generates the Jacobian for the end effector (leaf node) frames(s). More...
 
void getJEndEffector (HebiFrameType, const Eigen::VectorXd &positions, Eigen::MatrixXf &jacobian) const
 Generates the Jacobian for the end effector (leaf node) frames(s). More...
 

Detailed Description

Represents a kinematic chain or tree of bodies (links and joints and modules).

(Currently, only kinematic chains are fully supported).

Constructor & Destructor Documentation

hebi::kinematics::Kinematics::Kinematics ( )

Creates a kinematics object with no bodies and an identity base frame.

hebi::kinematics::Kinematics::~Kinematics ( )
virtualnoexcept

Destructor cleans up kinematics object, including all managed bodies.

Member Function Documentation

void hebi::kinematics::Kinematics::setBaseFrame ( const Eigen::Matrix4f &  base_frame)

Set the transform from a world coordinate system to the input of the root kinematic body in this kinematics object. Defaults to an identity 4x4 matrix.

The world coordinate system is used for all position, vector, and transformation matrix parameters in the member functions.

Parameters
base_frameThe 4x4 homogeneous transform from the world frame to the root kinematic body frame.
Eigen::Matrix4f hebi::kinematics::Kinematics::getBaseFrame ( ) const

Returns the transform from the world coordinate system to the root kinematic body, as set by the setBaseFrame function.

size_t hebi::kinematics::Kinematics::getFrameCount ( HebiFrameType  frame_type) const

Return the number of frames in the forward kinematics.

Note that this depends on the type of frame requested – for center of mass frames, there is one per added body; for output frames, there is one per output per body.

Parameters
frame_typeWhich type of frame to consider – see HebiFrameType enum.
size_t hebi::kinematics::Kinematics::getDoFCount ( ) const

Returns the number of settable degrees of freedom in the kinematic tree. (This is equal to the number of actuators added).

bool hebi::kinematics::Kinematics::addBody ( std::shared_ptr< KinematicBody new_body)

Add a body to a parent body connected to a kinematic tree object.

After the addition, the kinematics object manages the resources of the added body.

Parameters
new_bodyThe kinematic body which is added to the tree.
Returns
true if successful, false if unable to add the body.
void hebi::kinematics::Kinematics::getForwardKinematics ( HebiFrameType  frame_type,
const Eigen::VectorXd &  positions,
Matrix4fVector frames 
) const

Generates the forward kinematics for the given kinematic tree.

See getFK for details.

void hebi::kinematics::Kinematics::getFK ( HebiFrameType  frame_type,
const Eigen::VectorXd &  positions,
Matrix4fVector frames 
) const

Generates the forward kinematics for the given kinematic tree.

The order of the returned frames is in a depth-first tree. As an example, assume a body A has one output, to which body B is connected to. Body B has two outputs; actuator C is attached to the first output and actuator E is attached to the second output. Body D is attached to the only output of actuator C:

(BASE) A - B(1) - C - D (2) | E

For center of mass frames, the returned frames would be A-B-C-D-E.

For output frames, the returned frames would be A-B(1)-C-D-B(2)-E.

Parameters
frame_typeWhich type of frame to consider – see HebiFrameType enum.
positionsA vector of joint positions/angles (in SI units of meters or radians) equal in length to the number of DoFs of the kinematic tree.
framesAn array of 4x4 transforms; this is resized as necessary in the function and filled in with the 4x4 homogeneous transform of each frame. Note that the number of frames depends on the frame type.
void hebi::kinematics::Kinematics::getEndEffector ( HebiFrameType  frame_type,
const Eigen::VectorXd &  positions,
Eigen::Matrix4f &  transform 
) const

Generates the forward kinematics to the end effector (leaf node) frame(s).

Note – for center of mass frames, this is one per leaf node; for output frames, this is one per output per leaf node, in depth first order.

This overload is for kinematic chains that only have a single leaf node frame.

(Currently, kinematic trees are not fully supported – only kinematic chains – and so there are not other overloads for this function).

Parameters
frame_typeWhich type of frame to consider – see HebiFrameType enum.
positionsA vector of joint positions/angles (in SI units of meters or radians) equal in length to the number of DoFs of the kinematic tree.
transformA 4x4 transform that is resized as necessary in the function and filled in with the homogeneous transform to the end effector frame.
void hebi::kinematics::Kinematics::solveInverseKinematics ( const Eigen::Vector3f &  target_xyz,
const Eigen::VectorXd &  positions,
Eigen::VectorXd &  result 
) const

Solves for an inverse kinematics solution that moves the end effector to a given point.

See solveIK for details.

void hebi::kinematics::Kinematics::solveIK ( const Eigen::Vector3f &  target_xyz,
const Eigen::VectorXd &  initial_positions,
Eigen::VectorXd &  result 
) const

Solves for an inverse kinematics solution that moves the end effector to a given point.

WARNING: this function interface is not yet stable; future revisions will likely change the method for adding objectives and returning failure/status information about the solution.

Parameters
target_xyzA length 3 vector of the desired end effector location.
initial_positionsThe seed positions/angles (in SI units of meters or radians) to start the IK search from; equal in length to the number of DoFs of the kinematic tree.
resultA vector equal in length to the number of DoFs of the kinematic tree; this will be filled in with the IK solution (in SI units of meters or radians), and resized as necessary.
void hebi::kinematics::Kinematics::getJacobians ( HebiFrameType  frame_type,
const Eigen::VectorXd &  positions,
MatrixXfVector jacobians 
) const

Generates the Jacobian for each frame in the given kinematic tree.

See getJ for details.

void hebi::kinematics::Kinematics::getJ ( HebiFrameType  frame_type,
const Eigen::VectorXd &  positions,
MatrixXfVector jacobians 
) const

Generates the Jacobian for each frame in the given kinematic tree.

Parameters
frame_typeWhich type of frame to consider – see HebiFrameType enum.
positionsA vector of joint positions/angles (in SI units of meters or radians) equal in length to the number of DoFs of the kinematic tree.
jacobiansA vector (length equal to the number of frames) of matrices; each matrix is a (6 x number of dofs) jacobian matrix for the corresponding frame of reference on the robot. This vector is resized as necessary inside this function.
void hebi::kinematics::Kinematics::getJacobianEndEffector ( HebiFrameType  frame_type,
const Eigen::VectorXd &  positions,
Eigen::MatrixXf &  jacobian 
) const

Generates the Jacobian for the end effector (leaf node) frames(s).

See getJEndEffector for details.

void hebi::kinematics::Kinematics::getJEndEffector ( HebiFrameType  frame_type,
const Eigen::VectorXd &  positions,
Eigen::MatrixXf &  jacobian 
) const

Generates the Jacobian for the end effector (leaf node) frames(s).

Note – for center of mass frames, this is one per leaf node; for output frames, this is one per output per leaf node, in depth first order.

This overload is for kinematic chains that only have a single leaf node frame.

(Currently, kinematic trees are not fully supported – only kinematic chains – and so there are not other overloads for this function).

Parameters
frame_typeWhich type of frame to consider – see HebiFrameType enum.
positionsA vector of joint positions/angles (in SI units of meters or radians) equal in length to the number of DoFs of the kinematic tree.
jacobianA (6 x number of dofs) jacobian matrix for the corresponding end effector frame of reference on the robot. This vector is resized as necessary inside this function.

The documentation for this class was generated from the following files: