simulation.utils.urdf.joint module

Class definitions making up the <joint>.

Example

A simple joint connecting link2 to link1 with a revolute joint that can rotate along the z-axis:

>>> from simulation.utils.urdf import (
...     Origin, Link, Joint, Parent, Child, Axis, JointLimit, JointDynamics
... )
>>> link1 = Link("link_1")
>>> link2 = Link("link_2")
>>> simple_joint = Joint(
...     name="simple_joint",
...     parent=Parent(link1.name),
...     child=Child(link2.name),
...     type=Joint.REVOLUTE,
...     origin=Origin([1,3,2]),
...     axis=Axis([0, 0, 1]),
...     limit=JointLimit(effort=1000, lower=-10, upper=10),
...     dynamics=JointDynamics(damping=1, friction=1),
... )

Reference

class JointDynamics(damping: simulation.utils.urdf.core.Attribute = None, friction: simulation.utils.urdf.core.Attribute = None)[source]

Bases: simulation.utils.urdf.core.XmlObject

TAG = 'dynamics'
damping: simulation.utils.urdf.core.Attribute = None
friction: simulation.utils.urdf.core.Attribute = None
class JointLimit(effort: simulation.utils.urdf.core.Attribute = None, lower: simulation.utils.urdf.core.Attribute = None, upper: simulation.utils.urdf.core.Attribute = None, velocity: simulation.utils.urdf.core.Attribute = None)[source]

Bases: simulation.utils.urdf.core.XmlObject

TAG = 'limit'
effort: simulation.utils.urdf.core.Attribute = None
lower: simulation.utils.urdf.core.Attribute = None
upper: simulation.utils.urdf.core.Attribute = None
velocity: simulation.utils.urdf.core.Attribute = None
class Parent(link: simulation.utils.urdf.core.Attribute)[source]

Bases: simulation.utils.urdf.core.XmlObject

TAG = 'parent'
class Child(link: simulation.utils.urdf.core.Attribute)[source]

Bases: simulation.utils.urdf.core.XmlObject

TAG = 'child'
class Joint(name: simulation.utils.urdf.core.Attribute, parent: simulation.utils.urdf.joint.Parent, child: simulation.utils.urdf.joint.Child, type: simulation.utils.urdf.core.Attribute = 'fixed', axis: simulation.utils.geometry.vector.Vector = None, limit: simulation.utils.urdf.joint.JointLimit = None, dynamics: simulation.utils.urdf.joint.JointDynamics = None, origin: simulation.utils.urdf.core.Origin = None)[source]

Bases: simulation.utils.urdf.core.XmlObject

TAG = 'joint'
FIXED = 'fixed'
REVOLUTE = 'revolute'
CONTINUOUS = 'continuous'
name: simulation.utils.urdf.core.Attribute
parent: simulation.utils.urdf.joint.Parent
child: simulation.utils.urdf.joint.Child
type: simulation.utils.urdf.core.Attribute = 'fixed'
axis: simulation.utils.geometry.vector.Vector = None
limit: simulation.utils.urdf.joint.JointLimit = None
dynamics: simulation.utils.urdf.joint.JointDynamics = None
origin: simulation.utils.urdf.core.Origin = None