SCL  1.0
Standard Control Library : Control, dynamics, physics, and simulation
 All Classes Namespaces Files Functions Variables Typedefs Enumerations Friends Macros Groups Pages
Classes | Public Member Functions | Private Types | Private Attributes | List of all members
jspace::Model Class Reference
Collaboration diagram for jspace::Model:
Collaboration graph
[legend]

Classes

struct  SAncestryEntry
 

Public Member Functions

 Model ()
 
int init (STaoTreeInfo *kgm_tree, STaoTreeInfo *cc_tree, double grav_x_, double grav_y_, double grav_z_, std::ostream *msg)
 
void update (State const &state)
 
void setState (State const &state)
 
State const & getState () const
 
size_t getNNodes () const
 
size_t getNJoints () const
 
size_t getNDOF () const
 
std::string getNodeName (size_t id) const
 
std::string getJointName (size_t id) const
 
taoDNodegetNode (size_t id) const
 
taoDNodegetNodeByName (std::string const &name) const
 
taoDNodegetNodeByJointName (std::string const &name) const
 
void getJointLimits (Eigen::VectorXd &joint_limits_lower, Eigen::VectorXd &joint_limits_upper) const
 
void updateKinematics ()
 
bool getGlobalFrame (taoDNode const *node, Eigen::Affine3d &global_transform) const
 
bool computeGlobalFrame (taoDNode const *node, Eigen::Affine3d const &local_transform, Eigen::Affine3d &global_transform) const
 
bool computeGlobalFrame (taoDNode const *node, double local_x, double local_y, double local_z, Eigen::Affine3d &global_transform) const
 
bool computeGlobalFrame (taoDNode const *node, Eigen::VectorXd const &local_translation, Eigen::Affine3d &global_transform) const
 
bool computeGlobalCOMFrame (taoDNode const *node, Eigen::Affine3d &global_com_transform) const
 
bool computeJacobian (taoDNode const *node, Eigen::MatrixXd &jacobian) const
 
bool computeJacobian (taoDNode const *node, double gx, double gy, double gz, Eigen::MatrixXd &jacobian) const
 
bool computeJacobian (taoDNode const *node, Eigen::VectorXd const &global_point, Eigen::MatrixXd &jacobian) const
 
void updateDynamics ()
 
bool computeCOM (Eigen::VectorXd &com, Eigen::MatrixXd *opt_jcom) const
 
void computeGravity ()
 
bool disableGravityCompensation (size_t index, bool disable)
 
bool getGravity (Eigen::VectorXd &gravity) const
 
void computeCoriolisCentrifugal ()
 
bool getCoriolisCentrifugal (Eigen::VectorXd &coriolis_centrifugal) const
 
void computeMassInertia ()
 
bool getMassInertia (Eigen::MatrixXd &mass_inertia) const
 
void computeInverseMassInertia ()
 
bool getInverseMassInertia (Eigen::MatrixXd &inverse_mass_inertia) const
 
STaoTreeInfo_getKGMTree ()
 
STaoTreeInfo_getCCTree ()
 

Private Types

typedef std::set< size_t > dof_set_t
 

Private Attributes

std::size_t ndof_
 
STaoTreeInfokgm_tree_
 
STaoTreeInfocc_tree_
 
dof_set_t gravity_disabled_
 
deVector3gravity_
 
State state_
 
Eigen::VectorXd g_torque_
 
Eigen::VectorXd cc_torque_
 
std::vector< double > a_upper_triangular_
 
std::vector< double > ainv_upper_triangular_
 
std::map< taoDNode
*, std::list< SAncestryEntry > > 
ancestry_table_
 

Constructor & Destructor Documentation

jspace::Model::Model ( )

Please use the init() method in order to initialize your jspace::Model. It does some sanity checking, and error handling from within a constructor is just not so great.

Member Function Documentation

STaoTreeInfo* jspace::Model::_getCCTree ( )
inline

For debugging only, access to the optional Coriolis-centrifugal tree. Can NULL if the user is not interested in Coriolis-centrifugal effects.

STaoTreeInfo* jspace::Model::_getKGMTree ( )
inline

For debugging only, access to the kinematics-gravity-mass-inertia tree.

bool jspace::Model::computeCOM ( Eigen::VectorXd &  com,
Eigen::MatrixXd *  opt_jcom 
) const

Computes the location of the center of gravity, and optionally also its Jacobian. Pass opt_jcom=0 if you are not interested in the Jacobian. Failures can only be due to calls of computeJacobian() that happens for each node's contribution to the Jacobian of the COM.

void jspace::Model::computeCoriolisCentrifugal ( )

Compute the Coriolis and contrifugal joint-torque vector. If you set cc_tree=NULL in the constructor, then this is a no-op.

bool jspace::Model::computeGlobalFrame ( taoDNode const *  node,
Eigen::Affine3d const &  local_transform,
Eigen::Affine3d &  global_transform 
) const

Compute the global frame (translation and rotation) corresponding to a local frame expressed wrt the origin of a given node.

Returns
True on success. The only possible failure stems from an invalid node, so if you got that using getNode() or one of the related methods you can safely ignore the return value.
bool jspace::Model::computeGlobalFrame ( taoDNode const *  node,
double  local_x,
double  local_y,
double  local_z,
Eigen::Affine3d &  global_transform 
) const

Convenience method in case you are only interested in the translational part and hold the local point in three doubles. The copmuted global_transform will have the same rotational component as the node's origin.

Returns
True on success. The only possible failure stems from an invalid node, so if you got that using getNode() or one of the related methods you can safely ignore the return value.
bool jspace::Model::computeGlobalFrame ( taoDNode const *  node,
Eigen::VectorXd const &  local_translation,
Eigen::Affine3d &  global_transform 
) const

Convenience method in case you are only interested in the translational part and hold the local point in a three-dimensional vector. The copmuted global_transform will have the same rotational component as the node's origin.

Returns
True on success. The only possible failure stems from an invalid node, so if you got that using getNode() or one of the related methods you can safely ignore the return value.
void jspace::Model::computeGravity ( )

Compute the gravity joint-torque vector.

void jspace::Model::computeInverseMassInertia ( )

Compute the inverse joint-space mass-inertia matrix.

bool jspace::Model::computeJacobian ( taoDNode const *  node,
Eigen::MatrixXd &  jacobian 
) const

Compute the Jacobian (J_v over J_omega) at the origin of a given node.

Note
This just ends up calling the other computeJacobian() which takes a global point as argument, passing in the origin of the given node.
Returns
True on success. There are two possible failures: an invalid node, or an unsupported joint type. If you got the node using getNode() or one of the related methods, then you need to extend this implementation when it returns false.
bool jspace::Model::computeJacobian ( taoDNode const *  node,
double  gx,
double  gy,
double  gz,
Eigen::MatrixXd &  jacobian 
) const

Compute the Jacobian (J_v over J_omega) for a given node, at a point expressed wrt to the global frame.

Todo:
Implement support for more than one joint per node, and more than one DOF per joint.
Returns
True on success. There are two possible failures: an invalid node, or an unsupported joint type. If you got the node using getNode() or one of the related methods, then you need to extend this implementation when it returns false.
bool jspace::Model::computeJacobian ( taoDNode const *  node,
Eigen::VectorXd const &  global_point,
Eigen::MatrixXd &  jacobian 
) const
inline

Convenience method in case you are holding the global position in a three-dimensional vector.

void jspace::Model::computeMassInertia ( )

Compute the joint-space mass-inertia matrix, a.k.a. the kinetic energy matrix.

bool jspace::Model::disableGravityCompensation ( size_t  index,
bool  disable 
)

Disable (or enable) gravity compensation for a given DOF (specified using its index). If you set disable to true, then getGravity() will knock out (set to zero) the corresponding entry of the gravity joint-torque vector.

Note
Invalid indices are silently ignore, and true is returned. Valid indices are 0<=index<getNDOF().
Returns
The previous value of disable for this joint.
bool jspace::Model::getCoriolisCentrifugal ( Eigen::VectorXd &  coriolis_centrifugal) const

Retrieve the Coriolis and contrifugal joint-torque vector.

Returns
True on success. There are two possibility of receiving false: (i) you set cc_tree=NULL in the constructor, or (ii) you never called computeCoriolisCentrifugal(), which gets called by updateDynamics(), which gets called by update().
bool jspace::Model::getGlobalFrame ( taoDNode const *  node,
Eigen::Affine3d &  global_transform 
) const

Retrieve the frame (translation and rotation) of a node origin.

Returns
True on success. The only possible failure stems from an invalid node, so if you got that using getNode() or one of the related methods you can safely ignore the return value.
bool jspace::Model::getGravity ( Eigen::VectorXd &  gravity) const

Retrieve the gravity joint-torque vector.

Returns
True on success. The only possibility of receiving false is if you never called updateDynamics(), which gets called by updateDynamics(), which gets called by update().
bool jspace::Model::getInverseMassInertia ( Eigen::MatrixXd &  inverse_mass_inertia) const

Retrieve the inverse joint-space mass-inertia matrix.

Returns
True on success. The only possibility of receiving false is if you never called computeMassInertia(), which gets called by updateDynamics(), which gets called by update().
void jspace::Model::getJointLimits ( Eigen::VectorXd &  joint_limits_lower,
Eigen::VectorXd &  joint_limits_upper 
) const

Retrieve joint limit information. This method fills the provided vectors with the lower and upper joint limits. In case no joint limit information is available, it sets the lower limit to std::numeric_limits<double>::min() and the upper limit to std::numeric_limits<double>::max().

std::string jspace::Model::getJointName ( size_t  id) const

Retrieve the name of a joint. Returns an empty string in case the id is invalid. Use getNJoints() to find out how many joints there are.

Todo:
A joint can have any number of DOF, which means there should be a way to get at them individually, but currently we only support exactly one 1-DOF joints per node.
bool jspace::Model::getMassInertia ( Eigen::MatrixXd &  mass_inertia) const

Retrieve the joint-space mass-inertia matrix, a.k.a. the kinetic energy matrix.

Returns
True on success. The only possibility of receiving false is if you never called computeMassInertia(), which gets called by updateDynamics(), which gets called by update().
size_t jspace::Model::getNDOF ( ) const

Compute or retrieve the cached number of degrees of freedom of the robot. Note that each joint can have any number of degrees of freedom, which is why this method might return something else than getNJoints().

size_t jspace::Model::getNJoints ( ) const

Compute or retrieve the cached number of joints in the robot. Note that each joint can have any number of degrees of freedom, which is why getNDOF() might come in handy, too.

size_t jspace::Model::getNNodes ( ) const

Compute or retrieve the cached number of nodes in the robot.

Note
  • the root node is NOT included in this count.
  • in principle, each node can have any number of joints, and each joint can have any number of degrees of freedom, which is why getNJoints() and getNDOF() might come in handy, too.
taoDNode * jspace::Model::getNode ( size_t  id) const

Retrieve a node by ID.

taoDNode * jspace::Model::getNodeByJointName ( std::string const &  name) const

Retrieve a node by joint name. This will find and retrieve the node to which the joint is attached (see also getNodeByName()), which allows you to retrieve the taoJoint instance itself.

Note
In principle, a taoDNode can have any number of joints, so you might have to search through them to find the exact one you're looking for. However, all use cases so far seem to be limited to exactly one joint per node (and each node having exactly one joint).
Todo:
Add support for registering aliases, just as for getNodeByName().
taoDNode * jspace::Model::getNodeByName ( std::string const &  name) const

Retrieve a node by its name.

Todo:
Add support for registering aliases, such as "end-effector" or "End_Effector", which might correspond to "right-gripper" or so depending on the robot.
std::string jspace::Model::getNodeName ( size_t  id) const

Retrieve the name of a node. Returns an empty string in case the id is invalid. Use getNNodes() to find out how many nodes there are.

State const& jspace::Model::getState ( ) const
inline

Retrieve the state passed to setState() (or update(), for that matter).

int jspace::Model::init ( STaoTreeInfo kgm_tree,
STaoTreeInfo cc_tree,
double  grav_x_,
double  grav_y_,
double  grav_z_,
std::ostream *  msg 
)

Initialize the model with a TAO tree. Actually, it needs two copies of the same tree if you want to estimate centrifugal and Coriolis effects, but that is optional.

This method also does some sanity checks and will return a non-zero error code if something is amiss. In order to get human-readable error strings, just pass a non-NULL msg pointer in as well. For instance, &std::cout will do nicely in most cases.

Note
Transfers ownership of the given TAO trees. They will be deleted when this jspace::Model instance is destructed. Also note that their info vector might get reordered in order to ensure that each node sits at the index that corresponds to its ID.
Returns
0 on success.
Parameters
kgm_treeTAO tree info used for computing kinematics, the gravity torque vector, the mass-inertia matrix, and its inverse. This tree will be deleted in the jspace::Model destructor.
cc_treeOptional TAO tree info for computing Coriolis and centrifugal torques. If you set this to NULL, then the Coriolis and centrifugal forces won't be computed. This tree will be deleted in the jspace::Model destructor.
grav_x_Gravity x *
grav_y_Gravity y *
grav_z_Gravity z *
msgOptional stream that will receive error messages from the consistency checks.
void jspace::Model::setState ( State const &  state)

Inform the model about the joint state. We have to separate the state update from the computation of the various quantities in order to efficiently use the TAO tree representation, which forces us to distribute the state over its nodes before computing the model.

Note
The given state has to have the correct dimensions, but this is not checked by the implementation. If the given state has too few dimensions, then some positions and velocities of the model will remain at their old values. If there are too many dimensions, they will be ignored.
void jspace::Model::update ( State const &  state)

Calls setState(), updateKinematics(), and updateDynamics(). After calling the update() method, you can use any of the other methods without worrying whether you have already called the corresponding computeFoo() method.

Note
The given state has to have the correct dimensions, but this is not checked by the implementation. If the given state has too few dimensions, then some positions and velocities of the model will remain at their old values. If there are too many dimensions, they will be ignored.
void jspace::Model::updateDynamics ( )
void jspace::Model::updateKinematics ( )

Computes the node origins wrt the global frame.


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