Articulations#

Articulations are a way to represent a collection of rigid bodies that are connected by joints.

Joint types#

Joint Type

Description

DOFs in joint_q

DOFs in joint_qd

DOFs in joint_axis

JOINT_PRISMATIC

Prismatic (slider) joint with 1 linear degree of freedom

1

1

1

JOINT_REVOLUTE

Revolute (hinge) joint with 1 angular degree of freedom

1

1

1

JOINT_BALL

Ball (spherical) joint with quaternion state representation

4

3

3

JOINT_FIXED

Fixed (static) joint with no degrees of freedom

0

0

0

JOINT_FREE

Free (floating) joint with 6 degrees of freedom in velocity space

7 (3D position + 4D quaternion)

6 (see Twist conventions in Newton)

0

JOINT_COMPOUND

Compound joint with 3 rotational degrees of freedom

3

3

3

JOINT_UNIVERSAL

Universal joint with 2 rotational degrees of freedom

2

2

2

JOINT_DISTANCE

Distance joint that keeps two bodies at a distance within its joint limits

7

6

1

JOINT_D6

Generic D6 joint with up to 3 translational and 3 rotational degrees of freedom

up to 6

up to 6

up to 6

D6 joints are the most general joint type in Newton and can be used to represent any combination of translational and rotational degrees of freedom. Prismatic, revolute, planar, universal, and compound joints can be seen as special cases of the D6 joint.

Definition of joint_q#

The newton.Model.joint_q array stores the generalized joint positions for all joints in the model. The positional dofs for each joint can be queried as follows:

q_start = Model.joint_q_start[joint_id]
q_end = Model.joint_q_start[joint_id + 1]
# now the positional dofs can be queried as follows:
q0 = State.joint_q[q_start]
q1 = State.joint_q[q_start + 1]
...

Definition of joint_qd#

The newton.Model.joint_qd array stores the generalized joint velocities for all joints in the model. The generalized joint forces at newton.Control.joint_f are stored in the same order.

The velocity dofs for each joint can be queried as follows:

qd_start = Model.joint_qd_start[joint_id]
qd_end = Model.joint_qd_start[joint_id + 1]
# now the velocity dofs can be queried as follows:
qd0 = State.joint_qd[qd_start]
qd1 = State.joint_qd[qd_start + 1]
...
# the generalized joint forces can be queried as follows:
f0 = Control.joint_f[qd_start]
f1 = Control.joint_f[qd_start + 1]
...

Forward / Inverse Kinematics#

Articulated rigid-body mechanisms are kinematically described by the joints that connect the bodies as well as the relative transform from the parent and child body to the respective anchor frames of the joint in the parent and child body:

../_images/joint_transforms.png
Variable names in the kernels from newton.core.articulation#

Symbol

Description

x_wp

World transform of the parent body (stored at State.body_q)

x_wc

World transform of the child body (stored at State.body_q)

x_pj

Transform from the parent body to the joint parent anchor frame (defined by Model.joint_X_p)

x_cj

Transform from the child body to the joint child anchor frame (defined by Model.joint_X_c)

x_j

Joint transform from the joint parent anchor frame to the joint child anchor frame

In the forward kinematics, the joint transform is determined by the joint coordinates (generalized joint positions State.joint_q and velocities State.joint_qd). Given the parent body’s world transform \(x_{wp}\) and the joint transform \(x_{j}\), the child body’s world transform \(x_{wc}\) is computed as:

\[x_{wc} = x_{wp} \cdot x_{pj} \cdot x_{j} \cdot x_{cj}^{-1}.\]
newton.eval_fk(model, joint_q, joint_qd, state, mask=None)#

Evaluates the model’s forward kinematics given the joint coordinates and updates the state’s body information (State.body_q and State.body_qd).

Parameters:
  • model (Model) – The model to evaluate.

  • joint_q (array) – Generalized joint position coordinates, shape [joint_coord_count], float

  • joint_qd (array) – Generalized joint velocity coordinates, shape [joint_dof_count], float

  • mask (array) – The mask to use to enable / disable FK for an articulation. If None then treat all as enabled, shape [articulation_count], int/bool

  • state (State) – The state to update.

newton.eval_ik(model, state, joint_q, joint_qd)#

Evaluates the model’s inverse kinematics given the state’s body information (State.body_q and State.body_qd) and updates the generalized joint coordinates joint_q and joint_qd.

Parameters:
  • model (Model) – The model to evaluate.

  • state (State) – The state with the body’s maximal coordinates (positions State.body_q and velocities State.body_qd) to use.

  • joint_q (array) – Generalized joint position coordinates, shape [joint_coord_count], float

  • joint_qd (array) – Generalized joint velocity coordinates, shape [joint_dof_count], float