20 #define CHAIN_PER_GROUP 1
34 std::string finger_name
40 _finger_joint_map.insert(std::make_pair(finger_name, std::vector<std::string>()));
43 KDL::Chain actual_chain;
44 if ( _robot_tree.getChain ( base_link, tip_link, actual_chain ) ) {
46 int segments_num = actual_chain.getNrOfSegments();
47 for (
int i = 0; i < segments_num; i++ ) {
49 KDL::Segment actual_segment = actual_chain.getSegment ( i );
50 KDL::Joint actual_joint = actual_segment.getJoint();
52 bool is_valid_joint =
false;
55 is_valid_joint = actual_joint.getTypeName() ==
"RotAxis";
59 auto urdf_joint = _urdf_model->getJoint(actual_joint.getName());
60 bool is_mimic_joint = (urdf_joint->mimic ==
nullptr) ?
false :
true;
64 if ( is_valid_joint && (!is_mimic_joint) ) {
66 _finger_joint_map[finger_name].push_back ( actual_joint.getName() );
67 _joint_finger_map[actual_joint.getName()] = finger_name;
68 _urdf_joint_map[actual_joint.getName()] = _urdf_model->getJoint ( actual_joint.getName() );
78 ROS_ERROR_STREAM (
"chain from base_link " << base_link <<
" to tip_link " << tip_link <<
" not found in the URDF" );
88 _srdfdom.initFile ( *_urdf_model, _srdf_path );
91 std::vector<srdf::Model::EndEffector> srdf_end_effectors = _srdfdom.getEndEffectors();
95 if ( srdf_end_effectors.size() != 1 ) {
100 ROS_INFO_STREAM (
"ros_end_effector Parser found end_effector: " << srdf_end_effectors.at ( 0 ).name_ );
103 std::vector<srdf::Model::Group> srdf_groups = _srdfdom.getGroups();
109 int group_num = srdf_groups.size();
111 std::string end_effector_group_name = srdf_end_effectors.at ( 0 ).component_group_;
112 for (
int i = 0; i < group_num; i++ ) {
113 if ( srdf_groups[i].name_ == end_effector_group_name ) {
114 fingers_group = srdf_groups[i];
115 ROS_INFO_STREAM (
"ros_end_effector Parser found group: " << end_effector_group_name <<
" in the SRDF with the following fingers: " );
119 _fingers_num = fingers_group.
subgroups_.size();
120 _fingers_names.resize ( _fingers_num );
121 _fingers_group_id.resize ( _fingers_num );
124 for (
int i = 0; i < _fingers_num; i++ ) {
126 _fingers_names[i] = fingers_group.
subgroups_[i];
129 for (
int j = 0; j < group_num; j++ ) {
130 if ( srdf_groups[j].name_ == _fingers_names[i] ) {
131 _fingers_group_id[i] = j;
138 for (
int i = 0; i < _fingers_num; i++ ) {
144 ROS_ERROR_STREAM (
"for the finger chain groups you can specify only one chain per group in your SRDF check " <<
145 current_finger_group.
name_.c_str() <<
" group" );
150 if ( !getJointsInFinger ( current_finger_group.
chains_[0].first,
151 current_finger_group.
chains_[0].second,
152 current_finger_group.
name_
158 addNotInFingerJoints();
160 removePassiveJoints();
163 std::ifstream t_srdf ( _srdf_path );
164 std::stringstream buffer_srdf;
165 buffer_srdf << t_srdf.rdbuf();
166 _srdf_string = buffer_srdf.str();
174 for (
auto it : _urdf_model->joints_) {
176 if (it.second->mimic ==
nullptr) {
178 if (it.second->type == urdf::Joint::CONTINUOUS ||
179 it.second->type == urdf::Joint::REVOLUTE ) {
182 if (_urdf_joint_map.find(it.second->name) == _urdf_joint_map.end() ) {
184 _urdf_joint_map.insert(std::make_pair(it.second->name, it.second));
185 _finger_joint_map[
"virtual_finger"].push_back ( it.second->name );
186 _joint_finger_map[it.second->name] =
"virtual_finger";
198 std::vector<srdf::Model::PassiveJoint> passiveJointList = _srdfdom.getPassiveJoints();
200 for (
auto passiveJoint : passiveJointList) {
202 if (_urdf_joint_map.erase(passiveJoint.name_) > 0) {
205 std::string fingerOfPassive = _joint_finger_map.at(passiveJoint.name_);
206 _joint_finger_map.erase(passiveJoint.name_);
208 for (
auto it = _finger_joint_map.at(fingerOfPassive).begin();
209 it!= _finger_joint_map.at(fingerOfPassive).end(); ++it){
211 if (it->compare(passiveJoint.name_) == 0 ) {
212 _finger_joint_map.at(fingerOfPassive).erase(it);
228 std::fstream xml_file ( _urdf_path.c_str(), std::fstream::in );
229 if ( xml_file.is_open() ) {
231 while ( xml_file.good() ) {
234 std::getline ( xml_file, line );
249 std::ifstream t_urdf ( _urdf_path );
250 std::stringstream buffer_urdf;
251 buffer_urdf << t_urdf.rdbuf();
252 _urdf_string = buffer_urdf.str();
258 ROS_ERROR_STREAM (
"in " << __func__ <<
" : Can NOT open " << _urdf_path <<
" !" );
335 ROS_INFO_STREAM (
"ROSEndEffector Parser successfully configured using urdf file: " << _urdf_path
336 <<
"\n\t srdf file: " << _srdf_path <<
"\n\t actions folder " << _action_path
365 if ( _nh.getParam (
"/urdf_path", _urdf_path ) &&
366 _nh.getParam (
"/srdf_path", _srdf_path ) &&
367 _nh.getParam (
"/actions_folder_path", _action_path )
370 _is_initialized = configure();
371 return _is_initialized;
375 ROS_ERROR_STREAM (
"in " << __func__ <<
" : '_urdf_path' and/or '_srdf_path' and/or 'actions_folder_path' not found on ROS parameter server" );
380 bool ROSEE::Parser::init (
const std::string& urdf_path,
const std::string& srdf_path,
const std::string& action_path ) {
382 _urdf_path = urdf_path;
383 _srdf_path = srdf_path;
384 _action_path = action_path;
386 _is_initialized = configure();
387 return _is_initialized;
392 if ( _is_initialized ) {
396 for (
auto& chain_joints: _finger_joint_map ) {
399 int nJointInFinger = chain_joints.second.size();
401 if ( nJointInFinger == 0 ) {
407 for (
int i = 0; i < nJointInFinger ; i++ ) {
416 ROS_ERROR_STREAM (
"in " << __func__ <<
" : ROSEE::Parser needs to be initialized. Call init() frist." );
427 return _finger_joint_map;
432 return _joint_finger_map;
437 return _urdf_joint_map;
442 finger_joint_map = _finger_joint_map;
447 joint_finger_map = _joint_finger_map;
452 return _urdf_model->getName();