Public Types | Public Member Functions | Private Member Functions | Private Attributes | List of all members
ROSEE::ParserMoveIt Class Reference

class to parse urdf and srdf with moveit classes and to give information about the model parsed More...

#include <ParserMoveIt.h>

Public Types

typedef std::shared_ptr< const ParserMoveItConstPtr
 
typedef std::shared_ptr< ParserMoveItPtr
 

Public Member Functions

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) More...
 
bool checkIfContinuosJoint (const moveit::core::JointModel *joint) const
 check if the passed joint is continuos (i.e. a revolute one with sum of bounds greater than 2*PI) More...
 
std::vector< const moveit::core::JointModel * > getActiveJointModels () const
 getter for all active (actuated) joints. The analogous moveit function returns also the "passive" ones (defined in srdf), this one exclude the passive More...
 
std::vector< std::string > getActiveJointNames () const
 getter for all active (actuated) joints' names. The analogous moveit function returns also the "passive" ones (defined in srdf) More...
 
std::vector< double > getBiggerBoundFromZero (std::string jointName) const
 For each DOF of a joint, find the limit which is farther from 0 position. More...
 
std::vector< double > getBiggerBoundFromZero (const moveit::core::JointModel *joint) const
 For each DOF of a joint, find the limit which is farther from 0 position. More...
 
robot_model::RobotModelPtr getCopyModel () const
 This function reload another model, same as the one loaded in init but this one can be modified externally, because it will not affect the internal structures of this class. More...
 
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 moveit (see lookForDescendants doc) More...
 
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 moveit (see lookForDescendants doc) More...
 
std::string getFingerOfFingertip (std::string tipName) const
 This function returns the name of the finger which the passed tipName belongs to. More...
 
std::map< std::string, std::string > getFingerOfFingertipMap () const
 
std::vector< std::string > getFingertipNames () const
 
std::string getFingertipOfFinger (std::string fingerName) const
 This function returns the name of the fingertip that belongs to the passed fingerName. More...
 
std::map< std::string, std::string > getFingertipOfFingerMap () const
 
std::map< std::string, std::vector< std::string > > getFingertipsOfJointMap () 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 the first joint of the chain which the link belongs to. E.G. given a fingertip, it returns the first actuated joint of the finger (e.g. the joint that moves the firsts phalanges, if present) From the linkName given, this function explores the parent links until we found a link with more than 1 child joint. This means that we have found the "base" of the kinematic chain, so we can go forward to find the first actuated joint. More...
 
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. This ones will be the interesting joint More...
 
std::vector< std::string > getGroupOfLink (std::string linkName)
 This function explores all groups of srdf and says to which ones the linkName belongs to. Returns a vector because a link can be part of more group. More...
 
std::string getHandName () const
 
std::map< std::string, std::vector< std::string > > getJointsOfFingertipMap () const
 
std::pair< std::string, std::string > getMimicNLFatherOfJoint (std::string mimicNLJointName) const
 gets for the maps of non linear mimic joints More...
 
std::map< std::string, std::pair< std::string, std::string > > getMimicNLFatherOfJointMap () const
 
std::string getMimicNLJointOfFather (std::string mimicNLFatherName, std::string mimicNLJointName) const
 
std::map< std::string, std::string > getMimicNLJointsOfFather (std::string mimicNLFatherName) const
 
std::map< std::string, std::map< std::string, std::string > > getMimicNLJointsOfFatherMap () 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 this fingertip and not any other fingertips (obviously the joints can affect different other links that are not fingertips (e.g. middles phalanges) ) More...
 
unsigned int getNFingers () const
 
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 joint are passive (a mimic joint can also be not defined as passive in srdf) More...
 
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. More...
 
std::vector< double > getSmallerBoundFromZero (std::string jointName) const
 For each DOF of a joint, find the limit which is nearer from 0 position. More...
 
std::vector< double > getSmallerBoundFromZero (const moveit::core::JointModel *joint) const
 For each DOF of a joint, find the limit which is nearer from 0 position. More...
 
bool groupIsChain (const std::string groupName) const
 check if a group (defined in srdf file) is a chain. See groupIsChain ( moveit::core::JointModelGroup* group ) More...
 
bool groupIsChain (const moveit::core::JointModelGroup *group) const
 check if a group (defined in srdf file) is a chain. This is done simply exploring all the links of the group: if no links have more than 1 children, the group is a chain. Moveit has a function isChain() but I don't understand how it works, in fact also if there is a link with more children joint sometimes the group is considered a chain anyway. I can't find where the moveit _is_chain member is set. More...
 
bool init (std::string robot_description, bool verbose=true)
 Init the parser, fill the structures. More...
 
void parseNonLinearMimicRelations (std::string xml)
 
 ParserMoveIt ()
 
 ~ParserMoveIt ()
 

Private Member Functions

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. More...
 
void lookForActiveJoints ()
 This function look for all active joints in the model (i.e. not mimic, not fixed, not passive) There exist a moveit function getActiveJointModels() which return all not mimic and not fixed, but it can return also passive joints (a info that is stored in srdf file). So this function also check if the joint is not passive It stores both the joint names and pointer to joint models in two private vector (activeJointNames and activeJointModels) More...
 
void lookForDescendants ()
 Function to explore the kinematic tree from each actuated joint. It stores each descendants links and joints in two maps (descendantLinksOfJoint and descendantJointsOfJoint) where the key is the name of the joint and the value a vector of descendandts. The tree is explored recursively thanks to getRealDescendantLinkModelsRecursive support function. More...
 
void lookForFingertips (bool verbose=true)
 This function explore the robot_model (which was built from urdf and srdf files), and fills the fingerTipNames vector. In particular, the function explores only the groups specified in the srdf, and prints infos about each link it finds (eg. not a fingertin, not a chain group, and so on). A fingertip is a link with the following conditions: More...
 
void lookForPassiveJoints ()
 This function looks for all passive joints, defined so in the srdf file. More...
 
void lookJointsTipsCorrelation ()
 Here, we find for each tip, which are all the joints (active) that can modifies its position It is easier to start from each joint and see which tips has as its descendands, because there is the getDescendantLinkModels() function in moveit that gives ALL the child links. There is not a function like getNonFixedParentJointModels from the tip, there is only the one to take the FIRST parent joint (getParentJointModel()) Meanwhile, we find also, for each joint, all the tips that are influenced by the joint movement: fingertipsOfJointMap. More...
 

Private Attributes

std::vector< const moveit::core::JointModel * > activeJointModels
 
std::vector< std::string > activeJointNames
 
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. More...
 
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. More...
 
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 last (not virtual) link of the joint) More...
 
std::vector< std::string > fingertipNames
 
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 the finger name (defined in the srdf) More...
 
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 modified by the joint. More...
 
std::string handName
 
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 its pose. More...
 
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 with a father joint. As value there is a pair: first element is the name of the father joint, second element is the non linear equation. More...
 
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) More...
 
unsigned int nFingers
 
std::vector< std::string > passiveJointNames
 
std::string robot_description
 
robot_model::RobotModelPtr robot_model
 

Detailed Description

class to parse urdf and srdf with moveit classes and to give information about the model parsed

Todo:
merge this with Parser class?

Definition at line 36 of file ParserMoveIt.h.

Member Typedef Documentation

◆ ConstPtr

typedef std::shared_ptr<const ParserMoveIt> ROSEE::ParserMoveIt::ConstPtr

Definition at line 41 of file ParserMoveIt.h.

◆ Ptr

typedef std::shared_ptr<ParserMoveIt> ROSEE::ParserMoveIt::Ptr

Definition at line 40 of file ParserMoveIt.h.

Constructor & Destructor Documentation

◆ ParserMoveIt()

ROSEE::ParserMoveIt::ParserMoveIt ( )

Definition at line 19 of file ParserMoveIt.cpp.

◆ ~ParserMoveIt()

ROSEE::ParserMoveIt::~ParserMoveIt ( )

Definition at line 23 of file ParserMoveIt.cpp.

Member Function Documentation

◆ checkIfContinuosJoint() [1/2]

bool ROSEE::ParserMoveIt::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)

Parameters
jointNamethe name of the joint
Returns
bool true if joint is continuos

Definition at line 244 of file ParserMoveIt.cpp.

◆ checkIfContinuosJoint() [2/2]

bool ROSEE::ParserMoveIt::checkIfContinuosJoint ( const moveit::core::JointModel joint) const

check if the passed joint is continuos (i.e. a revolute one with sum of bounds greater than 2*PI)

Parameters
jointpointer to the joint model
Returns
bool true if joint is continuos

Definition at line 253 of file ParserMoveIt.cpp.

◆ getActiveJointModels()

std::vector< const moveit::core::JointModel * > ROSEE::ParserMoveIt::getActiveJointModels ( ) const

getter for all active (actuated) joints. The analogous moveit function returns also the "passive" ones (defined in srdf), this one exclude the passive

Returns
vector of pointer of all joints that are actuated

Definition at line 73 of file ParserMoveIt.cpp.

◆ getActiveJointNames()

std::vector< std::string > ROSEE::ParserMoveIt::getActiveJointNames ( ) const

getter for all active (actuated) joints' names. The analogous moveit function returns also the "passive" ones (defined in srdf)

Returns
vector of name of all joints that are actuated

Definition at line 69 of file ParserMoveIt.cpp.

◆ getBiggerBoundFromZero() [1/2]

std::vector< double > ROSEE::ParserMoveIt::getBiggerBoundFromZero ( std::string  jointName) const

For each DOF of a joint, find the limit which is farther from 0 position.

Parameters
jointNamethe name of the joint
Returns
std::vector<double> a vector (because joint can have more dofs) containing the values of the limits that are farther from 0

Definition at line 274 of file ParserMoveIt.cpp.

◆ getBiggerBoundFromZero() [2/2]

std::vector< double > ROSEE::ParserMoveIt::getBiggerBoundFromZero ( const moveit::core::JointModel joint) const

For each DOF of a joint, find the limit which is farther from 0 position.

Parameters
jointpointer to the joint model
Returns
std::vector<double> a vector (because joint can have more dofs) containing the values of the limits that are farther from 0

Definition at line 284 of file ParserMoveIt.cpp.

◆ getCopyModel()

robot_model::RobotModelPtr ROSEE::ParserMoveIt::getCopyModel ( ) const

This function reload another model, same as the one loaded in init but this one can be modified externally, because it will not affect the internal structures of this class.

Returns
robot_model::RobotModelPtr a pointer to a new robot model created

Definition at line 187 of file ParserMoveIt.cpp.

◆ getDescendantJointsOfJoint()

std::map< std::string, std::vector< const moveit::core::JointModel *> > ROSEE::ParserMoveIt::getDescendantJointsOfJoint ( ) const

getter for descendandsJointsOfJoint. "Descendants" is intended in a slightly different way respect to moveit (see lookForDescendants doc)

Returns
map with keys the joint name and values a vector of pointer of all descendants joints

Definition at line 85 of file ParserMoveIt.cpp.

◆ getDescendantLinksOfJoint()

std::map< std::string, std::vector< const moveit::core::LinkModel *> > ROSEE::ParserMoveIt::getDescendantLinksOfJoint ( ) const

getter for descendandsLinksOfJoint. "Descendants" is intended in a slightly different way respect to moveit (see lookForDescendants doc)

Returns
map with keys the joint name and values a vector of pointer of all descendants links

Definition at line 81 of file ParserMoveIt.cpp.

◆ getFingerOfFingertip()

std::string ROSEE::ParserMoveIt::getFingerOfFingertip ( std::string  tipName) const

This function returns the name of the finger which the passed tipName belongs to.

Parameters
tipNamethe name of the tip
Returns
the name of the finger which the tip belongs to, empty string if the tipName is not in the map
Note
use getFingerOfFingertipMap to get the full map

Definition at line 109 of file ParserMoveIt.cpp.

◆ getFingerOfFingertipMap()

std::map< std::string, std::string > ROSEE::ParserMoveIt::getFingerOfFingertipMap ( ) const

Definition at line 105 of file ParserMoveIt.cpp.

◆ getFingertipNames()

std::vector< std::string > ROSEE::ParserMoveIt::getFingertipNames ( ) const

Definition at line 65 of file ParserMoveIt.cpp.

◆ getFingertipOfFinger()

std::string ROSEE::ParserMoveIt::getFingertipOfFinger ( std::string  fingerName) const

This function returns the name of the fingertip that belongs to the passed fingerName.

Parameters
fingerNamethe name of the tip
Returns
the name of the fingertip that belongs to the finger, empty string if the fingerName is not in the map
Note
use getFingertipOfFingerMap to get the full map

Definition at line 125 of file ParserMoveIt.cpp.

◆ getFingertipOfFingerMap()

std::map< std::string, std::string > ROSEE::ParserMoveIt::getFingertipOfFingerMap ( ) const

Definition at line 121 of file ParserMoveIt.cpp.

◆ getFingertipsOfJointMap()

std::map< std::string, std::vector< std::string > > ROSEE::ParserMoveIt::getFingertipsOfJointMap ( ) const

Definition at line 97 of file ParserMoveIt.cpp.

◆ getFirstActuatedJointInFinger()

std::string ROSEE::ParserMoveIt::getFirstActuatedJointInFinger ( std::string  linkName) const

Given the linkName, this function returns the actuated joint that is a parent of this link and it is the first joint of the chain which the link belongs to. E.G. given a fingertip, it returns the first actuated joint of the finger (e.g. the joint that moves the firsts phalanges, if present) From the linkName given, this function explores the parent links until we found a link with more than 1 child joint. This means that we have found the "base" of the kinematic chain, so we can go forward to find the first actuated joint.

Parameters
linkNamethe name of the link which is part of the chain where we have to look in
Returns
std::string the name of the wanted joint

Definition at line 409 of file ParserMoveIt.cpp.

◆ getFirstActuatedParentJoint()

std::string ROSEE::ParserMoveIt::getFirstActuatedParentJoint ( std::string  linkName,
bool  includeContinuos 
) const

starting from the given link, we explore the parents joint, until we found the first actuated. This ones will be the interesting joint

Parameters
linkNamethe name of the link for which look for the parent joint
includeContinuosa bool set to true if we want to include continuos joint in the search
Returns
std::string the name of the first actuated parent joint

Definition at line 379 of file ParserMoveIt.cpp.

◆ getGroupOfLink()

std::vector< std::string > ROSEE::ParserMoveIt::getGroupOfLink ( std::string  linkName)

This function explores all groups of srdf and says to which ones the linkName belongs to. Returns a vector because a link can be part of more group.

Parameters
linkNamethe name on the link for which look the group
Returns
std::vector < std::string > a vector containing the name of all the groups which contain the linkName

Definition at line 192 of file ParserMoveIt.cpp.

◆ getHandName()

std::string ROSEE::ParserMoveIt::getHandName ( ) const

Definition at line 61 of file ParserMoveIt.cpp.

◆ getJointsOfFingertipMap()

std::map< std::string, std::vector< std::string > > ROSEE::ParserMoveIt::getJointsOfFingertipMap ( ) const

Definition at line 101 of file ParserMoveIt.cpp.

◆ getMimicNLFatherOfJoint()

std::pair< std::string, std::string > ROSEE::ParserMoveIt::getMimicNLFatherOfJoint ( std::string  mimicNLJointName) const

gets for the maps of non linear mimic joints

Definition at line 137 of file ParserMoveIt.cpp.

◆ getMimicNLFatherOfJointMap()

std::map< std::string, std::pair< std::string, std::string > > ROSEE::ParserMoveIt::getMimicNLFatherOfJointMap ( ) const

Definition at line 149 of file ParserMoveIt.cpp.

◆ getMimicNLJointOfFather()

std::string ROSEE::ParserMoveIt::getMimicNLJointOfFather ( std::string  mimicNLFatherName,
std::string  mimicNLJointName 
) const

Definition at line 155 of file ParserMoveIt.cpp.

◆ getMimicNLJointsOfFather()

std::map< std::string, std::string > ROSEE::ParserMoveIt::getMimicNLJointsOfFather ( std::string  mimicNLFatherName) const

Definition at line 168 of file ParserMoveIt.cpp.

◆ getMimicNLJointsOfFatherMap()

std::map< std::string, std::map< std::string, std::string > > ROSEE::ParserMoveIt::getMimicNLJointsOfFatherMap ( ) const

Definition at line 180 of file ParserMoveIt.cpp.

◆ getNExclusiveJointsOfTip()

unsigned int ROSEE::ParserMoveIt::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 this fingertip and not any other fingertips (obviously the joints can affect different other links that are not fingertips (e.g. middles phalanges) )

Parameters
tipNamethe name of the fingertip link
continuosIncludeda bool set to true if we want to count also the possible present continuos joints
Returns
unsigned int the number of the exclusive joints

Definition at line 334 of file ParserMoveIt.cpp.

◆ getNFingers()

unsigned int ROSEE::ParserMoveIt::getNFingers ( ) const

Definition at line 89 of file ParserMoveIt.cpp.

◆ getPassiveJointNames()

std::vector< std::string > ROSEE::ParserMoveIt::getPassiveJointNames ( ) const

getter for all the passive joints (defined in this way in the srdf file) Not all the not-actuated joint are passive (a mimic joint can also be not defined as passive in srdf)

Returns
std::vector <std::string> string with names of all passive joints

Definition at line 77 of file ParserMoveIt.cpp.

◆ getRealDescendantLinkModelsRecursive()

void ROSEE::ParserMoveIt::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
private

Recursive function, support for lookForDescendants, to explore the urdf tree.

Parameters
linkpointer to the actual link that is being explored
linksVect[out] vector of explored links are stored here at each iteration
jointpointer to the actual joint thaqt is being explored (father of link, each joint has always one and only one (direct) child link)
jointsVect[out] vector of explored joints are stored here at each iteration

Definition at line 563 of file ParserMoveIt.cpp.

◆ getRobotModel()

const robot_model::RobotModelPtr ROSEE::ParserMoveIt::getRobotModel ( ) const

the robot model can't be modified, if you want it to modify, use getCopyModel to get a copy.

Returns
const robot_model::RobotModelPtr a shared pointer to the robot model

Definition at line 93 of file ParserMoveIt.cpp.

◆ getSmallerBoundFromZero() [1/2]

std::vector< double > ROSEE::ParserMoveIt::getSmallerBoundFromZero ( std::string  jointName) const

For each DOF of a joint, find the limit which is nearer from 0 position.

Parameters
jointNamethe name of the joint
Returns
std::vector<double> a vector (because joint can have more dofs) containing the values of the limits that are nearer from 0

Definition at line 304 of file ParserMoveIt.cpp.

◆ getSmallerBoundFromZero() [2/2]

std::vector< double > ROSEE::ParserMoveIt::getSmallerBoundFromZero ( const moveit::core::JointModel joint) const

For each DOF of a joint, find the limit which is nearer from 0 position.

Parameters
jointpointer to the joint model
Returns
std::vector<double> a vector (because joint can have more dofs) containing the values of the limits that are nearer from 0

Definition at line 314 of file ParserMoveIt.cpp.

◆ groupIsChain() [1/2]

bool ROSEE::ParserMoveIt::groupIsChain ( const std::string  groupName) const

check if a group (defined in srdf file) is a chain. See groupIsChain ( moveit::core::JointModelGroup* group )

Parameters
groupNamethe name of the group
Returns
bool : true is group is chain, false othwerwise (also false if some errors happened)

Definition at line 212 of file ParserMoveIt.cpp.

◆ groupIsChain() [2/2]

bool ROSEE::ParserMoveIt::groupIsChain ( const moveit::core::JointModelGroup group) const

check if a group (defined in srdf file) is a chain. This is done simply exploring all the links of the group: if no links have more than 1 children, the group is a chain. Moveit has a function isChain() but I don't understand how it works, in fact also if there is a link with more children joint sometimes the group is considered a chain anyway. I can't find where the moveit _is_chain member is set.

Parameters
grouppointer to moveit::core::JointModelGroup object
Returns
bool : true is group is chain, false othwerwise (also false if some errors happened)

Definition at line 228 of file ParserMoveIt.cpp.

◆ init()

bool ROSEE::ParserMoveIt::init ( std::string  robot_description,
bool  verbose = true 
)

Init the parser, fill the structures.

Parameters
robot_descriptiona string containing the name given to the param set in ROS server for the urdf file. The srdf file must have the same param name but with a trailing "_semantic"
verbosepass false to reduce the quantity of informative prints

Definition at line 27 of file ParserMoveIt.cpp.

◆ lookForActiveJoints()

void ROSEE::ParserMoveIt::lookForActiveJoints ( )
private

This function look for all active joints in the model (i.e. not mimic, not fixed, not passive) There exist a moveit function getActiveJointModels() which return all not mimic and not fixed, but it can return also passive joints (a info that is stored in srdf file). So this function also check if the joint is not passive It stores both the joint names and pointer to joint models in two private vector (activeJointNames and activeJointModels)

Definition at line 493 of file ParserMoveIt.cpp.

◆ lookForDescendants()

void ROSEE::ParserMoveIt::lookForDescendants ( )
private

Function to explore the kinematic tree from each actuated joint. It stores each descendants links and joints in two maps (descendantLinksOfJoint and descendantJointsOfJoint) where the key is the name of the joint and the value a vector of descendandts. The tree is explored recursively thanks to getRealDescendantLinkModelsRecursive support function.

Note
Moveit has its own getDescendantLinkModels and getDescendandtsJoint model but it not suitable for us: those one store also the sons of joints that mimic the sons joint of the initial one (the map's key). So in this way we include also some links that may not move when we move the joint. These "errors" happens with schunk, softhand and robotiq for example
The descendants are found only for the actuated joints (not fixed, not mimic, not passive).

Definition at line 540 of file ParserMoveIt.cpp.

◆ lookForFingertips()

void ROSEE::ParserMoveIt::lookForFingertips ( bool  verbose = true)
private

This function explore the robot_model (which was built from urdf and srdf files), and fills the fingerTipNames vector. In particular, the function explores only the groups specified in the srdf, and prints infos about each link it finds (eg. not a fingertin, not a chain group, and so on). A fingertip is a link with the following conditions:

  • It is part of a group (defined in the srdf)
  • The group which the tip is part of is a chain (not a tree)
  • It is the last link of the group AND has a mesh or some visual geometry (if not, it is probably a virtual link). If the second condition is not valid, it is taken the last link of the group that has a mesh (so it will not be a "leaf")
    Parameters
    verboseset it to false to not print explored hand info
    Warning
    Only link belonging to a group are explored (and printed), so other links (if present) are not considered

Definition at line 436 of file ParserMoveIt.cpp.

◆ lookForPassiveJoints()

void ROSEE::ParserMoveIt::lookForPassiveJoints ( )
private

This function looks for all passive joints, defined so in the srdf file.

Definition at line 504 of file ParserMoveIt.cpp.

◆ lookJointsTipsCorrelation()

void ROSEE::ParserMoveIt::lookJointsTipsCorrelation ( )
private

Here, we find for each tip, which are all the joints (active) that can modifies its position It is easier to start from each joint and see which tips has as its descendands, because there is the getDescendantLinkModels() function in moveit that gives ALL the child links. There is not a function like getNonFixedParentJointModels from the tip, there is only the one to take the FIRST parent joint (getParentJointModel()) Meanwhile, we find also, for each joint, all the tips that are influenced by the joint movement: fingertipsOfJointMap.

Definition at line 514 of file ParserMoveIt.cpp.

◆ parseNonLinearMimicRelations()

void ROSEE::ParserMoveIt::parseNonLinearMimicRelations ( std::string  xml)
Todo:
make docs as convention, in the equation there must exist only the variable x, that is, the position of the father joint

Definition at line 582 of file ParserMoveIt.cpp.

Member Data Documentation

◆ activeJointModels

std::vector<const moveit::core::JointModel*> ROSEE::ParserMoveIt::activeJointModels
private

Definition at line 256 of file ParserMoveIt.h.

◆ activeJointNames

std::vector<std::string> ROSEE::ParserMoveIt::activeJointNames
private

Definition at line 253 of file ParserMoveIt.h.

◆ descendantJointsOfJoint

std::map<std::string, std::vector < const moveit::core::JointModel* > > ROSEE::ParserMoveIt::descendantJointsOfJoint
private

Map containing info about descendants joints of a joint see lookForDescendants function for more info.

Definition at line 264 of file ParserMoveIt.h.

◆ descendantLinksOfJoint

std::map<std::string, std::vector < const moveit::core::LinkModel* > > ROSEE::ParserMoveIt::descendantLinksOfJoint
private

Map containing info about descendants links of a joint see lookForDescendants function for more info.

Definition at line 261 of file ParserMoveIt.h.

◆ fingerOfFingertipMap

std::map<std::string, std::string> ROSEE::ParserMoveIt::fingerOfFingertipMap
private

The map with as key the name of the finger (defined in srdf file) and as value the fingertip (the last (not virtual) link of the joint)

Definition at line 274 of file ParserMoveIt.h.

◆ fingertipNames

std::vector<std::string> ROSEE::ParserMoveIt::fingertipNames
private

Definition at line 252 of file ParserMoveIt.h.

◆ fingertipOfFingerMap

std::map<std::string, std::string> ROSEE::ParserMoveIt::fingertipOfFingerMap
private

The map with as key the name of the fingertip (the last (not virtual) link of a finger) and as value the finger name (defined in the srdf)

Definition at line 278 of file ParserMoveIt.h.

◆ fingertipsOfJointMap

std::map<std::string, std::vector<std::string> > ROSEE::ParserMoveIt::fingertipsOfJointMap
private

The map with as key the name of the actuated joint and as value all the fingertips which pose can be modified by the joint.

Definition at line 270 of file ParserMoveIt.h.

◆ handName

std::string ROSEE::ParserMoveIt::handName
private

Definition at line 250 of file ParserMoveIt.h.

◆ jointsOfFingertipMap

std::map<std::string, std::vector<std::string> > ROSEE::ParserMoveIt::jointsOfFingertipMap
private

The map with as key the name of the fingertip and as value all the joints (actuated) that can modify its pose.

Definition at line 267 of file ParserMoveIt.h.

◆ mimicNLFatherOfJointMap

std::map<std::string, std::pair<std::string, std::string> > ROSEE::ParserMoveIt::mimicNLFatherOfJointMap
private

This map contain as key the name of the mimic joint which position follows a non linear relationship with a father joint. As value there is a pair: first element is the name of the father joint, second element is the non linear equation.

as convention, in the equation there must exist only the variable x, that is, the position of the father joint

Definition at line 288 of file ParserMoveIt.h.

◆ mimicNLJointsOfFatherMap

std::map<std::string, std::map<std::string, std::string> > ROSEE::ParserMoveIt::mimicNLJointsOfFatherMap
private

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)

Definition at line 296 of file ParserMoveIt.h.

◆ nFingers

unsigned int ROSEE::ParserMoveIt::nFingers
private

Definition at line 258 of file ParserMoveIt.h.

◆ passiveJointNames

std::vector<std::string> ROSEE::ParserMoveIt::passiveJointNames
private

Definition at line 254 of file ParserMoveIt.h.

◆ robot_description

std::string ROSEE::ParserMoveIt::robot_description
private

Definition at line 257 of file ParserMoveIt.h.

◆ robot_model

robot_model::RobotModelPtr ROSEE::ParserMoveIt::robot_model
private

Definition at line 251 of file ParserMoveIt.h.


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


end-effector
Author(s): Luca Muratore , Davide Torielli , Liana Bertoni
autogenerated on Tue Apr 5 2022 02:57:53