arm_finder.py
Go to the documentation of this file.
1 #!/usr/bin/env python
2 #
3 # Copyright 2015 Shadow Robot Company Ltd.
4 #
5 # This program is free software: you can redistribute it and/or modify it
6 # under the terms of the GNU General Public License as published by the Free
7 # Software Foundation, either version 2 of the License, or (at your option)
8 # any later version.
9 #
10 # This program is distributed in the hope that it will be useful, but WITHOUT
11 # ANY WARRANTY; without even the implied warranty of MERCHANTABILITY or
12 # FITNESS FOR A PARTICULAR PURPOSE. See the GNU General Public License for
13 # more details.
14 #
15 # You should have received a copy of the GNU General Public License along
16 # with this program. If not, see <http://www.gnu.org/licenses/>.
17 #
18 import rospy
19 from urdf_parser_py.urdf import URDF
20 from hand_finder import HandJoints
21 
22 
23 class ArmConfig(object):
24 
25  def __init__(self, mapping, joint_prefix):
26  """
27  Initializes arm configuration
28  """
29  self.mapping = mapping
30  self.joint_prefix = joint_prefix
31 
32 
33 class ArmFinder(object):
34  """
35  The ArmFinder is a utility library for detecting arms running on
36  the system. The idea is to make it easier to write generic code,
37  using this library to handle prefixes, joint prefixes etc...
38  """
39 
40  def __init__(self):
41  """
42  Parses the parameter server to extract the necessary information.
43  """
44  if not rospy.has_param("arm"):
45  rospy.logerr("No arm param defined.")
46  arm_parameters = {'joint_prefix': {}, 'mapping': {}}
47  else:
48  arm_parameters = rospy.get_param("arm")
49 
50  # TODO(@anyone): This parameter is never set. This script needs to be modified to find available
51  # arms from robot_description and present them appropriately. (sr_core issue #74)
52 
53  self.arm_config = ArmConfig(arm_parameters["mapping"], arm_parameters["joint_prefix"])
54  self.arm_joints = {}
55 
56  if rospy.has_param('robot_description'):
57 
58  robot_description = rospy.get_param('robot_description')
59  robot_urdf = URDF.from_xml_string(robot_description)
60 
61  hand_default_joints = HandJoints.get_default_joints()
62  possible_arm_joints = []
63 
64  for joint in robot_urdf.joints:
65  if joint.type != 'fixed' and joint.name not in hand_default_joints:
66  match_suffix = False
67  for hand_default_joint_name in hand_default_joints:
68  if joint.name.endswith('_' + hand_default_joint_name):
69  match_suffix = True
70  break
71 
72  if not match_suffix:
73  possible_arm_joints.append(joint.name)
74 
75  for arm_id, arm_mapping in self.arm_config.mapping.iteritems():
76  self.arm_joints[arm_mapping] = []
77  arm_joint_prefix = self.arm_config.joint_prefix[arm_id]
78  for joint_name in possible_arm_joints:
79  if joint_name.startswith(arm_joint_prefix):
80  self.arm_joints[arm_mapping].append(joint_name)
81  else:
82  rospy.logwarn("No robot_description found on parameter server. Assuming that there is no arm.")
83 
84  def get_arm_joints(self):
85  return self.arm_joints
86 
87  def get_arm_parameters(self):
88  return self.arm_config
def __init__(self, mapping, joint_prefix)
Definition: arm_finder.py:25


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