sr_hand_finder.cpp
Go to the documentation of this file.
1 /*
2 * Copyright 2015 Shadow Robot Company Ltd.
3 *
4 * This program is free software: you can redistribute it and/or modify it
5 * under the terms of the GNU General Public License as published by the Free
6 * Software Foundation version 2 of the License.
7 *
8 * This program is distributed in the hope that it will be useful, but WITHOUT
9 * ANY WARRANTY; without even the implied warranty of MERCHANTABILITY or
10 * FITNESS FOR A PARTICULAR PURPOSE. See the GNU General Public License for
11 * more details.
12 *
13 * You should have received a copy of the GNU General Public License along
14 * with this program. If not, see <http://www.gnu.org/licenses/>.
15 */
16 
17 /*
18 * File: sf_hand_finder.cpp
19 * Author: Vahid Aminzadeh <vahid@shadowrobot.com>
20 * @brief see README.md
21 */
22 
24 #include "urdf_parser/urdf_parser.h"
25 #include "urdf_model/model.h"
26 #include "urdf_model/joint.h"
27 #include <ros/package.h>
28 #include <boost/assign/list_of.hpp>
29 #include <boost/foreach.hpp>
30 #include <boost/shared_ptr.hpp>
31 #include <boost/algorithm/string/predicate.hpp>
32 #include <utility>
33 #include <map>
34 #include <set>
35 #include <vector>
36 #include <string>
37 #include <iostream>
38 
39 using boost::assign::list_of;
40 
41 namespace shadow_robot
42 {
43 const std::vector<std::string> SrHandFinder::joint_names_ = list_of("FFJ1")("FFJ2")("FFJ3")("FFJ4")("MFJ1")("MFJ2")(
44  "MFJ3")("MFJ4")("RFJ1")("RFJ2")("RFJ3")("RFJ4")("LFJ1")("LFJ2")("LFJ3")("LFJ4")("LFJ5")("THJ1")("THJ2")(
45  "THJ3")("THJ4")("THJ5")("WRJ1")("WRJ2");
46 
47 const std::vector<std::string> SrHandFinder::get_default_joints()
48 {
50 }
51 
53 {
54  return hand_config_;
55 }
56 
58 {
59  if (ros::param::has("/hand"))
60  {
61  std::map<std::string, std::string> mapping_map;
62  ros::param::get("/hand/mapping", hand_config_.mapping_);
63  ros::param::get("/hand/joint_prefix", hand_config_.joint_prefix_);
64 
65  std::pair<std::string, std::string> pair;
66  BOOST_FOREACH(pair, hand_config_.mapping_)
67  {
68  // hand empty mapping
69  if (pair.second.empty())
70  {
71  hand_config_.mapping_[pair.first] = pair.first;
72  ROS_INFO_STREAM("detected hands are \n" << "hand serial:" << pair.first << " hand_id:"
73  << pair.second << " , replaced internally by: " << pair.first);
74  }
75  else
76  ROS_INFO_STREAM("detected hands are \n" << "hand serial:" << pair.first << " hand_id:" << pair.second);
77  }
78 
82  }
83  else
84  {
85  ROS_ERROR_STREAM("No hand found");
86  }
87 }
88 
90 {
91  std::pair<std::string, std::string> hand;
92  if (ros::param::has("robot_description"))
93  {
94  std::set<std::string> hand_joints;
95 
96  BOOST_FOREACH(hand, hand_config_.joint_prefix_)
97  {
98  BOOST_FOREACH(std::string default_joint_name, joint_names_)
99  {
100  hand_joints.insert(hand.second + default_joint_name);
101  }
102  }
103  std::string robot_description;
104  ros::param::get("robot_description", robot_description);
105  const urdf::ModelInterfaceSharedPtr hand_urdf = urdf::parseURDF(robot_description);
106  BOOST_FOREACH(hand, hand_config_.joint_prefix_)
107  {
108  std::set<std::string> joints_tmp;
109  std::pair<std::string, urdf::JointSharedPtr> joint;
110  BOOST_FOREACH(joint, hand_urdf->joints_)
111  {
112  if (urdf::Joint::FIXED != joint.second->type)
113  {
114  const std::string joint_name = joint.first;
115  bool found_prefix = false;
116  std::pair<std::string, std::string> hand_prefix;
117  BOOST_FOREACH(hand_prefix, hand_config_.joint_prefix_)
118  {
119  if (boost::starts_with(joint_name, hand_prefix.second))
120  {
121  found_prefix = true;
122  }
123  }
124 
125  if (!found_prefix)
126  {
127  ROS_DEBUG_STREAM("Joint " + joint_name + "has invalid prefix");
128  }
129  else if (0 == joint_name.find(hand.second))
130  {
131  joints_tmp.insert(joint_name);
132  }
133  }
134  }
135 
136  std::set_intersection(joints_tmp.begin(), joints_tmp.end(), hand_joints.begin(), hand_joints.end(),
137  std::back_inserter(joints_[hand_config_.mapping_[hand.first]]));
138  }
139  }
140  else
141  {
142  ROS_WARN_STREAM("No robot_description found on parameter server. Joint names are loaded for 5 finger hand");
143  BOOST_FOREACH(hand, hand_config_.mapping_)
144  {
145  const std::string hand_mapping = hand.second;
146  BOOST_FOREACH(std::string default_joint_name, joint_names_)
147  {
148  joints_[hand_mapping].push_back(hand_config_.joint_prefix_[hand.first] + default_joint_name);
149  }
150  }
151  }
152 }
153 
155 {
156  std::string ethercat_path = ros::package::getPath("sr_ethercat_hand_config");
157  for (std::map<std::string, std::string>::const_iterator mapping_iter = hand_config_.mapping_.begin();
158  mapping_iter != hand_config_.mapping_.end(); ++mapping_iter)
159  {
160  calibration_path_[mapping_iter->second] = ethercat_path + "/calibrations/"
161  + mapping_iter->second + "/" + "calibration.yaml";
162  }
163 }
164 
166 {
167  std::string ethercat_path = ros::package::getPath("sr_ethercat_hand_config");
168  for (std::map<std::string, std::string>::const_iterator mapping_iter = hand_config_.mapping_.begin();
169  mapping_iter != hand_config_.mapping_.end(); ++mapping_iter)
170  {
171  hand_controller_tuning_.friction_compensation_[mapping_iter->second] =
172  ethercat_path + "/controls/" + "friction_compensation.yaml";
173  hand_controller_tuning_.motor_control_[mapping_iter->second] =
174  ethercat_path + "/controls/motors/" + mapping_iter->second + "/motor_board_effort_controllers.yaml";
175  std::string host_path(ethercat_path + "/controls/host/" + mapping_iter->second + "/");
176  hand_controller_tuning_.host_control_[mapping_iter->second].push_back(
177  host_path + "sr_edc_calibration_controllers.yaml");
178  hand_controller_tuning_.host_control_[mapping_iter->second].push_back(
179  host_path + "sr_edc_joint_velocity_controllers_PWM.yaml");
180  hand_controller_tuning_.host_control_[mapping_iter->second].push_back(
181  host_path + "sr_edc_effort_controllers_PWM.yaml");
182  hand_controller_tuning_.host_control_[mapping_iter->second].push_back(
183  host_path + "sr_edc_joint_velocity_controllers.yaml");
184  hand_controller_tuning_.host_control_[mapping_iter->second].push_back(
185  host_path + "sr_edc_effort_controllers.yaml");
186 
187  hand_controller_tuning_.host_control_[mapping_iter->second].push_back(
188  host_path + "sr_edc_mixed_position_velocity_joint_controllers_PWM.yaml");
189  hand_controller_tuning_.host_control_[mapping_iter->second].push_back(
190  host_path + "sr_edc_joint_position_controllers_PWM.yaml");
191  hand_controller_tuning_.host_control_[mapping_iter->second].push_back(
192  host_path + "sr_edc_mixed_position_velocity_joint_controllers.yaml");
193  hand_controller_tuning_.host_control_[mapping_iter->second].push_back(
194  host_path + "sr_edc_joint_position_controllers.yaml");
195  }
196 }
197 
198 std::map<std::string, std::vector<std::string> > SrHandFinder::get_joints()
199 {
200  return joints_;
201 }
202 
203 std::map<std::string, std::string> SrHandFinder::get_calibration_path()
204 {
205  return calibration_path_;
206 }
207 
209 {
211 }
212 } /* namespace shadow_robot */
HandControllerTuning get_hand_controller_tuning()
std::map< std::string, std::string > mapping_
std::map< std::string, std::vector< std::string > > host_control_
static const std::vector< std::string > get_default_joints()
HandControllerTuning hand_controller_tuning_
ROSCPP_DECL bool get(const std::string &key, std::string &s)
static const std::vector< std::string > joint_names_
ROSCPP_DECL bool has(const std::string &key)
std::map< std::string, std::string > get_calibration_path()
#define ROS_WARN_STREAM(args)
#define ROS_DEBUG_STREAM(args)
std::map< std::string, std::vector< std::string > > get_joints()
ROSLIB_DECL std::string getPath(const std::string &package_name)
std::map< std::string, std::string > motor_control_
#define ROS_INFO_STREAM(args)
std::map< std::string, std::string > friction_compensation_
#define ROS_ERROR_STREAM(args)
std::map< std::string, std::string > calibration_path_
std::map< std::string, std::string > joint_prefix_
std::map< std::string, std::vector< std::string > > joints_


sr_utilities
Author(s): Ugo Cupcic
autogenerated on Mon Feb 28 2022 23:52:19