pydrake.systems.rendering

Bindings for the rendering portion of the Systems framework.

class pydrake.systems.rendering.MultibodyPositionToGeometryPose

Bases: pydrake.systems.framework.LeafSystem

A direct-feedthrough system that converts a vector of joint positions directly to a geometry::FramePoseVector<T> to behave like a MultibodyPlant::get_geometry_pose_output_port().

position→
MultibodyPositionToGeometryPose
→ geometry_pose

The position input must be a vector whose length matches either the number of positions in the MultibodyPlant or the number of states (based on the optional argument in the constructor). This option to pass the full state vector is provided only for convenience – only the position values will affect the outputs.

__init__(self: pydrake.systems.rendering.MultibodyPositionToGeometryPose, plant: pydrake.multibody.plant.MultibodyPlant, input_multibody_state: bool = False) None

The MultibodyPositionToGeometryPose holds an internal, non-owned reference to the MultibodyPlant object so you must ensure that plant has a longer lifetime than this MultibodyPositionToGeometryPose system.

Parameter input_multibody_state:

If true, the vector input port will be the size of the plant state vector. If false, it will be the size of the plant position vector. In both cases, only the positions will affect the output. $*Default:* false.

Raises

if plant is not finalized and registered with a SceneGraph.