HEBI C++ API  3.4.0
hebi::robot_model::RobotModel Class Referencefinal

Represents a chain or tree of robot elements (rigid bodies and joints). More...

#include <robot_model.hpp>

Public Types

using ActuatorType = robot_model::ActuatorType
 
using BracketType = robot_model::BracketType
 
using LinkType = robot_model::LinkType
 

Public Member Functions

 RobotModel ()
 Creates a robot model object with no bodies and an identity base frame. More...
 
 ~RobotModel () noexcept
 Destructor cleans up robot model object, including all managed elements. More...
 
void setBaseFrame (const Eigen::Matrix4d &base_frame)
 Set the transform from a world coordinate system to the input of the root element in this robot model object. Defaults to an identity 4x4 matrix. More...
 
Eigen::Matrix4d 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 (FrameType frame_type) const
 Return the number of frames in the forward kinematics. 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 addRigidBody (const Eigen::Matrix4d &com, const Eigen::VectorXd &inertia, double mass, const Eigen::Matrix4d &output)
 Adds a rigid body with the specified properties to the robot model. More...
 
bool addJoint (JointType joint_type)
 Adds a degree of freedom about the specified axis. More...
 
bool addJoint (HebiJointType joint_type)
 Adds a degree of freedom about the specified axis. More...
 
bool addActuator (robot_model::ActuatorType actuator_type)
 Add an element to the robot model with the kinematics/dynamics of an X5 actuator. More...
 
bool addLink (robot_model::LinkType link_type, double extension, double twist, LinkInputType input_type=LinkInputType::RightAngle, LinkOutputType output_type=LinkOutputType::RightAngle)
 Add an element to the robot model with the kinematics/dynamics of a link between two actuators. More...
 
bool addBracket (robot_model::BracketType bracket_type)
 Add an element to the robot model with the kinematics/dynamics of a bracket between two actuators. More...
 
bool addEndEffector (EndEffectorType end_effector_type)
 Add an end effector element to the robot model. More...
 
bool addEndEffector (double x, double y, double z)
 Add an end effector element to the robot model. More...
 
bool addEndEffector (const Eigen::Matrix4d &com, const Eigen::VectorXd &inertia, double mass, const Eigen::Matrix4d &output)
 Adds a "custom" type end effector with the specified properties to the robot model. More...
 
void getForwardKinematics (FrameType, const Eigen::VectorXd &positions, Matrix4dVector &frames) const
 Generates the forward kinematics for the given robot model. More...
 
void getForwardKinematics (HebiFrameType frame_type, const Eigen::VectorXd &positions, Matrix4dVector &frames) const
 Generates the forward kinematics for the given robot model. More...
 
void getFK (FrameType, const Eigen::VectorXd &positions, Matrix4dVector &frames) const
 Generates the forward kinematics for the given robot model. More...
 
void getFK (HebiFrameType frame_type, const Eigen::VectorXd &positions, Matrix4dVector &frames) const
 Generates the forward kinematics for the given robot model. More...
 
void getEndEffector (const Eigen::VectorXd &positions, Eigen::Matrix4d &transform) const
 Generates the forward kinematics to the end effector (leaf node) frame(s). More...
 
template<typename... Args>
IKResult solveInverseKinematics (const Eigen::VectorXd &initial_positions, Eigen::VectorXd &result, Args... args) const
 Solves for an inverse kinematics solution given a set of objectives. More...
 
template<typename... Args>
IKResult solveIK (const Eigen::VectorXd &initial_positions, Eigen::VectorXd &result, Args... objectives) const
 Solves for an inverse kinematics solution given a set of objectives. More...
 
void getJacobians (FrameType, const Eigen::VectorXd &positions, MatrixXdVector &jacobians) const
 Generates the Jacobian for each frame in the given kinematic tree. More...
 
void getJacobians (HebiFrameType frame_type, const Eigen::VectorXd &positions, MatrixXdVector &jacobians) const
 Generates the Jacobian for each frame in the given kinematic tree. More...
 
void getJ (FrameType, const Eigen::VectorXd &positions, MatrixXdVector &jacobians) const
 Generates the Jacobian for each frame in the given kinematic tree. More...
 
void getJ (HebiFrameType frame_type, const Eigen::VectorXd &positions, MatrixXdVector &jacobians) const
 Generates the Jacobian for each frame in the given kinematic tree. More...
 
void getJacobianEndEffector (const Eigen::VectorXd &positions, Eigen::MatrixXd &jacobian) const
 Generates the Jacobian for the end effector (leaf node) frames(s). More...
 
void getJEndEffector (const Eigen::VectorXd &positions, Eigen::MatrixXd &jacobian) const
 Generates the Jacobian for the end effector (leaf node) frames(s). More...
 
void getMasses (Eigen::VectorXd &masses) const
 Returns the mass of each rigid body (or combination of rigid bodies) in the robot model. More...
 
void getMetadata (std::vector< MetadataBase > &metadata) const
 Returns the metadata of each component of the robot model. More...
 

Static Public Member Functions

static std::unique_ptr< RobotModelloadHRDF (const std::string &file)
 Creates a robot model object from the content of the HRDF file. More...
 
static std::unique_ptr< RobotModelloadHRDFString (const std::string &string)
 Creates a robot model object from the content of the HRDF description in the string. More...
 

Detailed Description

Represents a chain or tree of robot elements (rigid bodies and joints).

(Currently, only chains of elements are fully supported)

Member Typedef Documentation

◆ ActuatorType

◆ BracketType

◆ LinkType

Constructor & Destructor Documentation

◆ RobotModel()

hebi::robot_model::RobotModel::RobotModel ( )

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

◆ ~RobotModel()

hebi::robot_model::RobotModel::~RobotModel ( )
noexcept

Destructor cleans up robot model object, including all managed elements.

Member Function Documentation

◆ loadHRDF()

std::unique_ptr< RobotModel > hebi::robot_model::RobotModel::loadHRDF ( const std::string &  file)
static

Creates a robot model object from the content of the HRDF file.

◆ loadHRDFString()

std::unique_ptr< RobotModel > hebi::robot_model::RobotModel::loadHRDFString ( const std::string &  string)
static

Creates a robot model object from the content of the HRDF description in the string.

◆ setBaseFrame()

void hebi::robot_model::RobotModel::setBaseFrame ( const Eigen::Matrix4d &  base_frame)

Set the transform from a world coordinate system to the input of the root element in this robot model 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.

◆ getBaseFrame()

Eigen::Matrix4d hebi::robot_model::RobotModel::getBaseFrame ( ) const

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

◆ getFrameCount() [1/2]

size_t hebi::robot_model::RobotModel::getFrameCount ( FrameType  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.

◆ getFrameCount() [2/2]

size_t hebi::robot_model::RobotModel::getFrameCount ( HebiFrameType  frame_type) const
inline

Return the number of frames in the forward kinematics.

Deprecated:
Replaced by getFrameCount(FrameType) accepting C++ enum

◆ getDoFCount()

size_t hebi::robot_model::RobotModel::getDoFCount ( ) const

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

◆ addRigidBody()

bool hebi::robot_model::RobotModel::addRigidBody ( const Eigen::Matrix4d &  com,
const Eigen::VectorXd &  inertia,
double  mass,
const Eigen::Matrix4d &  output 
)

Adds a rigid body with the specified properties to the robot model.

Parameters
com4x4 matrix of the homogeneous transform to the center of mass location, relative to the input frame of the element. Note that this frame is also the frame the inertia tensor is given in.
inertiaThe 6 element representation (Ixx, Iyy, Izz, Ixy, Ixz, Iyz) of the inertia tensor, in the frame given by the COM.
output4x4 matrix of the homogeneous transform to the output frame, relative to the input frame of the element.
massThe mass of this element.

◆ addJoint() [1/2]

bool hebi::robot_model::RobotModel::addJoint ( JointType  joint_type)

Adds a degree of freedom about the specified axis.

This does not represent an element with size or mass, but only a connection between two other elements about a particular axis.

Parameters
joint_typeThe axis of rotation or translation about which this joint allows motion.

◆ addJoint() [2/2]

bool hebi::robot_model::RobotModel::addJoint ( HebiJointType  joint_type)
inline

Adds a degree of freedom about the specified axis.

Deprecated:
Replaced by addJoint(JointType) accepting C++ enum

◆ addActuator()

bool hebi::robot_model::RobotModel::addActuator ( robot_model::ActuatorType  actuator_type)

Add an element to the robot model with the kinematics/dynamics of an X5 actuator.

Parameters
actuator_typeThe type of actuator to add.

◆ addLink()

bool hebi::robot_model::RobotModel::addLink ( robot_model::LinkType  link_type,
double  extension,
double  twist,
LinkInputType  input_type = LinkInputType::RightAngle,
LinkOutputType  output_type = LinkOutputType::RightAngle 
)

Add an element to the robot model with the kinematics/dynamics of a link between two actuators.

Parameters
link_typeThe type of link between the actuators, e.g. a tube link between two X5 or X8 actuators.
extensionThe center-to-center distance between the actuator rotational axes.
twistThe rotation (in radians) between the actuator axes of rotation. Note that a 0 radian rotation will result in a z-axis offset between the two actuators, and a pi radian rotation will result in the actuator interfaces to this tube being in the same plane, but the rotational axes being anti-parallel.
input_typeThe style of input adapter on the link.
output_typeThe style of input adapter on the link.

◆ addBracket()

bool hebi::robot_model::RobotModel::addBracket ( robot_model::BracketType  bracket_type)

Add an element to the robot model with the kinematics/dynamics of a bracket between two actuators.

Parameters
bracket_typeThe type of bracket to add.

◆ addEndEffector() [1/3]

bool hebi::robot_model::RobotModel::addEndEffector ( EndEffectorType  end_effector_type)

Add an end effector element to the robot model.

For a "custom" type end effector, indentity transforms and zero mass and inertia parameters are used.

Parameters
end_effector_typeThe type of end_effector to add.

◆ addEndEffector() [2/3]

bool hebi::robot_model::RobotModel::addEndEffector ( double  x,
double  y,
double  z 
)

Add an end effector element to the robot model.

For a "custom" type end effector, indentity transforms and zero mass and inertia parameters are used.

Parameters
frameThe frame of the output of the end effector

◆ addEndEffector() [3/3]

bool hebi::robot_model::RobotModel::addEndEffector ( const Eigen::Matrix4d &  com,
const Eigen::VectorXd &  inertia,
double  mass,
const Eigen::Matrix4d &  output 
)

Adds a "custom" type end effector with the specified properties to the robot model.

Parameters
com4x4 matrix of the homogeneous transform to the center of mass location, relative to the input frame of the element. Note that this frame is also the frame the inertia tensor is given in.
inertiaThe 6 element representation (Ixx, Iyy, Izz, Ixy, Ixz, Iyz) of the inertia tensor, in the frame given by the COM.
output4x4 matrix of the homogeneous transform to the output frame, relative to the input frame of the element.
massThe mass of this element.

◆ getForwardKinematics() [1/2]

void hebi::robot_model::RobotModel::getForwardKinematics ( FrameType  frame_type,
const Eigen::VectorXd &  positions,
Matrix4dVector frames 
) const

Generates the forward kinematics for the given robot model.

See getFK for details.

◆ getForwardKinematics() [2/2]

void hebi::robot_model::RobotModel::getForwardKinematics ( HebiFrameType  frame_type,
const Eigen::VectorXd &  positions,
Matrix4dVector frames 
) const
inline

Generates the forward kinematics for the given robot model.

Deprecated:
Replaced by getForwardKinematics accepting C++ enum

◆ getFK() [1/2]

void hebi::robot_model::RobotModel::getFK ( FrameType  frame_type,
const Eigen::VectorXd &  positions,
Matrix4dVector frames 
) const

Generates the forward kinematics for the given robot model.

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 FrameType 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.

◆ getFK() [2/2]

void hebi::robot_model::RobotModel::getFK ( HebiFrameType  frame_type,
const Eigen::VectorXd &  positions,
Matrix4dVector frames 
) const
inline

Generates the forward kinematics for the given robot model.

Deprecated:
Replaced by getFK accepting C++ enum

◆ getEndEffector()

void hebi::robot_model::RobotModel::getEndEffector ( const Eigen::VectorXd &  positions,
Eigen::Matrix4d &  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
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.

◆ solveInverseKinematics()

template<typename... Args>
IKResult hebi::robot_model::RobotModel::solveInverseKinematics ( const Eigen::VectorXd &  initial_positions,
Eigen::VectorXd &  result,
Args...  args 
) const
inline

Solves for an inverse kinematics solution given a set of objectives.

See solveIK for details.

◆ solveIK()

template<typename... Args>
IKResult hebi::robot_model::RobotModel::solveIK ( const Eigen::VectorXd &  initial_positions,
Eigen::VectorXd &  result,
Args...  objectives 
) const
inline

Solves for an inverse kinematics solution given a set of objectives.

Parameters
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.
objectivesA variable number of objectives used to define the IK search (e.g., target end effector positions, etc). Each argument must have a base class of Objective.

◆ getJacobians() [1/2]

void hebi::robot_model::RobotModel::getJacobians ( FrameType  frame_type,
const Eigen::VectorXd &  positions,
MatrixXdVector jacobians 
) const

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

See getJ for details.

◆ getJacobians() [2/2]

void hebi::robot_model::RobotModel::getJacobians ( HebiFrameType  frame_type,
const Eigen::VectorXd &  positions,
MatrixXdVector jacobians 
) const
inline

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

Deprecated:
Replaced by getJacobians accepting C++ enum

◆ getJ() [1/2]

void hebi::robot_model::RobotModel::getJ ( FrameType  frame_type,
const Eigen::VectorXd &  positions,
MatrixXdVector jacobians 
) const

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

Parameters
frame_typeWhich type of frame to consider – see FrameType 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.

◆ getJ() [2/2]

void hebi::robot_model::RobotModel::getJ ( HebiFrameType  frame_type,
const Eigen::VectorXd &  positions,
MatrixXdVector jacobians 
) const
inline

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

Deprecated:
Replaced by getJ accepting C++ enum

◆ getJacobianEndEffector()

void hebi::robot_model::RobotModel::getJacobianEndEffector ( const Eigen::VectorXd &  positions,
Eigen::MatrixXd &  jacobian 
) const

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

See getJEndEffector for details.

◆ getJEndEffector()

void hebi::robot_model::RobotModel::getJEndEffector ( const Eigen::VectorXd &  positions,
Eigen::MatrixXd &  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
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.

◆ getMasses()

void hebi::robot_model::RobotModel::getMasses ( Eigen::VectorXd &  masses) const

Returns the mass of each rigid body (or combination of rigid bodies) in the robot model.

Parameters
massesA vector which is filled with the masses in the robot model. This vector is resized as necessary inside this function (it is set to have length equal to the number of com frames).

◆ getMetadata()

void hebi::robot_model::RobotModel::getMetadata ( std::vector< MetadataBase > &  metadata) const

Returns the metadata of each component of the robot model.


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