26 std::string motor_reference_topic =
"/ros_end_effector/motor_reference_pos";
31 std::string joint_state_topic =
"/ros_end_effector/joint_states";
49 return (_motor_reference_sub.getNumPublishers() > 0 && _mr_msg.name.size() != 0);
63 _joint_state_pub.publish(_js_msg);
71 if (this->fingers_names.size() != 0) {
73 fingers_names = this->fingers_names;
83 if (this->motors_names.size() != 0) {
85 motors_names = this->motors_names;
96 if (this->motors_stiffness.size() != 0) {
98 motors_stiffness = this->motors_stiffness;
109 if (this->tips_frictions.size() != 0) {
111 tips_frictions = this->tips_frictions;
122 if (this->motors_torque_limits.size() != 0) {
124 motors_torque_limits = this->motors_torque_limits;
135 if (this->tip_joint_to_tip_frame_x.size() != 0) {
137 tip_joint_to_tip_frame_x = this->tip_joint_to_tip_frame_x;
147 if (this->tip_joint_to_tip_frame_y.size() != 0) {
149 tip_joint_to_tip_frame_y = this->tip_joint_to_tip_frame_y;
159 std::string _rosee_config_path;
160 if (! _nh->getParam (
"/ros_ee_config_path", _rosee_config_path )) {
164 std::ifstream ifile(_rosee_config_path);
166 ROS_WARN_STREAM (
"EEHALExecutor: config file " << _rosee_config_path <<
" not found");
170 YAML::Node node = YAML::LoadFile(_rosee_config_path);
172 if (! node[
"hand_info"]) {
173 ROS_WARN_STREAM (
"EEHALExecutor: config file " << _rosee_config_path <<
" does not contain "
174 <<
"hand_info node. I will not parse hand information");
179 if(node[
"hand_info"][
"fingers_names"]){
181 fingers_names = node[
"hand_info"][
"fingers_names"].as<std::vector<std::string>>();
184 if(node[
"hand_info"][
"motors_names"]){
186 motors_names = node[
"hand_info"][
"motors_names"].as<std::vector<std::string>>();
189 if(node[
"hand_info"][
"motors_stiffness"]){
194 if(node[
"hand_info"][
"tips_frictions"]){
199 if(node[
"hand_info"][
"motors_torque_limits"]){
204 if(node[
"hand_info"][
"tip_joint_to_tip_frame_x"]){
209 if(node[
"hand_info"][
"tip_joint_to_tip_frame_y"]){
219 _hand_info_response.fingers_names = fingers_names;
221 _hand_info_response.motors_names = motors_names;
223 _hand_info_response.motors_stiffness =
226 _hand_info_response.tips_frictions =
229 _hand_info_response.motors_torque_limits =
237 _hand_info_server = _nh->advertiseService(_hand_info_service_name,
243 rosee_msg::HandInfo::Request& request,
244 rosee_msg::HandInfo::Response& response) {
256 std::string topic_name =
"/ros_end_effector/pressure_phalanges";
258 _pressure_pub = _nh->advertise<rosee_msg::MotorPhalangePressure>(topic_name, 10);
260 _pressure_active =
true;
268 _pressure_pub.publish(_pressure_msg);
276 Eigen::VectorXd motorRef;
277 motorRef.resize(_mr_msg.name.size());
278 for (
int i=0; i<_mr_msg.name.size(); i++ ) {
280 motorRef(i) = _mr_msg.position.at(i);
288 Eigen::VectorXd jointPos;
289 jointPos.resize(_js_msg.name.size());
290 for (
int i=0; i<_js_msg.name.size(); i++ ) {
292 jointPos(i) = _js_msg.position.at(i);
300 Eigen::VectorXd jointEffort;
301 jointEffort.resize(_js_msg.name.size());
302 for (
int i=0; i<_js_msg.name.size(); i++ ) {
304 jointEffort(i) = _js_msg.effort.at(i);
312 Eigen::MatrixXd pressure;
313 pressure.resize(4, _pressure_msg.pressure_finger1.size());
314 for (
int i=0; i<_pressure_msg.pressure_finger1.size(); i++ ) {
316 pressure(0, i) = _pressure_msg.pressure_finger1.at(i);
317 pressure(1, i) = _pressure_msg.pressure_finger2.at(i);
318 pressure(2, i) = _pressure_msg.pressure_finger3.at(i);
319 pressure(3, i) = _pressure_msg.pressure_thumb.at(i);