sr_arm_finder.cpp
Go to the documentation of this file.
1 /*
2 * File: sf_arm_finder.cpp
3 * Author: Andriy Petlovanyy <andriy@shadowrobot.com>
4 * Copyright 2015 Shadow Robot Company Ltd.
5 *
6 * This program is free software: you can redistribute it and/or modify it
7 * under the terms of the GNU General Public License as published by the Free
8 * Software Foundation, either version 2 of the License, or (at your option)
9 * any later version.
10 *
11 * This program is distributed in the hope that it will be useful, but WITHOUT
12 * ANY WARRANTY; without even the implied warranty of MERCHANTABILITY or
13 * FITNESS FOR A PARTICULAR PURPOSE. See the GNU General Public License for
14 * more details.
15 *
16 * You should have received a copy of the GNU General Public License along
17 * with this program. If not, see <http://www.gnu.org/licenses/>.
18 *
19 * @brief see README.md
20 */
21 
24 #include "urdf_parser/urdf_parser.h"
25 #include "urdf_model/model.h"
26 #include "urdf_model/joint.h"
27 #include <boost/foreach.hpp>
28 #include <boost/algorithm/string/predicate.hpp>
29 #include <map>
30 #include <set>
31 #include <utility>
32 #include <vector>
33 #include <string>
34 
35 using urdf::ModelInterface;
36 using urdf::Joint;
37 
38 namespace shadow_robot
39 {
41 {
42  if (ros::param::has("arm"))
43  {
44  ros::param::get("arm/mapping", arm_config_.mapping_);
45  ros::param::get("arm/joint_prefix", arm_config_.joint_prefix_);
46 
47  if (ros::param::has("robot_description"))
48  {
49  const std::vector<std::string> default_hand_joints_vector = SrHandFinder::get_default_joints();
50  const std::set<std::string> hand_default_joints(default_hand_joints_vector.begin(),
51  default_hand_joints_vector.end());
52  std::string robot_description;
53  ros::param::get("robot_description", robot_description);
54  const boost::shared_ptr<ModelInterface> hand_urdf = urdf::parseURDF(robot_description);
55 
56  std::pair<std::string, boost::shared_ptr<Joint> > joint;
57  BOOST_FOREACH(joint, hand_urdf->joints_)
58  {
59  const std::string joint_name = joint.first;
60  if ((Joint::FIXED != joint.second->type) && (hand_default_joints.end() == hand_default_joints.find(joint_name)))
61  {
62  bool found_suffix = false;
63  BOOST_FOREACH(std::string default_joint_name, hand_default_joints)
64  {
65  if (boost::ends_with(joint_name, default_joint_name))
66  {
67  found_suffix = true;
68  break;
69  }
70  }
71 
72  if (!found_suffix)
73  {
74  std::pair<std::string, std::string> hand;
75  BOOST_FOREACH(hand, arm_config_.mapping_)
76  {
77  const std::string hand_serial = hand.first;
78  const std::string hand_id = hand.second;
79 
80  if ((arm_config_.joint_prefix_.count(hand_serial) > 0) &&
81  boost::starts_with(joint_name, arm_config_.joint_prefix_[hand_serial]))
82  {
83  joints_[hand_id].push_back(joint_name);
84  }
85  }
86  }
87  }
88  }
89  }
90  else
91  {
92  ROS_WARN_STREAM("No robot_description found on parameter server. Assuming that there is no arm.");
93  }
94  }
95  else
96  {
97  ROS_ERROR_STREAM("No arm is detected");
98  }
99 }
100 
102 {
103  return arm_config_;
104 }
105 
106 std::map<std::string, std::vector<std::string> > SrArmFinder::get_joints()
107 {
108  return joints_;
109 }
110 
111 } /* namespace shadow_robot */
std::map< std::string, std::string > joint_prefix_
static const std::vector< std::string > get_default_joints()
ROSCPP_DECL bool get(const std::string &key, std::string &s)
ROSCPP_DECL bool has(const std::string &key)
#define ROS_WARN_STREAM(args)
std::map< std::string, std::string > mapping_
std::map< std::string, std::vector< std::string > > joints_
#define ROS_ERROR_STREAM(args)
std::map< std::string, std::vector< std::string > > get_joints()


sr_utilities
Author(s): Ugo Cupcic
autogenerated on Tue Oct 13 2020 03:55:49