AUTh-ARL Core Stack  0.7
 All Classes Namespaces Functions Variables Typedefs Enumerations Enumerator Friends Groups Pages
arl::mujoco::Model Class Reference

Class representing a Robot Model in MuJoCo. More...

#include <model.h>

Inheritance diagram for arl::mujoco::Model:
Collaboration diagram for arl::mujoco::Model:

Public Member Functions

 Model (const std::string &name, const std::string &key_path, const std::string &model_path)
 The default constructor. More...
 
 ~Model ()
 
- Public Member Functions inherited from arl::robot::Model
 Model ()
 An empty constructor. More...
 
 Model (const std::string &n)
 A basic constructor parsing the name of the model. More...
 
std::string getName ()
 Returns the name of the model. More...
 
unsigned int getNrOfChains ()
 Returns the total number of the chains of the model. More...
 
unsigned int getNrOfMainChains ()
 Returns the number of the main chains of the model. More...
 
std::string getChainName (unsigned int chain)
 Returns the name of a chain. More...
 
std::vector< std::string > getChainNames ()
 Returns the names of every chain of the model. More...
 
unsigned int getNrOfJoints ()
 Returns the total number of the joints (total DOFs) of the robot model. More...
 
unsigned int getNrOfJoints (int chain)
 Returns the number of the joints of a specific chain. More...
 
std::vector< std::string > getJointNames ()
 Returns the names of total joints of the robot model. More...
 
std::vector< std::string > getJointNames (unsigned int chain)
 Returns the names of joints of one chain. More...
 
std::string getJointName (unsigned int joint)
 Returns the name of a joint of the whole robot. More...
 
std::string getJointName (unsigned int chain, unsigned int joint)
 Returns the name of a joint existing in a given chain. More...
 
std::pair< double, double > getJointLimit (unsigned int chain, unsigned int joint)
 Returns the limit of a joint existing in a given chain. More...
 
double getJointVelocityLimit (unsigned int joint)
 Returns the velocity limit of a joint existing in the complete list joints. More...
 
std::pair< double, double > getJointLimit (unsigned int joint)
 Returns the limit of a joint existing in the complete list joints. More...
 
std::vector< std::pair< double,
double > > 
getJointLimits (unsigned int chain)
 Returns the limits of joints of one chain. More...
 
unsigned int getGlobalIndex (int chain, unsigned int joint)
 Returns the index of a joint existing in a given main chain. This index is out of the total main joints of the robot. More...
 
std::vector< std::pair< double,
double > > 
getJointLimits ()
 Returns the limits of total joints of the robot model. More...
 
void test ()
 Tests if a model has initialized properly. Call it in your implemented derived class constructor. More...
 

Public Attributes

mjModel * mujoco
 A pointer to a MuJoCo mjModel. More...
 
- Public Attributes inherited from arl::robot::Model
std::map< std::string, int > chain_index
 
std::vector
< KDL::ChainFkSolverPos_recursive > 
fk_solver
 A number of KDL forward kinematic solvers, one for each chain. More...
 
std::vector
< KDL::ChainJntToJacSolver > 
jac_solver
 A number of KDL Jacobian solvers, one for each chain. Calculates the base Jacobian matrix of the chain. More...
 
std::vector< KDL::Chain > chain
 A number of KDL Chains storing the kinematics of each chain. More...
 

Additional Inherited Members

- Protected Attributes inherited from arl::robot::Model
std::vector< std::vector
< unsigned int > > 
global_index
 An array storing the global indeces. Should be filled by every model which derives from this class. More...
 
std::string name
 The name of this Model. More...
 
unsigned int num_chains_exclusive
 The number of the mutually exclusive chains. More...
 
std::vector< std::string > chain_name
 The names of the chains of this Model. More...
 
std::vector< std::vector
< std::string > > 
joint_name
 The joint names of this Model. More...
 
std::vector< std::pair< double,
double > > 
joint_limit
 The joint limits of this Model. More...
 
std::vector< double > velocity_limit
 The joint velocity limits of this Model. More...
 
std::vector< std::vector
< std::string > > 
link_name
 The link names of this Model. More...
 

Detailed Description

Class representing a Robot Model in MuJoCo.

You can inherit this class in order to build models for various models in MuJoCo.

Constructor & Destructor Documentation

arl::mujoco::Model::Model ( const std::string &  name,
const std::string &  key_path,
const std::string &  model_path 
)

The default constructor.

Parameters
nameThe name of the model
key_pathThe path to the activation key of MuJoCo
model_pathThe path for the xml file containing a MuJoCo model

Here is the call graph for this function:

arl::mujoco::Model::~Model ( )

Member Data Documentation

mjModel* arl::mujoco::Model::mujoco

A pointer to a MuJoCo mjModel.