24 #include "urdf_parser/urdf_parser.h" 25 #include "urdf_model/model.h" 26 #include "urdf_model/joint.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> 39 using boost::assign::list_of;
44 "MFJ3")(
"MFJ4")(
"RFJ1")(
"RFJ2")(
"RFJ3")(
"RFJ4")(
"LFJ1")(
"LFJ2")(
"LFJ3")(
"LFJ4")(
"LFJ5")(
"THJ1")(
"THJ2")(
45 "THJ3")(
"THJ4")(
"THJ5")(
"WRJ1")(
"WRJ2");
61 std::map<std::string, std::string> mapping_map;
65 std::pair<std::string, std::string> pair;
69 if (pair.second.empty())
72 ROS_INFO_STREAM(
"detected hands are \n" <<
"hand serial:" << pair.first <<
" hand_id:" 73 << pair.second <<
" , replaced internally by: " << pair.first);
76 ROS_INFO_STREAM(
"detected hands are \n" <<
"hand serial:" << pair.first <<
" hand_id:" << pair.second);
91 std::pair<std::string, std::string> hand;
94 std::set<std::string> hand_joints;
98 BOOST_FOREACH(std::string default_joint_name,
joint_names_)
100 hand_joints.insert(hand.second + default_joint_name);
103 std::string robot_description;
105 const urdf::ModelInterfaceSharedPtr hand_urdf = urdf::parseURDF(robot_description);
108 std::set<std::string> joints_tmp;
109 std::pair<std::string, urdf::JointSharedPtr> joint;
110 BOOST_FOREACH(joint, hand_urdf->joints_)
112 if (urdf::Joint::FIXED != joint.second->type)
114 const std::string joint_name = joint.first;
115 bool found_prefix =
false;
116 std::pair<std::string, std::string> hand_prefix;
119 if (boost::starts_with(joint_name, hand_prefix.second))
129 else if (0 == joint_name.find(hand.second))
131 joints_tmp.insert(joint_name);
136 std::set_intersection(joints_tmp.begin(), joints_tmp.end(), hand_joints.begin(), hand_joints.end(),
142 ROS_WARN_STREAM(
"No robot_description found on parameter server. Joint names are loaded for 5 finger hand");
145 const std::string hand_mapping = hand.second;
146 BOOST_FOREACH(std::string default_joint_name,
joint_names_)
157 for (std::map<std::string, std::string>::const_iterator mapping_iter =
hand_config_.
mapping_.begin();
161 + mapping_iter->second +
"/" +
"calibration.yaml";
168 for (std::map<std::string, std::string>::const_iterator mapping_iter =
hand_config_.
mapping_.begin();
172 ethercat_path +
"/controls/" +
"friction_compensation.yaml";
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 +
"/");
177 host_path +
"sr_edc_calibration_controllers.yaml");
179 host_path +
"sr_edc_joint_velocity_controllers_PWM.yaml");
181 host_path +
"sr_edc_effort_controllers_PWM.yaml");
183 host_path +
"sr_edc_joint_velocity_controllers.yaml");
185 host_path +
"sr_edc_effort_controllers.yaml");
188 host_path +
"sr_edc_mixed_position_velocity_joint_controllers_PWM.yaml");
190 host_path +
"sr_edc_joint_position_controllers_PWM.yaml");
192 host_path +
"sr_edc_mixed_position_velocity_joint_controllers.yaml");
194 host_path +
"sr_edc_joint_position_controllers.yaml");
void generate_joints_with_prefix()
void generate_hand_controller_tuning_path()
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_
void generate_calibration_path()
ROSCPP_DECL bool get(const std::string &key, std::string &s)
static const std::vector< std::string > joint_names_
HandConfig get_hand_parameters()
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_