Public Types | Public Member Functions | Private Member Functions | Static Private Member Functions | Private Attributes | Static Private Attributes | List of all members
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

enum  ActuatorType {
  ActuatorType::X5_1, ActuatorType::X5_4, ActuatorType::X5_9, ActuatorType::X8_3,
  ActuatorType::X8_9, ActuatorType::X8_16
}
 
enum  BracketType {
  BracketType::X5LightLeft, BracketType::X5LightRight, BracketType::X5HeavyLeftInside, BracketType::X5HeavyLeftOutside,
  BracketType::X5HeavyRightInside, BracketType::X5HeavyRightOutside
}
 
enum  LinkType { LinkType::X5 }
 

Public Member Functions

bool addActuator (ActuatorType actuator_type)
 Add an element to the robot model with the kinematics/dynamics of an X5 actuator. More...
 
bool addBracket (BracketType bracket_type)
 Add an element to the robot model with the kinematics/dynamics of a bracket between two actuators. More...
 
bool addJoint (HebiJointType joint_type, bool combine)
 Adds a degree of freedom about the specified axis. More...
 
bool addLink (LinkType link_type, double extension, double twist)
 Add an element to the robot model with the kinematics/dynamics of a link between two actuators. More...
 
bool addRigidBody (const Eigen::Matrix4d &com, const Eigen::VectorXd &inertia, double mass, const Eigen::Matrix4d &output, bool combine)
 Adds a rigid body with the specified properties to the robot model. 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 getDoFCount () const
 Returns the number of settable degrees of freedom in the kinematic tree. (This is equal to the number of actuators added). More...
 
void getEndEffector (const Eigen::VectorXd &positions, Eigen::Matrix4d &transform) const
 Generates the forward kinematics to the end effector (leaf node) frame(s). More...
 
void getFK (HebiFrameType, const Eigen::VectorXd &positions, Matrix4dVector &frames) const
 Generates the forward kinematics for the given robot model. More...
 
void getForwardKinematics (HebiFrameType, const Eigen::VectorXd &positions, Matrix4dVector &frames) const
 Generates the forward kinematics for the given robot model. More...
 
size_t getFrameCount (HebiFrameType frame_type) const
 Return the number of frames in the forward kinematics. More...
 
void getJ (HebiFrameType, 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 getJacobians (HebiFrameType, const Eigen::VectorXd &positions, MatrixXdVector &jacobians) const
 Generates the Jacobian for each frame in the given kinematic tree. 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...
 
 RobotModel ()
 Creates a robot model object with no bodies and an identity base frame. 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...
 
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...
 
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...
 
 ~RobotModel () noexcept
 Destructor cleans up robot model object, including all managed elements. More...
 

Private Member Functions

template<typename T >
HebiStatusCode addObjectives (HebiIKPtr ik, const T &objective) const
 
template<typename T , typename... Args>
HebiStatusCode addObjectives (HebiIKPtr ik, const T &objective, Args...args) const
 
bool tryAdd (HebiRobotModelElementPtr element, bool combine)
 

Static Private Member Functions

static void setRodXAxisInertia (Eigen::VectorXd &inertia, double mass, double length)
 
static void setRotX (Eigen::Matrix4d &matrix, double radians)
 
static void setSphereInertia (Eigen::VectorXd &inertia, double mass, double radius)
 
static void setTranslate (Eigen::Matrix4d &matrix, double x, double y, double z)
 

Private Attributes

HebiRobotModelPtr const internal_
 
friend Objective
 

Static Private Attributes

static const std::map< ActuatorType, double > actuator_masses_
 

Detailed Description

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

(Currently, only chains of elements are fully supported)

Definition at line 86 of file robot_model.hpp.

Member Enumeration Documentation

Enumerator
X5_1 
X5_4 
X5_9 
X8_3 
X8_9 
X8_16 

Definition at line 148 of file robot_model.hpp.

Enumerator
X5LightLeft 
X5LightRight 
X5HeavyLeftInside 
X5HeavyLeftOutside 
X5HeavyRightInside 
X5HeavyRightOutside 

Definition at line 163 of file robot_model.hpp.

Enumerator
X5 

Definition at line 158 of file robot_model.hpp.

Constructor & Destructor Documentation

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

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

Definition at line 143 of file robot_model.cpp.

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

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

Definition at line 148 of file robot_model.cpp.

Member Function Documentation

bool hebi::robot_model::RobotModel::addActuator ( 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.

Definition at line 229 of file robot_model.cpp.

bool hebi::robot_model::RobotModel::addBracket ( 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.

Definition at line 315 of file robot_model.cpp.

bool hebi::robot_model::RobotModel::addJoint ( HebiJointType  joint_type,
bool  combine 
)

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.

Definition at line 222 of file robot_model.cpp.

bool hebi::robot_model::RobotModel::addLink ( LinkType  link_type,
double  extension,
double  twist 
)

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.

Definition at line 284 of file robot_model.cpp.

template<typename T >
HebiStatusCode hebi::robot_model::RobotModel::addObjectives ( HebiIKPtr  ik,
const T &  objective 
) const
inlineprivate

Internal function for resolving variadic template (stops recursion and detects invalid arguments).

Definition at line 101 of file robot_model.hpp.

template<typename T , typename... Args>
HebiStatusCode hebi::robot_model::RobotModel::addObjectives ( HebiIKPtr  ik,
const T &  objective,
Args...  args 
) const
inlineprivate

Internal function for resolving variadic template.

Definition at line 112 of file robot_model.hpp.

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

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

This can be 'combined' with the parent element (the element this is attaching to), which means that the mass, inertia, and output frames of this element will be integrated with the parent. The mass will be combined, and the reported parent output frame that this element attached to will be replaced with the output from this element (so that the number of output frames and masses remains constant).

Parameters
com4x4 matric 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.
combine'True' if the frames and masses of this body should be combined with the parent, 'false' otherwise.

Definition at line 186 of file robot_model.cpp.

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.

Definition at line 162 of file robot_model.cpp.

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

Definition at line 180 of file robot_model.cpp.

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

Definition at line 400 of file robot_model.cpp.

void hebi::robot_model::RobotModel::getFK ( HebiFrameType  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 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.

Definition at line 377 of file robot_model.cpp.

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

Generates the forward kinematics for the given robot model.

See getFK for details.

Definition at line 372 of file robot_model.cpp.

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

Definition at line 175 of file robot_model.cpp.

void hebi::robot_model::RobotModel::getJ ( HebiFrameType  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 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.

Definition at line 422 of file robot_model.cpp.

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.

Definition at line 446 of file robot_model.cpp.

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

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

See getJ for details.

Definition at line 418 of file robot_model.cpp.

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.

Definition at line 450 of file robot_model.cpp.

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

Definition at line 463 of file robot_model.cpp.

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.

Definition at line 153 of file robot_model.cpp.

void hebi::robot_model::RobotModel::setRodXAxisInertia ( Eigen::VectorXd &  inertia,
double  mass,
double  length 
)
staticprivate

Internal function for row-major double-array matrix manipulation

Definition at line 120 of file robot_model.cpp.

void hebi::robot_model::RobotModel::setRotX ( Eigen::Matrix4d &  matrix,
double  radians 
)
staticprivate

Internal function for row-major double-array matrix manipulation

Definition at line 97 of file robot_model.cpp.

void hebi::robot_model::RobotModel::setSphereInertia ( Eigen::VectorXd &  inertia,
double  mass,
double  radius 
)
staticprivate

Internal function for row-major double-array matrix manipulation

Definition at line 109 of file robot_model.cpp.

void hebi::robot_model::RobotModel::setTranslate ( Eigen::Matrix4d &  matrix,
double  x,
double  y,
double  z 
)
staticprivate

Internal function for row-major double-array matrix manipulation

Definition at line 90 of file robot_model.cpp.

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.

Definition at line 377 of file robot_model.hpp.

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.

Definition at line 357 of file robot_model.hpp.

bool hebi::robot_model::RobotModel::tryAdd ( HebiRobotModelElementPtr  element,
bool  combine 
)
private

Internal function for adding robot model elements

Definition at line 131 of file robot_model.cpp.

Member Data Documentation

const std::map< RobotModel::ActuatorType, double > hebi::robot_model::RobotModel::actuator_masses_
staticprivate
Initial value:
= {
std::make_pair(ActuatorType::X5_1, 0.315),
std::make_pair(ActuatorType::X5_4, 0.335),
std::make_pair(ActuatorType::X5_9, 0.360),
std::make_pair(ActuatorType::X8_3, 0.460),
std::make_pair(ActuatorType::X8_9, 0.480),
std::make_pair(ActuatorType::X8_16, 0.500)
}

Helper data structure that contains masses for various actuators

Definition at line 479 of file robot_model.hpp.

HebiRobotModelPtr const hebi::robot_model::RobotModel::internal_
private

C-style robot model object

Definition at line 94 of file robot_model.hpp.

friend hebi::robot_model::RobotModel::Objective
private

Definition at line 88 of file robot_model.hpp.


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


hebiros
Author(s): Xavier Artache , Matthew Tesch
autogenerated on Thu Sep 3 2020 04:11:00