8 xmlr.start_namespace(
'urdf')
    10 xmlr.add_type(
'element_link', xmlr.SimpleElementType(
'link', str))
    11 xmlr.add_type(
'element_xyz', xmlr.SimpleElementType(
'xyz', 
'vector3'))
    22         assert (self.
xyz is None or len(self.
xyz) == 3) 
and \
    23             (self.
rpy is None or len(self.
rpy) == 3)
    39 xmlr.reflect(Pose, params=[
    40     xmlr.Attribute(
'xyz', 
'vector3', 
False, default=[0, 0, 0]),
    41     xmlr.Attribute(
'rpy', 
'vector3', 
False, default=[0, 0, 0])
    46 name_attribute = xmlr.Attribute(
'name', str)
    47 origin_element = xmlr.Element(
'origin', Pose, 
False)
    54         if count == 4 
or count == 3:
    60         if self.
rgba is not None:
    61             if len(self.
rgba) == 3:
    63             if len(self.
rgba) != 4:
    64                 raise Exception(
'Invalid color argument count')
    67 xmlr.reflect(Color, params=[
    68     xmlr.Attribute(
'rgba', 
'vector4')
    73     def __init__(self, damping=None, friction=None):
    78 xmlr.reflect(JointDynamics, params=[
    79     xmlr.Attribute(
'damping', float, 
False),
    80     xmlr.Attribute(
'friction', float, 
False)
    84 class Box(xmlr.Object):
    89 xmlr.reflect(Box, params=[
    90     xmlr.Attribute(
'size', 
'vector3')
   100 xmlr.reflect(Cylinder, params=[
   101     xmlr.Attribute(
'radius', float),
   102     xmlr.Attribute(
'length', float)
   111 xmlr.reflect(Sphere, params=[
   112     xmlr.Attribute(
'radius', float)
   122 xmlr.reflect(Mesh, params=[
   123     xmlr.Attribute(
'filename', str),
   124     xmlr.Attribute(
'scale', 
'vector3', required=
False)
   130         self.
factory = xmlr.FactoryType(
'geometric', {
   132             'cylinder': Cylinder,
   139         assert len(children) == 1, 
'One element only for geometric'   140         return self.factory.from_xml(children[0])
   143         name = self.factory.get_name(obj)
   157 xmlr.reflect(Collision, params=[
   159     xmlr.Element(
'geometry', 
'geometric')
   168 xmlr.reflect(Texture, params=[
   169     xmlr.Attribute(
'filename', str)
   174     def __init__(self, name=None, color=None, texture=None):
   181             xmlr.on_error(
"Material has neither a color nor texture.")
   184 xmlr.reflect(Material, params=[
   186     xmlr.Element(
'color', Color, 
False),
   187     xmlr.Element(
'texture', Texture, 
False)
   196 class Visual(xmlr.Object):
   197     def __init__(self, geometry=None, material=None, origin=None):
   203 xmlr.reflect(Visual, params=[
   205     xmlr.Element(
'geometry', 
'geometric'),
   206     xmlr.Element(
'material', LinkMaterial, 
False)
   211     KEYS = [
'ixx', 
'ixy', 
'ixz', 
'iyy', 
'iyz', 
'izz']
   213     def __init__(self, ixx=0.0, ixy=0.0, ixz=0.0, iyy=0.0, iyz=0.0, izz=0.0):
   228 xmlr.reflect(Inertia,
   229              params=[xmlr.Attribute(key, float) 
for key 
in Inertia.KEYS])
   233     def __init__(self, mass=0.0, inertia=None, origin=None):
   239 xmlr.reflect(Inertial, params=[
   241     xmlr.Element(
'mass', 
'element_value'),
   242     xmlr.Element(
'inertia', Inertia, 
False)
   253 xmlr.reflect(JointCalibration, params=[
   254     xmlr.Attribute(
'rising', float, 
False, 0),
   255     xmlr.Attribute(
'falling', float, 
False, 0)
   260     def __init__(self, effort=None, velocity=None, lower=None, upper=None):
   267 xmlr.reflect(JointLimit, params=[
   268     xmlr.Attribute(
'effort', float),
   269     xmlr.Attribute(
'lower', float, 
False, 0),
   270     xmlr.Attribute(
'upper', float, 
False, 0),
   271     xmlr.Attribute(
'velocity', float)
   278     def __init__(self, joint_name=None, multiplier=None, offset=None):
   284 xmlr.reflect(JointMimic, params=[
   285     xmlr.Attribute(
'joint', str),
   286     xmlr.Attribute(
'multiplier', float, 
False),
   287     xmlr.Attribute(
'offset', float, 
False)
   292     def __init__(self, velocity=None, position=None, lower=None, upper=None):
   299 xmlr.reflect(SafetyController, params=[
   300     xmlr.Attribute(
'k_velocity', float),
   301     xmlr.Attribute(
'k_position', float, 
False, 0),
   302     xmlr.Attribute(
'soft_lower_limit', float, 
False, 0),
   303     xmlr.Attribute(
'soft_upper_limit', float, 
False, 0)
   308     TYPES = [
'unknown', 
'revolute', 
'continuous', 
'prismatic',
   309              'floating', 
'planar', 
'fixed']
   311     def __init__(self, name=None, parent=None, child=None, joint_type=None,
   312                  axis=
None, origin=
None,
   313                  limit=
None, dynamics=
None, safety_controller=
None,
   314                  calibration=
None, mimic=
None):
   328         assert self.
type in self.
TYPES, 
"Invalid joint type: {}".format(self.
type)  
   337 xmlr.reflect(Joint, params=[
   339     xmlr.Attribute(
'type', str),
   341     xmlr.Element(
'axis', 
'element_xyz', 
False),
   342     xmlr.Element(
'parent', 
'element_link'),
   343     xmlr.Element(
'child', 
'element_link'),
   344     xmlr.Element(
'limit', JointLimit, 
False),
   345     xmlr.Element(
'dynamics', JointDynamics, 
False),
   346     xmlr.Element(
'safety_controller', SafetyController, 
False),
   347     xmlr.Element(
'calibration', JointCalibration, 
False),
   348     xmlr.Element(
'mimic', JointMimic, 
False),
   353     def __init__(self, name=None, visual=None, inertial=None, collision=None,
   361 xmlr.reflect(Link, params=[
   364     xmlr.Element(
'inertial', Inertial, 
False),
   365     xmlr.Element(
'visual', Visual, 
False),
   366     xmlr.Element(
'collision', Collision, 
False)
   371     def __init__(self, name=None, joint=None, actuator=None, type=None,
   372                  mechanicalReduction=1):
   380 xmlr.reflect(PR2Transmission, tag=
'pr2_transmission', params=[
   382     xmlr.Attribute(
'type', str),
   383     xmlr.Element(
'joint', 
'element_name'),
   384     xmlr.Element(
'actuator', 
'element_name'),
   385     xmlr.Element(
'mechanicalReduction', float)
   390     def __init__(self, name=None, mechanicalReduction=1):
   395 xmlr.reflect(Actuator, tag=
'actuator', params=[
   397     xmlr.Element(
'mechanicalReduction', float, required=
False)
   403         self.aggregate_init()
   411 xmlr.reflect(TransmissionJoint, tag=
'joint', params=[
   413     xmlr.AggregateElement(
'hardwareInterface', str),
   418     """ New format: http://wiki.ros.org/urdf/XML/Transmission """   421         self.aggregate_init()
   427         assert len(self.
joints) > 0, 
"no joint defined"   428         assert len(self.
actuators) > 0, 
"no actuator defined"   431 xmlr.reflect(Transmission, tag=
'new_transmission', params=[
   433     xmlr.Element(
'type', str),
   434     xmlr.AggregateElement(
'joint', TransmissionJoint),
   435     xmlr.AggregateElement(
'actuator', Actuator)
   438 xmlr.add_type(
'transmission',
   439               xmlr.DuckTypedFactory(
'transmission',
   440                                     [Transmission, PR2Transmission]))
   445         self.aggregate_init()
   461         xmlr.Object.add_aggregate(self, typeName, elem)
   463         if typeName == 
'joint':
   466             self.
parent_map[joint.child] = (joint.name, joint.parent)
   468                 self.
child_map[joint.parent].append((joint.name, joint.child))
   470                 self.
child_map[joint.parent] = [(joint.name, joint.child)]
   471         elif typeName == 
'link':
   481     def get_chain(self, root, tip, joints=True, links=True, fixed=True):
   489                 if fixed 
or self.
joint_map[joint].joint_type != 
'fixed':
   501                 assert root 
is None, 
"Multiple roots detected, invalid URDF."   503         assert root 
is not None, 
"No roots detected, invalid URDF."   509         Retrieve the robot model on the parameter server   510         and parse it to create a URDF robot structure.   512         Warning: this requires roscore to be running.   516         return cls.from_xml_string(rospy.get_param(key))
   519 xmlr.reflect(Robot, tag=
'robot', params=[
   520     xmlr.Attribute(
'name', str, 
False),  
   521     xmlr.AggregateElement(
'link', Link),
   522     xmlr.AggregateElement(
'joint', Joint),
   523     xmlr.AggregateElement(
'gazebo', xmlr.RawType()),
   524     xmlr.AggregateElement(
'transmission', 
'transmission'),
   525     xmlr.AggregateElement(
'material', Material)
 
def __init__(self, name=None)
def from_parameter_server(cls, key='robot_description')
def add_aggregate(self, typeName, elem)
def add_joint(self, joint)
def __init__(self, xyz=None, rpy=None)
def __init__(self, name=None, parent=None, child=None, joint_type=None, axis=None, origin=None, limit=None, dynamics=None, safety_controller=None, calibration=None, mimic=None)
def __init__(self, joint_name=None, multiplier=None, offset=None)
def __init__(self, geometry=None, origin=None)
def __init__(self, size=None)
def __init__(self, radius=0.0)
def get_chain(self, root, tip, joints=True, links=True, fixed=True)
def __init__(self, name=None, joint=None, actuator=None, type=None, mechanicalReduction=1)
def __init__(self, effort=None, velocity=None, lower=None, upper=None)
def __init__(self, name=None)
def __init__(self, ixx=0.0, ixy=0.0, ixz=0.0, iyy=0.0, iyz=0.0, izz=0.0)
def __init__(self, name=None, mechanicalReduction=1)
def __init__(self, velocity=None, position=None, lower=None, upper=None)
def __init__(self, mass=0.0, inertia=None, origin=None)
def __init__(self, name=None, color=None, texture=None)
def __init__(self, geometry=None, material=None, origin=None)
def __init__(self, filename=None, scale=None)
def __init__(self, radius=0.0, length=0.0)
def write_xml(self, node, obj)
def __init__(self, rising=None, falling=None)
def __init__(self, damping=None, friction=None)
def __init__(self, name=None)
def __init__(self, filename=None)
def __init__(self, name=None, visual=None, inertial=None, collision=None, origin=None)