ROSEndEffector
ROS End-Effector package: provides a ROS-based set of standard interfaces to command robotics end-effectors in an agnostic fashion.
EEInterface.cpp
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 
19 
21 
22  // get number of joints from parse and resize dynamic structure
24  _upper_limits.resize(_joints_num);
25  _lower_limits.resize(_joints_num);
26 
27  // get the EE name
29 
30  // get the ee description
32 
33  // get he joints urdf description
35 
36  int id = 0;
37 
38  // save the finger names
39  for( const auto& finger_joints_pair : _ee_description ) {
40 
41  // fingers
42  std::string finger_name = finger_joints_pair.first;
43  _fingers_names.push_back(finger_name);
44 
45  for( const auto& j : finger_joints_pair.second ) {
46 
47  // joint name
48  _actuated_joints.push_back(j);
49 
50  // internal id
52 
53  // finger internal id map
54  _finger_joints_internal_id_map[finger_name].push_back(id);
55 
56  // upper limits
57  _upper_limits[id] = _urdf_joint_map.at(j)->limits->upper;
58 
59  // lower limits
60  _lower_limits[id] = _urdf_joint_map.at(j)->limits->lower;
61 
62  // increase internal id
63  id++;
64  }
65  }
66 
67 }
68 
70 
71  return _ee_name;
72 }
73 
74 
76 
77  return _lower_limits;
78 }
79 
81 
82  return _upper_limits;
83 }
84 
85 bool ROSEE::EEInterface::getInternalIdForJoint ( std::string joint_name, int& internal_id ) {
86 
87  if ( _joints_internal_id_map.count(joint_name) ) {
88 
89  internal_id = _joints_internal_id_map.at(joint_name);
90  return true;
91  }
92 
93  return false;
94 
95 }
96 
97 
98 bool ROSEE::EEInterface::getInternalIdsForFinger ( std::string finger_name, std::vector< int >& internal_ids ) {
99 
100  if ( _finger_joints_internal_id_map.count(finger_name) ) {
101 
102  internal_ids = _finger_joints_internal_id_map.at(finger_name);
103  return true;
104  }
105 
106  return false;
107 
108 }
109 
110 const std::vector< std::string >& ROSEE::EEInterface::getFingers() {
111 
112  return _fingers_names;
113 }
114 
115 bool ROSEE::EEInterface::isFinger ( std::string finger_name ) {
116 
117  return ( _ee_description.count(finger_name) > 0 );
118 }
119 
120 
121 
122 const std::vector< std::string >& ROSEE::EEInterface::getActuatedJoints () {
123 
124  return _actuated_joints;
125 }
126 
127 
128 bool ROSEE::EEInterface::getActuatedJointsInFinger ( std::string finger_name, std::vector< std::string >& actuated_joints ) {
129 
130  if( !isFinger(finger_name) ) {
131 
132  return false;
133  }
134 
135  actuated_joints = _ee_description.at(finger_name);
136  return true;
137 }
138 
140 
141  return _joints_num;
142 }
143 
144 int ROSEE::EEInterface::getActuatedJointsNumInFinger ( std::string finger_name ) {
145 
146  if( !isFinger(finger_name) ) {
147 
148  return -1;
149  }
150 
151  return _ee_description.at(finger_name).size();
152 }
153 
155 
156  return _fingers_names.size();
157 }
158 
159 
161 
162 }
bool getInternalIdsForFinger(std::string finger_name, std::vector< int > &internal_ids)
getter for the internal ids (position in the EEInterface vectors) of joints in a certain finger ...
Definition: EEInterface.cpp:98
int getActuatedJointsNumber() const
getter for the total number of actuated joints in the configuration files
Definition: Parser.cpp:420
std::vector< std::string > _fingers_names
Definition: EEInterface.h:149
bool getActuatedJointsInFinger(std::string finger_name, std::vector< std::string > &actuated_joints)
getter for the actuated joints of a finger
std::vector< std::string > _actuated_joints
Definition: EEInterface.h:149
std::map< std::string, int > _joints_internal_id_map
Definition: EEInterface.h:147
std::string _ee_name
Definition: EEInterface.h:153
std::map< std::string, std::vector< std::string > > _ee_description
Definition: EEInterface.h:142
int getFingersNumber()
getter for the number of fingers in the End-Effector
std::string getEndEffectorName() const
getter for the configure End-Effector name
Definition: Parser.cpp:450
const std::vector< std::string > & getActuatedJoints()
getter for the actuated joints of the end-effector
std::string getName()
getter for the EE name
Definition: EEInterface.cpp:69
bool getInternalIdForJoint(std::string joint_name, int &internal_id)
getter for the internal id of a certain joint
Definition: EEInterface.cpp:85
virtual ~EEInterface()
int getActuatedJointsNum()
getter for the number of actuated joints in the end-effector
Eigen::VectorXd getUpperPositionLimits()
getter for the upper position limits of EE joints as specified in the URDF
Definition: EEInterface.cpp:80
bool isFinger(std::string finger_name)
check is the requested finger exists
const std::vector< std::string > & getFingers()
getter for the fingers name in the current End-Effector
Eigen::VectorXd getLowerPositionLimits()
getter for the lower position limits of EE joints as specified in the URDF
Definition: EEInterface.cpp:75
std::map< std::string, urdf::JointConstSharedPtr > _urdf_joint_map
Definition: EEInterface.h:143
int getActuatedJointsNumInFinger(std::string finger_name)
getter for the number of actuated joints in the requested finger
std::map< std::string, urdf::JointConstSharedPtr > getUrdfJointMap() const
getter for the URDF information of the joints of the End-Effector
Definition: Parser.cpp:435
Class responsible for parsing the YAML file providing the URDF, SRDF, the EE-HAL library implementati...
Definition: Parser.h:46
Eigen::VectorXd _lower_limits
Definition: EEInterface.h:151
Eigen::VectorXd _upper_limits
Definition: EEInterface.h:151
EEInterface(const ROSEE::Parser &p)
Definition: EEInterface.cpp:20
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
std::map< std::string, std::vector< int > > _finger_joints_internal_id_map
Definition: EEInterface.h:145