manipulation.systems

This file contains a number of helper systems useful for setting up diagrams.

manipulation.systems.AddIiwaDifferentialIK(builder, plant, frame=None)

Adds a DifferentialInverseKinematicsIntegrator system to the builder with default parameters suitable for use with the standard 7-link iiwa models or the 3-link planar iiwa models.

Parameters:
  • builder (DiagramBuilder) – The DiagramBuilder to which the system should be added.

  • plant (MultibodyPlant) – The MultibodyPlant passed to the DifferentialInverseKinematicsIntegrator.

  • frame (Frame | None) – The frame to use for the end effector command. Defaults to the body frame of “iiwa_link_7”.

Returns:

The DifferentialInverseKinematicsIntegrator system.

Return type:

DifferentialInverseKinematicsIntegrator

class manipulation.systems.ExtractPose(index, X_BA=RigidTransform(R=RotationMatrix([[1.0, 0.0, 0.0], [0.0, 1.0, 0.0], [0.0, 0.0, 1.0]]), p=[0.0, 0.0, 0.0]))

A system that extracts a single pose from a List[RigidTransform], which is the output of the MultibodyPlant body_poses output port.

Parameters:
  • index (int) – The index of the element in the vector whose pose we want to extract (e.g. int(plant.GetBodyByName(“body”).index())).

  • X_BA (RigidTransform) – An optional fixed transform from the frame B in the list to an output frame A.

class manipulation.systems.MultibodyPositionToBodyPose(plant, body)

A system that computes a body pose from a MultibodyPlant position vector. The output port calls plant.SetPositions() and then plant.EvalBodyPoseInWorld().

Parameters:
  • plant (MultibodyPlant) – The MultibodyPlant.

  • body (RigidBody) – A body in the plant whose pose we want to compute (e.g. plant. GetBodyByName(“body”)).