17 #ifndef __ROSEE_PARSER_MOVEIT_H 18 #define __ROSEE_PARSER_MOVEIT_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;
374 #endif // __ROSEE_PARSER_MOVEIT_H
std::map< std::string, std::vector< const moveit::core::LinkModel *> > getDescendantLinksOfJoint() const
getter for descendandsLinksOfJoint. "Descendants" is intended in a slightly different way respect to ...
std::map< std::string, std::vector< const moveit::core::JointModel *> > getDescendantJointsOfJoint() const
getter for descendandsJointsOfJoint. "Descendants" is intended in a slightly different way respect 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::string getFingerOfFingertip(std::string tipName) const
This function returns the name of the finger which the passed tipName belongs to. ...
std::vector< double > getSmallerBoundFromZero(std::string jointName) const
For each DOF of a joint, find the limit which is nearer from 0 position.
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...
std::map< std::string, std::string > getMimicNLJointsOfFather(std::string mimicNLFatherName) const
std::map< std::string, std::map< std::string, std::string > > getMimicNLJointsOfFatherMap() const
void lookForPassiveJoints()
This function looks for all passive joints, defined so in the srdf file.
std::string getFingertipOfFinger(std::string fingerName) const
This function returns the name of the fingertip that belongs to the passed fingerName.
std::shared_ptr< ParserMoveIt > Ptr
std::vector< std::string > getActiveJointNames() const
getter for all active (actuated) joints' names. The analogous moveit function returns also the "passi...
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
robot_model::RobotModelPtr getCopyModel() const
This function reload another model, same as the one loaded in init but this one can be modified exter...
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::string getMimicNLJointOfFather(std::string mimicNLFatherName, std::string mimicNLJointName) const
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::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< double > getBiggerBoundFromZero(std::string jointName) const
For each DOF of a joint, find the limit which is farther from 0 position.
std::pair< std::string, std::string > getMimicNLFatherOfJoint(std::string mimicNLJointName) const
gets for the maps of non linear mimic joints
void lookForDescendants()
Function to explore the kinematic tree from each actuated joint. It stores each descendants links and...
std::vector< std::string > getFingertipNames() const
bool groupIsChain(const std::string groupName) const
check if a group (defined in srdf file) is a chain. See groupIsChain ( moveit::core::JointModelGroup*...
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. the key is the name of the father, the value is a map because more than one child can mimic the father (In the other map, there is a pair)
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::map< std::string, std::pair< std::string, std::string > > getMimicNLFatherOfJointMap() const
std::vector< std::string > passiveJointNames
std::map< std::string, std::string > getFingerOfFingertipMap() const
std::vector< const moveit::core::JointModel * > getActiveJointModels() const
getter for all active (actuated) joints. The analogous moveit function returns also the "passive" one...
bool init(std::string robot_description, bool verbose=true)
Init the parser, fill the structures.
std::map< std::string, std::vector< std::string > > getFingertipsOfJointMap() const
void lookForActiveJoints()
This function look for all active joints in the model (i.e. not mimic, not fixed, not passive) There ...
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::vector< std::string > > getJointsOfFingertipMap() const
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...
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::string getHandName() 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...
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...
void parseNonLinearMimicRelations(std::string xml)
std::map< std::string, std::string > getFingertipOfFingerMap() const
class to parse urdf and srdf with moveit classes and to give information about the model parsed ...
void lookForFingertips(bool verbose=true)
This function explore the robot_model (which was built from urdf and srdf files), and fills the finge...
unsigned int getNFingers() const
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::string robot_description
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 ...
bool checkIfContinuosJoint(const std::string jointName) const
check if the passed joint is continuos (i.e. a revolute one with sum of bounds greater than 2*PI) ...