17 #ifndef __ROSEE_PARSER_MOVEIT_H    18 #define __ROSEE_PARSER_MOVEIT_H    25 #include <moveit/robot_model_loader/robot_model_loader.h>    40     typedef std::shared_ptr<ParserMoveIt> 
Ptr;
    41     typedef std::shared_ptr<const ParserMoveIt> 
ConstPtr;
   138     std::vector < std::string > 
getGroupOfLink ( std::string linkName );
   145     bool groupIsChain ( 
const std::string groupName ) 
const;
   156     bool groupIsChain ( 
const moveit::core::JointModelGroup* group ) 
const;
   363                                                 const moveit::core::JointModel* joint,  std::vector< const moveit::core::JointModel* > & jointsVect ) 
const;
   374 #endif // __ROSEE_PARSER_MOVEIT_H 
std::string getMimicNLJointOfFather(std::string mimicNLFatherName, std::string mimicNLJointName) const 
 
std::string getFirstActuatedJointInFinger(std::string linkName) const 
Given the linkName, this function returns the actuated joint that is a parent of this link and it is ...
 
std::string getFingerOfFingertip(std::string tipName) const 
This function returns the name of the finger which the passed tipName belongs to. ...
 
std::vector< std::string > activeJointNames
 
std::vector< std::string > fingertipNames
 
std::vector< std::string > getGroupOfLink(std::string linkName)
This function explores all groups of srdf and says to which ones the linkName belongs to...
 
std::map< std::string, std::string > getMimicNLJointsOfFather(std::string mimicNLFatherName) const 
 
const robot_model::RobotModelPtr getRobotModel() const 
the robot model can't be modified, if you want it to modify, use getCopyModel to get a copy...
 
std::vector< double > getSmallerBoundFromZero(std::string jointName) const 
For each DOF of a joint, find the limit which is nearer from 0 position. 
 
std::vector< std::string > getActiveJointNames() const 
getter for all active (actuated) joints' names. 
 
std::map< std::string, std::vector< const moveit::core::LinkModel * > > getDescendantLinksOfJoint() const 
getter for descendandsLinksOfJoint. 
 
void lookForPassiveJoints()
This function looks for all passive joints, defined so in the srdf file. 
 
std::shared_ptr< ParserMoveIt > Ptr
 
bool checkIfContinuosJoint(const std::string jointName) const 
check if the passed joint is continuos (i.e. 
 
std::vector< double > getBiggerBoundFromZero(std::string jointName) const 
For each DOF of a joint, find the limit which is farther from 0 position. 
 
std::vector< std::string > getPassiveJointNames() const 
getter for all the passive joints (defined in this way in the srdf file) Not all the not-actuated joi...
 
std::vector< const moveit::core::JointModel * > getActiveJointModels() const 
getter for all active (actuated) joints. 
 
std::map< std::string, std::string > fingerOfFingertipMap
The map with as key the name of the finger (defined in srdf file) and as value the fingertip (the las...
 
std::map< std::string, std::string > fingertipOfFingerMap
The map with as key the name of the fingertip (the last (not virtual) link of a finger) and as value ...
 
std::vector< const moveit::core::JointModel * > activeJointModels
 
std::map< std::string, std::vector< const moveit::core::JointModel * > > getDescendantJointsOfJoint() const 
getter for descendandsJointsOfJoint. 
 
unsigned int getNExclusiveJointsOfTip(std::string tipName, bool continuosIncluded) const 
Given a fingertip link, this function return the number of the joint that affect only the position of...
 
robot_model::RobotModelPtr robot_model
 
void lookJointsTipsCorrelation()
Here, we find for each tip, which are all the joints (active) that can modifies its position It is ea...
 
std::map< std::string, std::pair< std::string, std::string > > mimicNLFatherOfJointMap
This map contain as key the name of the mimic joint which position follows a non linear relationship ...
 
std::shared_ptr< const ParserMoveIt > ConstPtr
 
std::map< std::string, std::map< std::string, std::string > > getMimicNLJointsOfFatherMap() const 
 
std::string getFirstActuatedParentJoint(std::string linkName, bool includeContinuos) const 
starting from the given link, we explore the parents joint, until we found the first actuated...
 
void lookForDescendants()
Function to explore the kinematic tree from each actuated joint. 
 
std::map< std::string, std::map< std::string, std::string > > mimicNLJointsOfFatherMap
inverse map of previous, even if the function is replicated, this is anyway useful, at the cost of having 2 copy of a string type. 
 
std::map< std::string, std::pair< std::string, std::string > > getMimicNLFatherOfJointMap() const 
 
std::map< std::string, std::vector< std::string > > fingertipsOfJointMap
The map with as key the name of the actuated joint and as value all the fingertips which pose can be ...
 
std::vector< std::string > passiveJointNames
 
bool init(std::string robot_description, bool verbose=true)
Init the parser, fill the structures. 
 
std::map< std::string, std::string > getFingerOfFingertipMap() const 
 
void lookForActiveJoints()
This function look for all active joints in the model (i.e. 
 
bool groupIsChain(const std::string groupName) const 
check if a group (defined in srdf file) is a chain. 
 
robot_model::RobotModelPtr getCopyModel() const 
This function reload another model, same as the one loaded in init but this one can be modified exter...
 
std::string getFingertipOfFinger(std::string fingerName) const 
This function returns the name of the fingertip that belongs to the passed fingerName. 
 
std::pair< std::string, std::string > getMimicNLFatherOfJoint(std::string mimicNLJointName) const 
gets for the maps of non linear mimic joints 
 
std::map< std::string, std::vector< const moveit::core::JointModel * > > descendantJointsOfJoint
Map containing info about descendants joints of a joint see lookForDescendants function for more info...
 
std::map< std::string, std::vector< std::string > > getJointsOfFingertipMap() const 
 
unsigned int getNFingers() const 
 
std::map< std::string, std::vector< const moveit::core::LinkModel * > > descendantLinksOfJoint
Map containing info about descendants links of a joint see lookForDescendants function for more info...
 
void parseNonLinearMimicRelations(std::string xml)
 
class to parse urdf and srdf with moveit classes and to give information about the model parsed ...
 
std::string getHandName() const 
 
void lookForFingertips(bool verbose=true)
This function explore the robot_model (which was built from urdf and srdf files), and fills the finge...
 
std::map< std::string, std::vector< std::string > > jointsOfFingertipMap
The map with as key the name of the fingertip and as value all the joints (actuated) that can modify ...
 
std::map< std::string, std::vector< std::string > > getFingertipsOfJointMap() const 
 
void getRealDescendantLinkModelsRecursive(const moveit::core::LinkModel *link, std::vector< const moveit::core::LinkModel * > &linksVect, const moveit::core::JointModel *joint, std::vector< const moveit::core::JointModel * > &jointsVect) const 
Recursive function, support for lookForDescendants, to explore the urdf tree. 
 
std::map< std::string, std::string > getFingertipOfFingerMap() const 
 
std::string robot_description
 
std::vector< std::string > getFingertipNames() const