pydrake.manipulation
- pydrake.manipulation.ApplyDriverConfig(*args, **kwargs)
Overloaded function.
ApplyDriverConfig(driver_config: pydrake.manipulation.IiwaDriver, model_instance_name: str, sim_plant: drake::multibody::MultibodyPlant<double>, models_from_directives: dict[str, pydrake.multibody.parsing.ModelInstanceInfo], lcms: pydrake.systems.lcm.LcmBuses, builder: pydrake.systems.framework.DiagramBuilder) -> None
Wires up Drake systems between an LCM interface and the actuation input ports of a MultibodyPlant. This simulates the role that driver software and control cabinets would take in real life.
- Precondition:
model_instance_name is in models_from_directives.
- Precondition:
driver_config.hand_model_name is in models_from_directives.
ApplyDriverConfig(driver_config: pydrake.manipulation.SchunkWsgDriver, model_instance_name: str, sim_plant: drake::multibody::MultibodyPlant<double>, models_from_directives: dict[str, pydrake.multibody.parsing.ModelInstanceInfo], lcms: pydrake.systems.lcm.LcmBuses, builder: pydrake.systems.framework.DiagramBuilder) -> None
Wires up Drake systems between an LCM interface and the actuation input ports of a MultibodyPlant. This simulates the role that driver software and robot firmware would take in real life.
ApplyDriverConfig(driver_config: pydrake.manipulation.ZeroForceDriver, model_instance_name: str, sim_plant: drake::multibody::MultibodyPlant<double>, models_from_directives: dict[str, pydrake.multibody.parsing.ModelInstanceInfo], lcms: pydrake.systems.lcm.LcmBuses, builder: pydrake.systems.framework.DiagramBuilder) -> None
Applies zero actuation to every joint of a model mainly for debugging and testing purposes.
- Precondition:
The sim_plant.is_finalized() is true.
- pydrake.manipulation.ApplyDriverConfigs(*, driver_configs, sim_plant, models_from_directives, lcm_buses, builder)
Applies many driver configurations to a model.
A “driver configuration” helps stack Drake systems between an LCM interface subscriber system and the actuation input ports of a MultibodyPlant (to enact the driver command), as well as the output ports of a MultibodyPlant back to an LCM interface publisher system (to provide the driver status).
These conceptually simulate “drivers” – they take the role that driver software and control cabinets would take in real life – but may also model some physical properties of the robot that are not easily reflected in MultibodyPlant (e.g., the WSG belt drive).
This function assumes that the ApplyDriverConfig functions associated with the values in the driver_configs map are defined in the same module as the value itself.
- Parameters
driver_configs – The configurations to apply, mapping a
str
model instance name to some kind of a DriverConfig object (e.g., apydrake.manipulation.util.ZeroForceDriver
).sim_plant – The plant containing the model.
models_from_directives – The list of
ModelInstanceInfo
from previously-loaded directives (e.g., fromProcessModelDirectives
).lcm_buses – The available LCM buses to drive and/or sense from this driver.
builder – The
DiagramBuilder
into which to install this driver.
- pydrake.manipulation.BuildIiwaControl(plant: drake::multibody::MultibodyPlant<double>, iiwa_instance: pydrake.multibody.tree.ModelInstanceIndex, controller_plant: drake::multibody::MultibodyPlant<double>, lcm: pydrake.lcm.DrakeLcmInterface, builder: pydrake.systems.framework.DiagramBuilder, ext_joint_filter_tau: float = 0.01, desired_iiwa_kp_gains: Optional[numpy.ndarray[numpy.float64[m, 1]]] = None, control_mode: pydrake.manipulation.IiwaControlMode = <IiwaControlMode.kPositionAndTorque: 2>) None
Given a
plant
(and associatediiwa_instance)
and abuilder
, installs in that builder the systems necessary to control and monitor an Iiwa described bycontroller_plant
in that plant.The installed plant will communicate over the LCM interface
lcm
.The installed plant will connect itself to the actuation input port and state output ports in
plant
corresponding to the Iiwa model.desired_iiwa_kp_gains
is an optional argument to pass in gains corresponding to the Iiwa Dof (7) in the controller. If no argument is passed, the gains derived from hardware will be used instead (hardcoded within the implementation of this function). These gains must be nullopt ifcontrol_mode
does not include position control.control_mode
the control mode for the controller.Note: The Diagram will maintain an internal reference to
controller_plant
, so you must ensure thatcontroller_plant
has a longer lifetime than the Diagram.
- pydrake.manipulation.BuildSchunkWsgControl(plant: drake::multibody::MultibodyPlant<double>, wsg_instance: pydrake.multibody.tree.ModelInstanceIndex, lcm: pydrake.lcm.DrakeLcmInterface, builder: pydrake.systems.framework.DiagramBuilder, pid_gains: Optional[numpy.ndarray[numpy.float64[3, 1]]] = None) None
Builds (into
builder)
the WSG control and sensing systems for the wsg model inplant
indicated bywsg_instance
; hooks those systems up tolcm
and the relevant MultibodyPlant ports in the diagram.pid_gains
can be used to override the default sim PID gains.
- pydrake.manipulation.get_iiwa_max_joint_velocities() numpy.ndarray[numpy.float64[m, 1]]
Returns the maximum joint velocities (rad/s) provided by Kuka.
- pydrake.manipulation.GetSchunkWsgOpenPosition() numpy.ndarray[numpy.float64[m, 1]]
Returns the position vector corresponding to the open position of the gripper.
- class pydrake.manipulation.IiwaCommandReceiver
Bases:
pydrake.systems.framework.LeafSystem
Handles lcmt_iiwa_command message from a LcmSubscriberSystem.
Note that this system does not actually subscribe to an LCM channel. To receive the message, the input of this system should be connected to a LcmSubscriberSystem::Make<drake::lcmt_iiwa_command>().
It has one required input port, “lcmt_iiwa_command”.
It has three output ports: one for the commanded position for each joint, one for commanded additional feedforward joint torque, and one for the timestamp in the most recently received message.
lcmt_iiwa_command→ position_measured (optional)→ IiwaCommandReceiver → position → torque → time @par Output prior to receiving a valid lcmt_iiwa_command message: The “position” output initially feeds through from the “position_measured” input port – or if not connected, outputs zero. When discrete update events are enabled (e.g., during a simulation), the system latches the “position_measured” input into state during the first event, and the “position” output comes from the latched state, no longer fed through from the “position” input. Alternatively, the LatchInitialPosition() method is available to achieve the same effect without using events. The “torque” output will be a vector of zeros, and the “time” output will be a vector of a single zero.
- __init__(self: pydrake.manipulation.IiwaCommandReceiver, num_joints: int = 7, control_mode: pydrake.manipulation.IiwaControlMode = <IiwaControlMode.kPositionAndTorque: 2>) None
- get_commanded_position_output_port(self: pydrake.manipulation.IiwaCommandReceiver) pydrake.systems.framework.OutputPort
- Raises
RuntimeError if control_mode does not include position control. –
- get_commanded_torque_output_port(self: pydrake.manipulation.IiwaCommandReceiver) pydrake.systems.framework.OutputPort
- Raises
RuntimeError if control_mode does not include torque control. –
- get_message_input_port(self: pydrake.manipulation.IiwaCommandReceiver) pydrake.systems.framework.InputPort
- get_position_measured_input_port(self: pydrake.manipulation.IiwaCommandReceiver) pydrake.systems.framework.InputPort
- get_time_output_port(self: pydrake.manipulation.IiwaCommandReceiver) pydrake.systems.framework.OutputPort
- class pydrake.manipulation.IiwaCommandSender
Bases:
pydrake.systems.framework.LeafSystem
Creates and outputs lcmt_iiwa_command messages.
Note that this system does not actually send the message on an LCM channel. To send the message, the output of this system should be connected to a systems::lcm::LcmPublisherSystem::Make<lcmt_iiwa_command>().
This system has three vector-valued input ports:
one for the commanded position, which must be connected if position mode is
specified, - one for commanded torque, which is optional if position and torque mode is specified (for backwards compatibility), but must be connected if it is torque only, and - one for the time to use, in seconds, for the message timestamp, which is optional.
If position and torque mode is specified, the torque input port can remain unconnected; the message will contain torque values of size zero. If position mode is not specified, the message will contain position values of size zero.
If the time input port is not connected, the context time will be used for message timestamp.
This system has one abstract-valued output port of type lcmt_iiwa_command.
position (required if using position mode)→ torque (optional if using position mode, required in torque mode)→ time (optional)→ IiwaCommandSender → lcmt_iiwa_command See also
lcmt_iiwa_command.lcm
for additional documentation.- __init__(self: pydrake.manipulation.IiwaCommandSender, num_joints: int = 7, control_mode: pydrake.manipulation.IiwaControlMode = <IiwaControlMode.kPositionAndTorque: 2>) None
- get_position_input_port(self: pydrake.manipulation.IiwaCommandSender) pydrake.systems.framework.InputPort
- get_time_input_port(self: pydrake.manipulation.IiwaCommandSender) pydrake.systems.framework.InputPort
- get_torque_input_port(self: pydrake.manipulation.IiwaCommandSender) pydrake.systems.framework.InputPort
- class pydrake.manipulation.IiwaControlMode
Enumeration for control modes.
Members:
kPositionOnly :
kTorqueOnly :
kPositionAndTorque :
- __init__(self: pydrake.manipulation.IiwaControlMode, value: int) None
- kPositionAndTorque = <IiwaControlMode.kPositionAndTorque: 2>
- kPositionOnly = <IiwaControlMode.kPositionOnly: 0>
- kTorqueOnly = <IiwaControlMode.kTorqueOnly: 1>
- property name
- property value
- class pydrake.manipulation.IiwaDriver
This config struct specifies how to wire up Drake systems between an LCM interface and the actuation input ports of a MultibodyPlant. This simulates the role that driver software and control cabinets would take in real life.
It creates an LCM publisher on the
IIWA_STATUS
channel and an LCM subscriber on theIIWA_COMMAND
channel.- __init__(self: pydrake.manipulation.IiwaDriver, **kwargs) None
- property control_mode
The driver’s control mode. Valid options (per ParseIiwaControlMode) are: - “position_only” - “position_and_torque” (default) - “torque_only”
- property ext_joint_filter_tau
Per BuildIiwaControl.
- property hand_model_name
The name of the model (
name
element of theadd_model
directive) in the simulation that the driver will analyze to compute end effector inertia for its copy of the arm in inverse dynamics.
- property lcm_bus
- class pydrake.manipulation.IiwaStatusReceiver
Bases:
pydrake.systems.framework.LeafSystem
@system name: IiwaStatusReceiver input_ports: - lcmt_iiwa_status output_ports: - time_measured - position_commanded - position_measured - velocity_estimated - torque_commanded - torque_measured - torque_external @endsystem
See also
lcmt_iiwa_status.lcm
for additional documentation.- __init__(self: pydrake.manipulation.IiwaStatusReceiver, num_joints: int = 7) None
- get_position_commanded_output_port(self: pydrake.manipulation.IiwaStatusReceiver) pydrake.systems.framework.OutputPort
- get_position_measured_output_port(self: pydrake.manipulation.IiwaStatusReceiver) pydrake.systems.framework.OutputPort
- get_time_measured_output_port(self: pydrake.manipulation.IiwaStatusReceiver) pydrake.systems.framework.OutputPort
- get_torque_commanded_output_port(self: pydrake.manipulation.IiwaStatusReceiver) pydrake.systems.framework.OutputPort
- get_torque_external_output_port(self: pydrake.manipulation.IiwaStatusReceiver) pydrake.systems.framework.OutputPort
- get_torque_measured_output_port(self: pydrake.manipulation.IiwaStatusReceiver) pydrake.systems.framework.OutputPort
- get_velocity_estimated_output_port(self: pydrake.manipulation.IiwaStatusReceiver) pydrake.systems.framework.OutputPort
- class pydrake.manipulation.IiwaStatusSender
Bases:
pydrake.systems.framework.LeafSystem
Creates and outputs lcmt_iiwa_status messages.
Note that this system does not actually send the message an LCM channel. To send the message, the output of this system should be connected to a systems::lcm::LcmPublisherSystem::Make<lcmt_iiwa_status>().
This system has many vector-valued input ports, most of which have exactly num_joints elements. The exception is
time_measured
which is the one-dimensional time in seconds to set as the message timestamp (i.e. the time inputted will be converted to microseconds and sent to the hardware). It is optional and if unset, the context time is used.position_commanded
: the most recently received position command.position_measured
: the plant’s current position.velocity_estimated
(optional): the plant’s current velocity (thisshould be a low-pass filter of the position’s derivative; see detailed comments in
lcmt_iiwa_status.lcm
); when absent, the output message will use zeros.
torque_commanded
: the most recently received joint torque command.torque_measured
(optional): the plant’s measured joint torque; whenabsent, the output message will duplicate torque_commanded.
torque_external
(optional): the plant’s external joint torque; whenabsent, the output message will use zeros.
This system has one abstract-valued output port of type lcmt_iiwa_status.
This system is presently only used in simulation. The robot hardware drivers publish directly to LCM and do not make use of this system.
position_commanded→ position_measured→ velocity_estimated→ torque_commanded→ torque_measured→ torque_external→ time_measured→ IiwaStatusSender → lcmt_iiwa_status The ports
velocity_estimated
, torque_measured,torque_external
, andtime_measured
may be left unconnected, as detailed above.See also
lcmt_iiwa_status.lcm
for additional documentation.- __init__(self: pydrake.manipulation.IiwaStatusSender, num_joints: int = 7) None
- get_position_commanded_input_port(self: pydrake.manipulation.IiwaStatusSender) pydrake.systems.framework.InputPort
- get_position_measured_input_port(self: pydrake.manipulation.IiwaStatusSender) pydrake.systems.framework.InputPort
- get_time_measured_input_port(self: pydrake.manipulation.IiwaStatusSender) pydrake.systems.framework.InputPort
- get_torque_commanded_input_port(self: pydrake.manipulation.IiwaStatusSender) pydrake.systems.framework.InputPort
- get_torque_external_input_port(self: pydrake.manipulation.IiwaStatusSender) pydrake.systems.framework.InputPort
- get_torque_measured_input_port(self: pydrake.manipulation.IiwaStatusSender) pydrake.systems.framework.InputPort
- get_velocity_estimated_input_port(self: pydrake.manipulation.IiwaStatusSender) pydrake.systems.framework.InputPort
- pydrake.manipulation.MakeMultibodyForceToWsgForceSystem() pydrake.systems.framework.VectorSystem
Helper method to create a MultibodyForceToWsgForceSystem.
- pydrake.manipulation.MakeMultibodyStateToWsgStateSystem() pydrake.systems.primitives.MatrixGain
Extract the distance between the fingers (and its time derivative) out of the plant model which pretends the two fingers are independent.
- pydrake.manipulation.ParseIiwaControlMode(control_mode: str) pydrake.manipulation.IiwaControlMode
Parses control mode with the following mapping: - “position_only”: kPositionOnly - “torque_only”: kTorqueOnly - “position_and_torque”: kPositionAndTorque
- pydrake.manipulation.position_enabled(control_mode: pydrake.manipulation.IiwaControlMode) bool
Reports if the given control
mode
includes positions.
- class pydrake.manipulation.SchunkWsgCommandReceiver
Bases:
pydrake.systems.framework.LeafSystem
Handles the command for the Schunk WSG gripper from a LcmSubscriberSystem.
It has one input port: “command_message” for lcmt_schunk_wsg_command abstract values.
It has two output ports: one for the commanded finger position represented as the desired distance between the fingers in meters, and one for the commanded force limit. The commanded position and force limit are scalars (BasicVector<double> of size 1).
command_message→ SchunkWsgCommandReceiver → position → force_limit - __init__(self: pydrake.manipulation.SchunkWsgCommandReceiver, initial_position: float = 0.02, initial_force: float = 40.0) None
- Parameter
initial_position
: the commanded position to output if no LCM message has been received yet.
- Parameter
initial_force
: the commanded force limit to output if no LCM message has been received yet.
- Parameter
- get_force_limit_output_port(self: pydrake.manipulation.SchunkWsgCommandReceiver) pydrake.systems.framework.OutputPort
- get_position_output_port(self: pydrake.manipulation.SchunkWsgCommandReceiver) pydrake.systems.framework.OutputPort
- class pydrake.manipulation.SchunkWsgCommandSender
Bases:
pydrake.systems.framework.LeafSystem
Send lcmt_schunk_wsg_command messages for a Schunk WSG gripper. Has two input ports: one for the commanded finger position represented as the desired signed distance between the fingers in meters, and one for the commanded force limit. The commanded position and force limit are scalars (BasicVector<double> of size 1).
position→ force_limit→ SchunkWsgCommandSender → lcmt_schunk_wsg_command The
force_limit
input port can be left unconnected; in this case, thedefault_force_limit
value given at construction time will be used.- __init__(self: pydrake.manipulation.SchunkWsgCommandSender, default_force_limit: float = 40.0) None
- get_command_output_port(self: pydrake.manipulation.SchunkWsgCommandSender) pydrake.systems.framework.OutputPort
- get_force_limit_input_port(self: pydrake.manipulation.SchunkWsgCommandSender) pydrake.systems.framework.InputPort
- get_position_input_port(self: pydrake.manipulation.SchunkWsgCommandSender) pydrake.systems.framework.InputPort
- class pydrake.manipulation.SchunkWsgController
Bases:
pydrake.systems.framework.Diagram
This class implements a controller for a Schunk WSG gripper. It has two input ports: lcmt_schunk_wsg_command message and the current state, and an output port which emits the target force for the actuated finger. Note, only one of the command input ports should be connected, However, if both are connected, the message input will be ignored. The internal implementation consists of a PID controller (which controls the target position from the command message) combined with a saturation block (which applies the force control from the command message).
state→ command_message→ SchunkWsgController → force - __init__(self: pydrake.manipulation.SchunkWsgController, kp: float = 2000.0, ki: float = 0.0, kd: float = 5.0) None
- class pydrake.manipulation.SchunkWsgDriver
This config struct specifies how to wire up Drake systems between an LCM interface and the actuation input ports of a MultibodyPlant. This simulates the role that driver software and control cabinets would take in real life.
It creates an LCM publisher on the
SCHUNK_WSG_STATUS
channel and an LCM subscriber on theSCHUNK_WSG_COMMAND
channel.- __init__(self: pydrake.manipulation.SchunkWsgDriver, **kwargs) None
- property lcm_bus
- property pid_gains
Gains to apply to the the WSG fingers. The p term corresponds approximately to the elastic modulus of the belt, the d term to the viscous friction of the geartrain. The i term is nonphysical.
- class pydrake.manipulation.SchunkWsgPositionController
Bases:
pydrake.systems.framework.Diagram
This class implements a controller for a Schunk WSG gripper in position control mode adding a discrete-derivative to estimate the desired velocity from the desired position commands. It is a thin wrapper around SchunkWsgPdController.
desired_position→ force_limit→ state→ SchunkWSGPositionController → generalized_force → grip_force The
force_limit
input port can be left unconnected; in this case, thedefault_force_limit
value given at construction time will be used.See also
SchunkWsgPdController
- __init__(self: pydrake.manipulation.SchunkWsgPositionController, time_step: float = 0.05, kp_command: float = 200.0, kd_command: float = 5.0, kp_constraint: float = 2000.0, kd_constraint: float = 5.0, default_force_limit: float = 40.0) None
Initialize the controller. The default
time_step
is set to match the update rate of the wsg firmware. The gain parameters are set based limited tuning in simulation with a kuka picking up small objects.See also
SchunkWsgPdController::SchunkWsgPdController()
- get_desired_position_input_port(self: pydrake.manipulation.SchunkWsgPositionController) pydrake.systems.framework.InputPort
- get_force_limit_input_port(self: pydrake.manipulation.SchunkWsgPositionController) pydrake.systems.framework.InputPort
- get_generalized_force_output_port(self: pydrake.manipulation.SchunkWsgPositionController) pydrake.systems.framework.OutputPort
- get_grip_force_output_port(self: pydrake.manipulation.SchunkWsgPositionController) pydrake.systems.framework.OutputPort
- get_state_input_port(self: pydrake.manipulation.SchunkWsgPositionController) pydrake.systems.framework.InputPort
- class pydrake.manipulation.SchunkWsgStatusReceiver
Bases:
pydrake.systems.framework.LeafSystem
Handles lcmt_schunk_wsg_status messages from a LcmSubscriberSystem. Has two output ports: one for the measured state of the gripper, represented as the signed distance between the fingers in meters and its corresponding velocity, and one for the measured force.
lcmt_schunk_wsg_status→ SchunkWsgStatusReceiver → state → force - __init__(self: pydrake.manipulation.SchunkWsgStatusReceiver) None
- get_force_output_port(self: pydrake.manipulation.SchunkWsgStatusReceiver) pydrake.systems.framework.OutputPort
- get_state_output_port(self: pydrake.manipulation.SchunkWsgStatusReceiver) pydrake.systems.framework.OutputPort
- get_status_input_port(self: pydrake.manipulation.SchunkWsgStatusReceiver) pydrake.systems.framework.InputPort
- class pydrake.manipulation.SchunkWsgStatusSender
Bases:
pydrake.systems.framework.LeafSystem
Sends lcmt_schunk_wsg_status messages for a Schunk WSG. This system has one input port for the current state of the WSG, and one optional input port for the measured gripping force.
state→ force→ SchunkStatusSender → lcmt_schunk_wsg_status The state input is a BasicVector<double> of size 2 – with one position and one velocity – representing the distance between the fingers (positive implies non-penetration).
- __init__(self: pydrake.manipulation.SchunkWsgStatusSender) None
- get_force_input_port(self: pydrake.manipulation.SchunkWsgStatusSender) pydrake.systems.framework.InputPort
- get_state_input_port(self: pydrake.manipulation.SchunkWsgStatusSender) pydrake.systems.framework.InputPort
- class pydrake.manipulation.SimIiwaDriver
Bases:
pydrake.systems.framework.Diagram
SimIiwaDriver simulates the IIWA control and status interface using a MultibodyPlant.
Warning
This feature is considered to be experimental and may change or be removed at any time, without any deprecation notice ahead of time.
state→ generalized_contact_forces→ position (in kPositionOnly or kPositionAndTorque mode)→ torque (in kTorqueOnly or kPositionAndTorque mode)→ SimIiwaDriver → actuation → position_commanded → position_measured → velocity_estimated → state_estimated → torque_commanded → torque_measured → torque_external Ports shown in <b style=”color:orange”>orange</b> are intended to connect to the MultibodyPlant’s per-model-instance ports of the same name. All other ports are intended to mimic the LCM command and status message fields.
- __init__(self: pydrake.manipulation.SimIiwaDriver, control_mode: pydrake.manipulation.IiwaControlMode, controller_plant: drake::multibody::MultibodyPlant<double>, ext_joint_filter_tau: float, kp_gains: Optional[numpy.ndarray[numpy.float64[m, 1]]]) None
Constructs a diagram with the given parameters. A reference to the
controller_plant
is retained by this system, so thecontroller_plant
must outlivethis
.
- static AddToBuilder(builder: pydrake.systems.framework.DiagramBuilder, plant: drake::multibody::MultibodyPlant<double>, iiwa_instance: pydrake.multibody.tree.ModelInstanceIndex, controller_plant: drake::multibody::MultibodyPlant<double>, ext_joint_filter_tau: float, desired_iiwa_kp_gains: Optional[numpy.ndarray[numpy.float64[m, 1]]], control_mode: pydrake.manipulation.IiwaControlMode) pydrake.systems.framework.System
Given a
plant
(and associatediiwa_instance
) and abuilder
, installs in that builder theSimIiwaDriver
system to control and monitor an iiwa described bycontroller_plant
.The added
SimIiwaDriver
system is connected to the actuation input port, state and generalized contact forces output ports inplant
corresponding to the iiwa model.Returns the newly-added
SimIiwaDriver
System.Note: The Diagram will maintain an internal reference to
controller_plant
, so you must ensure thatcontroller_plant
has a longer lifetime than the Diagram.
- pydrake.manipulation.torque_enabled(control_mode: pydrake.manipulation.IiwaControlMode) bool
Reports if the given control
mode
includes torques.
- class pydrake.manipulation.ZeroForceDriver
A driver that applies zero actuation to every joint of a model. Useful for debugging and testing; useless in reality. No LCM channels are created.
- __init__(self: pydrake.manipulation.ZeroForceDriver, **kwargs) None