skbot.ignition.sdformat.generic_sdf.joint.Joint

class skbot.ignition.sdformat.generic_sdf.joint.Joint(*, name, type, parent, child, origin=None, pose=None, gearbox_ratio=1.0, gearbox_reference_body=None, thread_pitch=1.0, axis=None, axis2=None, physics=None, frames=None, sensors=None, sdf_version)[source]

A constraint between two rigid bodys.

A joint connects two links with kinematic and dynamic properties. This defines a constraint between the two bodies, and constructing a :mod``transform graph <skbot.transform>`` using to_dynamic_graph will build this constraint into the underlying graph structure.

Parameters
namestr

The name of the joint.

typestr
The type of joint, which must be one of the following:
continuous

A hinge joint that rotates around Joint.Axis with a continuous range of motion. This means that the upper and lower axis limits are ignored.

revolute

a hinge joint that rotates around Joint.Axis with a fixed range of motion.

gearbox

A geared revolute joints.

revolute2

Two revolute joints connected in series. The first one rotates around :class:Joint.Axis, and the second one rotates around :class:Joint.Axis.

prismatic

A sliding joint that slides along :class:Joint.Axis with a limited range of motion.

ball

A ball and socket joint.

screw

A 1DoF joint with coupled sliding and rotational motion.

universal

Like a joint with type ball but constrains one degree of freedom.

fixed

A joint with zero DoF that rigidly connects two links.

parentUnion[str, Joint.Parent]

The first Link that this joint constraints. It may be set to “world”, in which case the movement of the rigid body in Joint.child is constrained relative to the inertial world frame.

Changed in version SDFormat: v1.7 Parent may now be set to “world” and, if so, will connect to the inertial world frame.

Changed in version SDFormat: v1.2 Parent is now a string instead of Joint.Parent.

childUnion[str, Joint.Child]

The second Link that this joint constraints.

Changed in version SDFormat: v1.2 Child is now a string instead of Joint.Child.

posePose

The links’s initial position (x,y,z) and orientation (roll, pitch, yaw).

New in version SDFormat: 1.2

gearbox_ratiofloat

Parameter for gearbox joints. Given theta_1 and theta_2 defined in description for gearbox_reference_body, theta_2 = -gearbox_ratio * theta_1. Default: 1.0

New in version SDFormat: v1.4

gearbox_reference_bodystr

Parameter for gearbox joints. Gearbox ratio is enforced over two joint angles. First joint angle (theta_1) is the angle from the gearbox_reference_body to the parent link defined by Joint.Axis and the second joint angle (theta_2) is the angle from the gearbox_reference_body to the child link defined by Joint.Axis.

New in version SDFormat: v1.4

thread_pitchfloat

Parameter for screw joints. The amount of linear displacement for each full rotation of the joint.

axisJoint.Axis

Configuration parameters for joints that rotate around or translate along at least one axis.

axis2Joint.Axis

Configuration parameters for joints that rotate around or translate along at least two axis.

physicsJoint.Physics

Configuration parameters for various physics engines. (Currently: ODE and Simbody.)

framesList[Frame]

A list of frames of reference in which poses may be expressed.

Deprecated since version SDFormat: v1.7 Use Model.frame instead.

New in version SDFormat: v1.5

sensorsList[Sensor]

A list of sensors attached to this joint.

New in version SDFormat: v1.4

sdf_versionstr

The SDFormat version to use when constructing this element.

originOrigin

The joint’s origin.

Deprecated since version SDFormat: v1.2 Use Joint.pose instead.

Notes

A joint defines an implicit frame of reference to which other Frame`s may be ``attached_to`. As such its name must be unique among all frames and frame-bearing elements.

Attributes
namestr

See Parameters section.

typestr

See Parameters section.

parentstr

See Parameters section.

childstr

See Parameters section.

posePose

See Parameters section.

gearbox_ratiofloat

See Parameters section.

gearbox_reference_bodystr

See Parameters section.

thread_pitchfloat

See Parameters section.

axisJoint.Axis

See Parameters section.

axis2Joint.Axis

See Parameters section.

physicsJoint.Physics

See Parameters section.

framesList[Frame]

See Parameters section.

sensorsList[Sensor]

See Parameters section.

sdf_versionstr

See Parameters section.

originOrigin

See Parameters section.

__init__(*, name, type, parent, child, origin=None, pose=None, gearbox_ratio=1.0, gearbox_reference_body=None, thread_pitch=1.0, axis=None, axis2=None, physics=None, frames=None, sensors=None, sdf_version)[source]

Methods

__init__(*, name, type, parent, child[, ...])

declared_frames()

Frames contained in this element.

from_specific(specific, *, version)

Create from version-specific object

to_dynamic_graph(declared_frames, *[, seed, ...])

Convert to transform graph

to_static_graph(declared_frames, *[, seed, axis])

Convert to transform graph

to_tf_link(scaffolding, *[, shape, axis])

tf.Link from child to parent frame

Attributes

frames

origin