Parser.h
Go to the documentation of this file.
1 /*
2  * Copyright (C) 2019 IIT-HHCM
3  * Author: Luca Muratore
4  * email: luca.muratore@iit.it
5  *
6  * Licensed under the Apache License, Version 2.0 (the "License");
7  * you may not use this file except in compliance with the License.
8  * You may obtain a copy of the License at
9  * http://www.apache.org/licenses/LICENSE-2.0
10  *
11  * Unless required by applicable law or agreed to in writing, software
12  * distributed under the License is distributed on an "AS IS" BASIS,
13  * WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.
14  * See the License for the specific language governing permissions and
15  * limitations under the License.
16 */
17 
18 #ifndef __ROSEE_PARSER__
19 #define __ROSEE_PARSER__
20 
21 
22 #include <iostream>
23 #include <fstream>
24 #include <memory>
25 
26 #include <ros/ros.h>
27 #include <ros/console.h>
28 
29 #include <end_effector/Utils.h>
30 
31 #include <yaml-cpp/yaml.h>
32 #include <urdf_parser/urdf_parser.h>
34 #include <srdfdom/model.h>
35 
36 //to find relative path for the config files
37 #include <boost/filesystem/path.hpp>
38 
39 namespace ROSEE {
40 
46  class Parser {
47 
48  public:
49 
50  typedef std::shared_ptr<Parser> Ptr;
51  typedef std::shared_ptr<const Parser> ConstPtr;
52 
53  Parser( const ros::NodeHandle& nh );
54  //Parser ( const Parser& other );
55  //Parser& operator= ( const Parser& p );
56  virtual ~Parser();
57 
63  bool init ();
64 
73  bool init (const std::string& urdf_path, const std::string& srdf_path, const std::string& action_path );
74 
75 
81  std::map<std::string, urdf::JointConstSharedPtr> getUrdfJointMap() const;
82 
90  std::map<std::string, std::vector<std::string>> getFingerJointMap() const;
91 
98  void getFingerJointMap(std::map<std::string, std::vector<std::string>>& finger_joint_map) const;
99 
107  std::map<std::string, std::string> getJointFingerMap() const;
108 
117  void getJointFingerMap(std::map<std::string, std::string>& joint_finger_map) const;
118 
124  std::string getEndEffectorName() const;
125 
131  int getActuatedJointsNumber() const;
132 
138  void printEndEffectorFingerJointsMap() const;
139 
145  std::string getUrdfString() const;
146 
152  std::string getSrdfString() const;
153 
159  std::string getActionPath() const;
160 
167  std::string getRoseeConfigPath() const;
168 
169  private:
170 
173  std::string _action_path;
174  bool _is_initialized = false;
175 
176  urdf::ModelInterfaceSharedPtr _urdf_model;
177  KDL::Tree _robot_tree;
178 
180 
181  int _fingers_num = 0;
182  std::vector<std::string> _fingers_names;
183  std::vector<int> _fingers_group_id;
184 
185  int _joints_num = 0;
186 
187  std::map<std::string, std::vector<std::string>> _finger_joint_map;
188  std::map<std::string, std::string> _joint_finger_map;
189  std::map<std::string, urdf::JointConstSharedPtr> _urdf_joint_map;
190 
191 
197  bool configure();
198 
207  //bool getROSEndEffectorConfig();
208 
214  bool parseURDF();
215 
221  bool parseSRDF();
222 
226  void addNotInFingerJoints();
227 
233  bool removePassiveJoints();
234 
243  bool getJointsInFinger(std::string base_link, std::string tip_link, std::string finger_name);
244 
245 
246  };
247 }
248 
249 #endif // __ROSEE_PARSER__
ROSEE::Parser::_finger_joint_map
std::map< std::string, std::vector< std::string > > _finger_joint_map
Definition: Parser.h:187
ROSEE::Parser::_joint_finger_map
std::map< std::string, std::string > _joint_finger_map
Definition: Parser.h:188
ROSEE::Parser::getEndEffectorName
std::string getEndEffectorName() const
getter for the configure End-Effector name
Definition: Parser.cpp:450
ROSEE::Parser::addNotInFingerJoints
void addNotInFingerJoints()
Definition: Parser.cpp:172
ROSEE::Parser::removePassiveJoints
bool removePassiveJoints()
Function to remove the passive joints from the filled maps.
Definition: Parser.cpp:196
ROSEE::Parser::_fingers_group_id
std::vector< int > _fingers_group_id
Definition: Parser.h:183
ros.h
ROSEE
Definition: EEInterface.h:30
ROSEE::Parser::getUrdfJointMap
std::map< std::string, urdf::JointConstSharedPtr > getUrdfJointMap() const
getter for the URDF information of the joints of the End-Effector
Definition: Parser.cpp:435
ROSEE::Parser::ConstPtr
std::shared_ptr< const Parser > ConstPtr
Definition: Parser.h:51
ROSEE::Parser::getJointFingerMap
std::map< std::string, std::string > getJointFingerMap() const
getter for a description of the End-Effector as a map of joint name, finger name
Definition: Parser.cpp:430
ROSEE::Parser::_fingers_num
int _fingers_num
Definition: Parser.h:181
console.h
ROSEE::Parser::getFingerJointMap
std::map< std::string, std::vector< std::string > > getFingerJointMap() const
getter for a description of the End-Effector as a map of finger name, finger joint names....
Definition: Parser.cpp:425
Utils.h
ROSEE::Parser::_joints_num
int _joints_num
Definition: Parser.h:185
ROSEE::Parser::_urdf_path
std::string _urdf_path
Definition: Parser.h:172
ROSEE::Parser::getSrdfString
std::string getSrdfString() const
get the whole srdf file parsed as a string
Definition: Parser.cpp:459
model.h
ROSEE::Parser::_fingers_names
std::vector< std::string > _fingers_names
Definition: Parser.h:182
ROSEE::Parser::_urdf_joint_map
std::map< std::string, urdf::JointConstSharedPtr > _urdf_joint_map
Definition: Parser.h:189
ROSEE::Parser::parseSRDF
bool parseSRDF()
Function responsible to parse the SRDF data.
Definition: Parser.cpp:85
ROSEE::Parser::getJointsInFinger
bool getJointsInFinger(std::string base_link, std::string tip_link, std::string finger_name)
fill a data structure related with the revolute/prismatic joints included in between base_link and ti...
Definition: Parser.cpp:32
ROSEE::Parser::_nh
ros::NodeHandle _nh
Definition: Parser.h:171
ROSEE::Parser::_urdf_model
urdf::ModelInterfaceSharedPtr _urdf_model
Definition: Parser.h:176
ROSEE::Parser::_robot_tree
KDL::Tree _robot_tree
Definition: Parser.h:177
ROSEE::Parser::getActionPath
std::string getActionPath() const
get the path where emit and parse grasping actions
Definition: Parser.cpp:464
ROSEE::Parser::Ptr
std::shared_ptr< Parser > Ptr
Definition: Parser.h:50
ROSEE::Parser::Parser
Parser(const ros::NodeHandle &nh)
Definition: Parser.cpp:22
kdl_parser.hpp
ROSEE::Parser::_urdf_string
std::string _urdf_string
Definition: Parser.h:172
ROSEE::Parser::getUrdfString
std::string getUrdfString() const
get the whole urdf file parsed as a string
Definition: Parser.cpp:455
ROSEE::Parser::~Parser
virtual ~Parser()
Definition: Parser.cpp:28
ROSEE::Parser::_srdfdom
srdf::Model _srdfdom
Definition: Parser.h:179
ROSEE::Parser::_srdf_string
std::string _srdf_string
Definition: Parser.h:172
ROSEE::Parser::init
bool init()
Initialization function using the ROS param ROSEEConfigPath.
Definition: Parser.cpp:362
ROSEE::Parser::_is_initialized
bool _is_initialized
Definition: Parser.h:174
ROSEE::Parser::_action_path
std::string _action_path
Definition: Parser.h:173
ROSEE::Parser::printEndEffectorFingerJointsMap
void printEndEffectorFingerJointsMap() const
Utility to print the mapping between the End Effector finger chains and the related actuated joints.
Definition: Parser.cpp:390
ROSEE::Parser::configure
bool configure()
configure the ROSEE parser based on the configration files requested
Definition: Parser.cpp:326
ROSEE::Parser::getRoseeConfigPath
std::string getRoseeConfigPath() const
get the filename (with path) of the yaml config file. Useful get to print infos about file parsed out...
ROSEE::Parser::getActuatedJointsNumber
int getActuatedJointsNumber() const
getter for the total number of actuated joints in the configuration files
Definition: Parser.cpp:420
ROSEE::Parser::parseURDF
bool parseURDF()
Function responsible to get the file needed to fill the internal data structure of the Parser with da...
Definition: Parser.cpp:225
ROSEE::Parser
Class responsible for parsing the YAML file providing the URDF, SRDF, the EE-HAL library implementati...
Definition: Parser.h:46
srdf::Model
ROSEE::Parser::_srdf_path
std::string _srdf_path
Definition: Parser.h:172
ros::NodeHandle


end-effector
Author(s): Luca Muratore , Davide Torielli , Liana Bertoni
autogenerated on Sat Dec 14 2024 03:49:26