ROSEndEffector
ROS End-Effector package: provides a ROS-based set of standard interfaces to command robotics end-effectors in an agnostic fashion.
ParserMoveIt.h
Go to the documentation of this file.
1 /*
2  * Copyright 2020 <copyright holder> <email>
3  *
4  * Licensed under the Apache License, Version 2.0 (the "License");
5  * you may not use this file except in compliance with the License.
6  * You may obtain a copy of the License at
7  *
8  * http://www.apache.org/licenses/LICENSE-2.0
9  *
10  * Unless required by applicable law or agreed to in writing, software
11  * distributed under the License is distributed on an "AS IS" BASIS,
12  * WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.
13  * See the License for the specific language governing permissions and
14  * limitations under the License.
15  */
16 
17 #ifndef __ROSEE_PARSER_MOVEIT_H
18 #define __ROSEE_PARSER_MOVEIT_H
19 
20 #include <string>
21 #include <vector>
22 #include <map>
23 #include <iostream>
24 
25 #include <moveit/robot_model_loader/robot_model_loader.h>
26 
27 //parse customized urdf with non linear mimic
28 #include <tinyxml.h>
29 
30 
31 namespace ROSEE {
36 class ParserMoveIt {
37 
38 public:
39 
40  typedef std::shared_ptr<ParserMoveIt> Ptr;
41  typedef std::shared_ptr<const ParserMoveIt> ConstPtr;
42 
43  ParserMoveIt();
44  ~ParserMoveIt();
45 
54  bool init (std::string robot_description, bool verbose = true) ;
55  std::string getHandName () const;
56  unsigned int getNFingers () const ;
57  std::vector <std::string> getFingertipNames () const;
58 
63  std::vector <std::string> getActiveJointNames () const;
64 
69  std::vector <const moveit::core::JointModel*> getActiveJointModels () const;
70 
77  std::vector <std::string> getPassiveJointNames () const;
78 
84  std::map <std::string, std::vector < const moveit::core::LinkModel* > > getDescendantLinksOfJoint() const ;
85 
91  std::map <std::string, std::vector < const moveit::core::JointModel* > > getDescendantJointsOfJoint() const ;
92 
98  const robot_model::RobotModelPtr getRobotModel () const ;
99 
100  std::map < std::string, std::vector<std::string> > getFingertipsOfJointMap () const;
101  std::map < std::string, std::vector<std::string> > getJointsOfFingertipMap () const;
102  std::map < std::string, std::string > getFingerOfFingertipMap () const;
103  std::map < std::string, std::string > getFingertipOfFingerMap () const;
104 
113  std::string getFingerOfFingertip (std::string tipName) const;
114 
122  std::string getFingertipOfFinger (std::string fingerName) const;
123 
124 
130  robot_model::RobotModelPtr getCopyModel ( ) const;
131 
138  std::vector < std::string > getGroupOfLink ( std::string linkName );
139 
145  bool groupIsChain ( const std::string groupName ) const;
146 
156  bool groupIsChain ( const moveit::core::JointModelGroup* group ) const;
157 
163  bool checkIfContinuosJoint ( const std::string jointName) const;
169  bool checkIfContinuosJoint ( const moveit::core::JointModel* joint ) const;
170 
176  std::vector<double> getBiggerBoundFromZero ( std::string jointName ) const;
182  std::vector<double> getBiggerBoundFromZero ( const moveit::core::JointModel* joint ) const;
183 
189  std::vector<double> getSmallerBoundFromZero ( std::string jointName ) const;
195  std::vector<double> getSmallerBoundFromZero ( const moveit::core::JointModel* joint ) const;
196 
206  unsigned int getNExclusiveJointsOfTip (std::string tipName, bool continuosIncluded) const;
207 
215  std::string getFirstActuatedParentJoint ( std::string linkName, bool includeContinuos ) const;
216 
227  std::string getFirstActuatedJointInFinger (std::string linkName) const ;
228 
234  void parseNonLinearMimicRelations(std::string xml);
235 
240  std::pair<std::string, std::string> getMimicNLFatherOfJoint(std::string mimicNLJointName) const;
241  std::map<std::string, std::pair<std::string, std::string>> getMimicNLFatherOfJointMap() const;
242 
243  std::string getMimicNLJointOfFather(std::string mimicNLFatherName, std::string mimicNLJointName) const;
244  std::map<std::string, std::string> getMimicNLJointsOfFather(std::string mimicNLFatherName) const;
245  std::map<std::string, std::map<std::string, std::string>> getMimicNLJointsOfFatherMap() const;
246 
247 
248 private:
249 
250  std::string handName;
251  robot_model::RobotModelPtr robot_model;
252  std::vector<std::string> fingertipNames;
253  std::vector<std::string> activeJointNames;
254  std::vector<std::string> passiveJointNames;
255 
256  std::vector<const moveit::core::JointModel*> activeJointModels;
257  std::string robot_description;
258  unsigned int nFingers;
259 
261  std::map <std::string, std::vector < const moveit::core::LinkModel* > > descendantLinksOfJoint;
262 
264  std::map <std::string, std::vector < const moveit::core::JointModel* > > descendantJointsOfJoint;
265 
267  std::map<std::string, std::vector<std::string>> jointsOfFingertipMap;
268 
270  std::map<std::string, std::vector<std::string>> fingertipsOfJointMap;
271 
274  std::map<std::string, std::string> fingerOfFingertipMap;
275 
278  std::map<std::string, std::string> fingertipOfFingerMap;
279 
288  std::map<std::string, std::pair<std::string, std::string>> mimicNLFatherOfJointMap;
289 
296  std::map<std::string, std::map<std::string, std::string>> mimicNLJointsOfFatherMap;
297 
298 
314  void lookForFingertips(bool verbose = true);
315 
316 
323  void lookForActiveJoints();
324 
325 
330  void lookForPassiveJoints();
331 
332 
343 
353  void lookForDescendants();
354 
362  void getRealDescendantLinkModelsRecursive ( const moveit::core::LinkModel* link, std::vector< const moveit::core::LinkModel* > & linksVect,
363  const moveit::core::JointModel* joint, std::vector< const moveit::core::JointModel* > & jointsVect ) const;
364 
365 
366 
367 
368 
369 
370 };
371 
372 } //namespace
373 
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
Definition: ParserMoveIt.h:253
std::vector< std::string > fingertipNames
Definition: ParserMoveIt.h:252
std::vector< std::string > getGroupOfLink(std::string linkName)
This function explores all groups of srdf and says to which ones the linkName belongs to...
unsigned int nFingers
Definition: ParserMoveIt.h:258
std::map< std::string, std::string > getMimicNLJointsOfFather(std::string mimicNLFatherName) const
const robot_model::RobotModelPtr getRobotModel() const
the robot model can&#39;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&#39; 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
Definition: ParserMoveIt.h:40
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...
Definition: ParserMoveIt.h:274
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 ...
Definition: ParserMoveIt.h:278
std::vector< const moveit::core::JointModel * > activeJointModels
Definition: ParserMoveIt.h:256
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
Definition: ParserMoveIt.h:251
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 ...
Definition: ParserMoveIt.h:288
std::shared_ptr< const ParserMoveIt > ConstPtr
Definition: ParserMoveIt.h:41
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.
Definition: ParserMoveIt.h:296
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 ...
Definition: ParserMoveIt.h:270
std::vector< std::string > passiveJointNames
Definition: ParserMoveIt.h:254
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...
Definition: ParserMoveIt.h:264
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...
Definition: ParserMoveIt.h:261
void parseNonLinearMimicRelations(std::string xml)
class to parse urdf and srdf with moveit classes and to give information about the model parsed ...
Definition: ParserMoveIt.h:36
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 ...
Definition: ParserMoveIt.h:267
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
Definition: ParserMoveIt.h:257
std::vector< std::string > getFingertipNames() const
std::string handName
Definition: ParserMoveIt.h:250