<Joint> element

The joint element describes the kinematics and dynamics of the joint and also specifies the safety limits of the joint.

Here is an example of a joint element:

   1  <joint name="my_joint" type="floating">
   2     <origin xyz="0 0 1" rpy="0 0 3.1416"/>
   3     <parent link="link1"/>
   4     <child link="link2"/>
   5 
   6     <calibration rising="0.0"/>
   7     <dynamics damping="0.0" friction="0.0"/>
   8     <limit effort="30" velocity="1.0" lower="-2.2" upper="0.7" />
   9     <safety_controller k_velocity="10" k_position="15" soft_lower_limit="-2.0" soft_upper_limit="0.5" />
  10  </joint>

joint.png

Attributes

The joint element has two attributes:

  • name (required)

    • Specifies a unique name of the joint

    type (required)

    • Specifies the type of joint, where type can be one of the following:
      • revolute — a hinge joint that rotates along the axis and has a limited range specified by the upper and lower limits.

      • continuous — a continuous hinge joint that rotates around the axis and has no upper and lower limits.

      • prismatic — a sliding joint that slides along the axis, and has a limited range specified by the upper and lower limits.

      • fixed — this is not really a joint because it cannot move. All degrees of freedom are locked. This type of joint does not require the <axis>, <calibration>, <dynamics>, <limits> or <safety_controller>.

      • floating — this joint allows motion for all 6 degrees of freedom.

      • planar — this joint allows motion in a plane perpendicular to the axis.

Elements

The joint element has following elements:

  • <origin> (optional: defaults to identity if not specified)

    • This is the transform from the parent link to the child link. The joint is located at the origin of the child link, as shown in the figure above.

      xyz (optional: defaults to zero vector)

      • Represents the x, y, z offset. All positions are specified in metres.

      rpy (optional: defaults to zero vector)

      • Represents the rotation around fixed axis: first roll around x, then pitch around y and finally yaw around z. All angles are specified in radians.

    <parent> (required)

    • Parent link name with mandatory attribute:

      link

      • The name of the link that is the parent of this link in the robot tree structure.

    <child> (required)

    • Child link name with mandatory attribute:

      link

      • The name of the link that is the child link.

    <axis> (optional: defaults to (1,0,0))

    • The joint axis specified in the joint frame. This is the axis of rotation for revolute joints, the axis of translation for prismatic joints, and the surface normal for planar joints. The axis is specified in the joint frame of reference. Fixed and floating joints do not use the axis field.

      xyz (required)

      • Represents the (x, y, z) components of a vector. The vector should be normalized.

    <calibration> (optional)

    • The reference positions of the joint, used to calibrate the absolute position of the joint.

      rising (optional)

      • When the joint moves in a positive direction, this reference position will trigger a rising edge.

      falling (optional)

      • When the joint moves in a positive direction, this reference position will trigger a falling edge.

    <dynamics> (optional)

    • An element specifying physical properties of the joint. These values are used to specify modeling properties of the joint, particularly useful for simulation.

      damping (optional, defaults to 0)

      • The physical damping value of the joint (in newton-seconds per metre [Ns/m] for prismatic joints, in newton-metre-seconds per radian [Nms/rad] for revolute joints).

      friction (optional, defaults to 0)

      • The physical static friction value of the joint (in newtons [N] for prismatic joints, in newton-metres [Nm] for revolute joints).

    <limit> (required only for revolute and prismatic joint)

    • An element can contain the following attributes:

      lower (optional, defaults to 0)

      • An attribute specifying the lower joint limit (in radians for revolute joints, in metres for prismatic joints). Omit if joint is continuous.

      upper (optional, defaults to 0)

      • An attribute specifying the upper joint limit (in radians for revolute joints, in metres for prismatic joints). Omit if joint is continuous.

      effort (required)

      • An attribute for enforcing the maximum joint effort (|applied effort| < |effort|). See safety limits.

      velocity (required)

      • An attribute for enforcing the maximum joint velocity (in radians per second [rad/s] for revolute joints, in metres per second [m/s] for prismatic joints). See safety limits.

    <mimic> (optional) (New with ROS Groovy. See issue)

    • This tag is used to specify that the defined joint mimics another existing joint. The value of this joint can be computed as value = multiplier * other_joint_value + offset.

    • Expected and optional attributes:

    • joint (required)

      • This specifies the name of the joint to mimic.
    • multiplier (optional)

      • Specifies the multiplicative factor in the formula above.
    • offset (optional)

      • Specifies the offset to add in the formula above. Defaults to 0 (radians for revolute joints, meters for prismatic joints)

    <safety_controller> (optional)

    • An element can contain the following attributes:

      soft_lower_limit (optional, defaults to 0)

      • An attribute specifying the lower joint boundary where the safety controller starts limiting the position of the joint. This limit needs to be larger than the lower joint limit (see above). See See safety limits for more details.

      soft_upper_limit (optional, defaults to 0)

      • An attribute specifying the upper joint boundary where the safety controller starts limiting the position of the joint. This limit needs to be smaller than the upper joint limit (see above). See See safety limits for more details.

      k_position (optional, defaults to 0)

      • An attribute specifying the relation between position and velocity limits. See See safety limits for more details.

      k_velocity (required)

      • An attribute specifying the relation between effort and velocity limits. See See safety limits for more details.

Wiki: urdf/XML/joint (last edited 2022-06-17 23:41:48 by IlyaPankov)