pydrake.examples
Provides bindings of existing C++ example library code as well as a few pure Python examples.
- class pydrake.examples.AcrobotGeometry
Bases:
pydrake.systems.framework.LeafSystem
Expresses an AcrobotPlant’s geometry to a SceneGraph.
state→ AcrobotGeometry → geometry_pose This class has no public constructor; instead use the AddToBuilder() static method to create and add it to a DiagramBuilder directly.
- __init__(*args, **kwargs)
- static AddToBuilder(*args, **kwargs)
Overloaded function.
AddToBuilder(builder: pydrake.systems.framework.DiagramBuilder, acrobot_state_port: pydrake.systems.framework.OutputPort, acrobot_params: pydrake.examples.AcrobotParams, scene_graph: pydrake.geometry.SceneGraph) -> pydrake.examples.AcrobotGeometry
Creates, adds, and connects an AcrobotGeometry system into the given
builder
. Both theacrobot_state.get_system()
andscene_graph
systems must have been added to the givenbuilder
already.- Parameter
acrobot_params
: sets the parameters of the geometry registered with
scene_graph
.
The
scene_graph
pointer is not retained by the AcrobotGeometry system. The return value pointer is an alias of the new AcrobotGeometry system that is owned by thebuilder
.AddToBuilder(builder: pydrake.systems.framework.DiagramBuilder, acrobot_state_port: pydrake.systems.framework.OutputPort, scene_graph: pydrake.geometry.SceneGraph) -> pydrake.examples.AcrobotGeometry
Creates, adds, and connects an AcrobotGeometry system into the given
builder
. Both theacrobot_state.get_system()
andscene_graph
systems must have been added to the givenbuilder
already.Acrobot parameters are set to their default values.
The
scene_graph
pointer is not retained by the AcrobotGeometry system. The return value pointer is an alias of the new AcrobotGeometry system that is owned by thebuilder
.
- class pydrake.examples.AcrobotInput
Bases:
pydrake.systems.framework.BasicVector
Specializes BasicVector with specific getters and setters.
- __init__(self: pydrake.examples.AcrobotInput) None
Default constructor. Sets all rows to their default value:
tau
defaults to 0.0 Nm.
- set_tau(self: pydrake.examples.AcrobotInput, arg0: float) None
Setter that matches tau().
- tau(self: pydrake.examples.AcrobotInput) float
Torque at the elbow
Note
tau
is expressed in units of Nm.
- class pydrake.examples.AcrobotParams
Bases:
pydrake.systems.framework.BasicVector
Specializes BasicVector with specific getters and setters.
- __init__(self: pydrake.examples.AcrobotParams) None
Default constructor. Sets all rows to their default value:
m1
defaults to 1.0 kg.m2
defaults to 1.0 kg.l1
defaults to 1.0 m.l2
defaults to 2.0 m.lc1
defaults to 0.5 m.lc2
defaults to 1.0 m.Ic1
defaults to 0.083 kg*m^2.Ic2
defaults to 0.33 kg*m^2.b1
defaults to 0.1 kg*m^2/s.b2
defaults to 0.1 kg*m^2/s.gravity
defaults to 9.81 m/s^2.
- b1(self: pydrake.examples.AcrobotParams) float
Damping coefficient of the shoulder joint.
Note
b1
is expressed in units of kg*m^2/s.Note
b1
has a limited domain of [0.0, +Inf].
- b2(self: pydrake.examples.AcrobotParams) float
Damping coefficient of the elbow joint.
Note
b2
is expressed in units of kg*m^2/s.Note
b2
has a limited domain of [0.0, +Inf].
- gravity(self: pydrake.examples.AcrobotParams) float
Gravitational constant.
Note
gravity
is expressed in units of m/s^2.Note
gravity
has a limited domain of [0.0, +Inf].
- Ic1(self: pydrake.examples.AcrobotParams) float
Inertia of link 1 about the center of mass of link 1.
Note
Ic1
is expressed in units of kg*m^2.Note
Ic1
has a limited domain of [0.0, +Inf].
- Ic2(self: pydrake.examples.AcrobotParams) float
Inertia of link 2 about the center of mass of link 2.
Note
Ic2
is expressed in units of kg*m^2.Note
Ic2
has a limited domain of [0.0, +Inf].
- l1(self: pydrake.examples.AcrobotParams) float
Length of link 1.
Note
l1
is expressed in units of m.Note
l1
has a limited domain of [0.0, +Inf].
- lc1(self: pydrake.examples.AcrobotParams) float
Vertical distance from shoulder joint to center of mass of link 1.
Note
lc1
is expressed in units of m.Note
lc1
has a limited domain of [0.0, +Inf].
- lc2(self: pydrake.examples.AcrobotParams) float
Vertical distance from elbow joint to center of mass of link 1.
Note
lc2
is expressed in units of m.Note
lc2
has a limited domain of [0.0, +Inf].
- m1(self: pydrake.examples.AcrobotParams) float
Mass of link 1.
Note
m1
is expressed in units of kg.Note
m1
has a limited domain of [0.0, +Inf].
- m2(self: pydrake.examples.AcrobotParams) float
Mass of link 2.
Note
m2
is expressed in units of kg.Note
m2
has a limited domain of [0.0, +Inf].
- set_b1(self: pydrake.examples.AcrobotParams, arg0: float) None
Setter that matches b1().
- set_b2(self: pydrake.examples.AcrobotParams, arg0: float) None
Setter that matches b2().
- set_gravity(self: pydrake.examples.AcrobotParams, arg0: float) None
Setter that matches gravity().
- set_Ic1(self: pydrake.examples.AcrobotParams, arg0: float) None
Setter that matches Ic1().
- set_Ic2(self: pydrake.examples.AcrobotParams, arg0: float) None
Setter that matches Ic2().
- set_l1(self: pydrake.examples.AcrobotParams, arg0: float) None
Setter that matches l1().
- set_lc1(self: pydrake.examples.AcrobotParams, arg0: float) None
Setter that matches lc1().
- set_lc2(self: pydrake.examples.AcrobotParams, arg0: float) None
Setter that matches lc2().
- set_m1(self: pydrake.examples.AcrobotParams, arg0: float) None
Setter that matches m1().
- set_m2(self: pydrake.examples.AcrobotParams, arg0: float) None
Setter that matches m2().
- class pydrake.examples.AcrobotPlant
Bases:
pydrake.systems.framework.LeafSystem
The Acrobot - a canonical underactuated system as described in <a href=”http://underactuated.mit.edu/underactuated.html?chapter=3”>Chapter 3 of Underactuated Robotics</a>.
elbow_torque (optional)→ AcrobotPlant → acrobot_state Note: If the elbow_torque input port is not connected, then the torque is taken to be zero.
- __init__(self: pydrake.examples.AcrobotPlant) None
Constructs the plant. The parameters of the system are stored as Parameters in the Context (see acrobot_params.h).
- DynamicsBiasTerm(self: pydrake.examples.AcrobotPlant, arg0: pydrake.systems.framework.Context) numpy.ndarray[numpy.float64[2, 1]]
Manipulator equation of Acrobot: M(q)q̈ + bias(q,q̇) = B*u.
M[2x2] is the mass matrix. - bias[2x1] includes the Coriolis term,
gravity term and the damping term, i.e. bias[2x1] = C(q,v)*v - τ_g(q) + [b1*q̇₁;b2*q̇₂].
- get_mutable_parameters(self: pydrake.examples.AcrobotPlant, context: pydrake.systems.framework.Context) drake::examples::acrobot::AcrobotParams<double>
- static get_mutable_state(context: pydrake.systems.framework.Context) drake::examples::acrobot::AcrobotState<double>
- get_parameters(self: pydrake.examples.AcrobotPlant, context: pydrake.systems.framework.Context) drake::examples::acrobot::AcrobotParams<double>
- static get_state(context: pydrake.systems.framework.Context) drake::examples::acrobot::AcrobotState<double>
- MassMatrix(self: pydrake.examples.AcrobotPlant, arg0: pydrake.systems.framework.Context) numpy.ndarray[numpy.float64[2, 2]]
- SetMitAcrobotParameters(self: pydrake.examples.AcrobotPlant, arg0: drake::examples::acrobot::AcrobotParams<double>) None
Sets the parameters to describe MIT Robot Locomotion Group’s hardware acrobot.
- class pydrake.examples.AcrobotSpongController
Bases:
pydrake.systems.framework.LeafSystem
The Spong acrobot swing-up controller as described in: Spong, Mark W. “Swing up control of the acrobot.” Robotics and Automation, 1994. Proceedings., 1994 IEEE International Conference on. IEEE, 1994.
Note that the Spong controller works well on the default set of parameters, which Spong used in his paper. In contrast, it is difficult to find a functional set of gains to stabilize the robot about its upright fixed point using the parameters of the physical robot we have in lab.
acrobot_state→ AcrobotSpongController → elbow_torque - __init__(self: pydrake.examples.AcrobotSpongController) None
- get_mutable_parameters(self: pydrake.examples.AcrobotSpongController, context: pydrake.systems.framework.Context) drake::examples::acrobot::SpongControllerParams<double>
- get_parameters(self: pydrake.examples.AcrobotSpongController, context: pydrake.systems.framework.Context) drake::examples::acrobot::SpongControllerParams<double>
- class pydrake.examples.AcrobotState
Bases:
pydrake.systems.framework.BasicVector
Specializes BasicVector with specific getters and setters.
- __init__(self: pydrake.examples.AcrobotState) None
Default constructor. Sets all rows to their default value:
theta1
defaults to 0.0 rad.theta2
defaults to 0.0 rad.theta1dot
defaults to 0.0 rad/s.theta2dot
defaults to 0.0 rad/s.
- set_theta1(self: pydrake.examples.AcrobotState, arg0: float) None
Setter that matches theta1().
- set_theta1dot(self: pydrake.examples.AcrobotState, arg0: float) None
Setter that matches theta1dot().
- set_theta2(self: pydrake.examples.AcrobotState, arg0: float) None
Setter that matches theta2().
- set_theta2dot(self: pydrake.examples.AcrobotState, arg0: float) None
Setter that matches theta2dot().
- theta1(self: pydrake.examples.AcrobotState) float
The shoulder joint angle
Note
theta1
is expressed in units of rad.
- theta1dot(self: pydrake.examples.AcrobotState) float
The shoulder joint velocity
Note
theta1dot
is expressed in units of rad/s.
- theta2(self: pydrake.examples.AcrobotState) float
The elbow joint angle
Note
theta2
is expressed in units of rad.
- theta2dot(self: pydrake.examples.AcrobotState) float
The elbow joint velocity
Note
theta2dot
is expressed in units of rad/s.
- class pydrake.examples.AcrobotWEncoder
Bases:
pydrake.systems.framework.Diagram
Constructs the Acrobot with (only) encoder outputs.
elbow_torque→ AcrobotWEncoder → measured_joint_positions → acrobot_state The
acrobot_state
output port is present only if the construction parameteracrobot_state_as_second_output
is true.- __init__(self: pydrake.examples.AcrobotWEncoder, acrobot_state_as_second_output: bool = False) None
- acrobot_plant(self: pydrake.examples.AcrobotWEncoder) pydrake.examples.AcrobotPlant
- get_mutable_acrobot_state(self: pydrake.examples.AcrobotWEncoder, context: pydrake.systems.framework.Context) drake::examples::acrobot::AcrobotState<double>
- class pydrake.examples.CompassGait
Bases:
pydrake.systems.framework.LeafSystem
Dynamical representation of the idealized hybrid dynamics of a “compass gait”, as described in http://underactuated.mit.edu/underactuated.html?chapter=simple_legs . This implementation has two additional state variables that are not required in the mathematical model:
a discrete state for the position of the stance toe along the ramp
a Boolean indicator for “left support” (true when the stance leg is the left leg).
These are helpful for outputting the floating-base model coordinate, e.g. for visualization.
Note
This model only supports walking downhill on the ramp, because that restriction enables a clean / numerically robust implementation of the foot collision witness function that avoids fall detection on the “foot scuffing” collision.
hip_torque (optional)→ CompassGait → minimal_state → floating_base_state Continuous States: stance, swing, stancedot, swingdot.
Discrete State: stance toe position.
Abstract State: left support indicator.
Note: If the hip_torque input port is not connected, then the torque is taken to be zero.
- __init__(self: pydrake.examples.CompassGait) None
Constructs the plant.
- get_floating_base_state_output_port(self: pydrake.examples.CompassGait) pydrake.systems.framework.OutputPort
Returns reference to the output port that provides the state in the floating-base coordinates (described via left leg xyz & rpy + hip angle + derivatives).
- get_minimal_state_output_port(self: pydrake.examples.CompassGait) pydrake.systems.framework.OutputPort
Returns reference to the output port that publishes only [theta_stance, theta_swing, thetatdot_stance, thetadot_swing].
- class pydrake.examples.CompassGaitContinuousState
Bases:
pydrake.systems.framework.BasicVector
Specializes BasicVector with specific getters and setters.
- __init__(self: pydrake.examples.CompassGaitContinuousState) None
Default constructor. Sets all rows to their default value:
stance
defaults to 0.0 radians.swing
defaults to 0.0 radians.stancedot
defaults to 0.0 rad/sec.swingdot
defaults to 0.0 rad/sec.
- set_stance(self: pydrake.examples.CompassGaitContinuousState, arg0: float) None
Setter that matches stance().
- set_stancedot(self: pydrake.examples.CompassGaitContinuousState, arg0: float) None
Setter that matches stancedot().
- set_swing(self: pydrake.examples.CompassGaitContinuousState, arg0: float) None
Setter that matches swing().
- set_swingdot(self: pydrake.examples.CompassGaitContinuousState, arg0: float) None
Setter that matches swingdot().
- stance(self: pydrake.examples.CompassGaitContinuousState) float
The orientation of the stance leg, measured clockwise from the vertical axis.
Note
stance
is expressed in units of radians.
- stancedot(self: pydrake.examples.CompassGaitContinuousState) float
The angular velocity of the stance leg.
Note
stancedot
is expressed in units of rad/sec.
- swing(self: pydrake.examples.CompassGaitContinuousState) float
The orientation of the swing leg, measured clockwise from the vertical axis.
Note
swing
is expressed in units of radians.
- swingdot(self: pydrake.examples.CompassGaitContinuousState) float
The angular velocity of the swing leg.
Note
swingdot
is expressed in units of rad/sec.
- class pydrake.examples.CompassGaitGeometry
Bases:
pydrake.systems.framework.LeafSystem
Expresses a CompassGait’s geometry to a SceneGraph.
floating_base_state→ CompassGaitGeometry → geometry_pose This class has no public constructor; instead use the AddToBuilder() static method to create and add it to a DiagramBuilder directly.
- __init__(*args, **kwargs)
- static AddToBuilder(*args, **kwargs)
Overloaded function.
AddToBuilder(builder: pydrake.systems.framework.DiagramBuilder, floating_base_state_port: pydrake.systems.framework.OutputPort, compass_gait_params: pydrake.examples.CompassGaitParams, scene_graph: pydrake.geometry.SceneGraph) -> pydrake.examples.CompassGaitGeometry
Creates, adds, and connects a CompassGaitGeometry system into the given
builder
. Both thefloating_base_state_port.get_system()
andscene_graph
systems must have been added to the givenbuilder
already. Thecompass_gait_params
sets the parameters of the geometry registered withscene_graph
; the visualization changes based on the leg length and the ration of leg mass to hip mass (the leg mass sphere is scaled assuming a constant density).The
scene_graph
pointer is not retained by the CompassGaitGeometry system. The return value pointer is an alias of the new CompassGaitGeometry system that is owned by thebuilder
.AddToBuilder(builder: pydrake.systems.framework.DiagramBuilder, floating_base_state_port: pydrake.systems.framework.OutputPort, scene_graph: pydrake.geometry.SceneGraph) -> pydrake.examples.CompassGaitGeometry
Creates, adds, and connects a CompassGaitGeometry system into the given
builder
. Both thefloating_base_state_port.get_system()
andscene_graph
systems must have been added to the givenbuilder
already. CompassGaitParams are set to their default values.The
scene_graph
pointer is not retained by the CompassGaitGeometry system. The return value pointer is an alias of the new CompassGaitGeometry system that is owned by thebuilder
.
- class pydrake.examples.CompassGaitParams
Bases:
pydrake.systems.framework.BasicVector
Specializes BasicVector with specific getters and setters.
- __init__(self: pydrake.examples.CompassGaitParams) None
Default constructor. Sets all rows to their default value:
mass_hip
defaults to 10.0 kg.mass_leg
defaults to 5.0 kg.length_leg
defaults to 1.0 m.center_of_mass_leg
defaults to 0.5 m.gravity
defaults to 9.81 m/s^2.slope
defaults to 0.0525 radians.
- center_of_mass_leg(self: pydrake.examples.CompassGaitParams) float
Distance from the hip to the center of mass of each leg.
Note
center_of_mass_leg
is expressed in units of m.Note
center_of_mass_leg
has a limited domain of [0.0, +Inf].
- gravity(self: pydrake.examples.CompassGaitParams) float
An approximate value for gravitational acceleration.
Note
gravity
is expressed in units of m/s^2.Note
gravity
has a limited domain of [0.0, +Inf].
- length_leg(self: pydrake.examples.CompassGaitParams) float
The length of each leg.
Note
length_leg
is expressed in units of m.Note
length_leg
has a limited domain of [0.0, +Inf].
- mass_hip(self: pydrake.examples.CompassGaitParams) float
Point mass at the hip.
Note
mass_hip
is expressed in units of kg.Note
mass_hip
has a limited domain of [0.0, +Inf].
- mass_leg(self: pydrake.examples.CompassGaitParams) float
Mass of each leg (modeled as a point mass at the center of mass).
Note
mass_leg
is expressed in units of kg.Note
mass_leg
has a limited domain of [0.0, +Inf].
- set_center_of_mass_leg(self: pydrake.examples.CompassGaitParams, arg0: float) None
Setter that matches center_of_mass_leg().
- set_gravity(self: pydrake.examples.CompassGaitParams, arg0: float) None
Setter that matches gravity().
- set_length_leg(self: pydrake.examples.CompassGaitParams, arg0: float) None
Setter that matches length_leg().
- set_mass_hip(self: pydrake.examples.CompassGaitParams, arg0: float) None
Setter that matches mass_hip().
- set_mass_leg(self: pydrake.examples.CompassGaitParams, arg0: float) None
Setter that matches mass_leg().
- set_slope(self: pydrake.examples.CompassGaitParams, arg0: float) None
Setter that matches slope().
- slope(self: pydrake.examples.CompassGaitParams) float
The angle of the ramp on which the compass gait is walking. Must have 0 <= slope < PI/2 so that forward == downhill (an assumption used in the foot collision witness function).
Note
slope
is expressed in units of radians.Note
slope
has a limited domain of [0.0, 1.5707].
- pydrake.examples.CreateClutterClearingYcbObjectList()
Creates a list of (model_file, pose) pairs to add six YCB objects to a ManipulationStation with the ClutterClearing setup.
- pydrake.examples.CreateManipulationClassYcbObjectList()
Creates a list of (model_file, pose) pairs to add five YCB objects to a ManipulationStation with the ManipulationClass setup.
- class pydrake.examples.IiwaCollisionModel
Determines which sdf is loaded for the IIWA in the ManipulationStation.
Members:
kNoCollision :
kBoxCollision :
- __init__(self: pydrake.examples.IiwaCollisionModel, value: int) None
- kBoxCollision = <IiwaCollisionModel.kBoxCollision: 1>
- kNoCollision = <IiwaCollisionModel.kNoCollision: 0>
- property name
- property value
- class pydrake.examples.ManipulationStation
Bases:
pydrake.systems.framework.Diagram
A system that represents the complete manipulation station, including exactly one robotic arm (a Kuka IIWA LWR), one gripper (a Schunk WSG 50), and anything a user might want to load into the model. SetupDefaultStation() provides the setup that is used in the MIT Intelligent Robot Manipulation class, which includes the supporting structure for IIWA and several RGBD cameras. Alternative Setup___() methods are provided, as well.
iiwa_position→ iiwa_feedforward_torque (optional)→ wsg_position→ wsg_force_limit (optional)→ applied_spatial_force (optional)→ ManipulationStation → iiwa_position_commanded → iiwa_position_measured → iiwa_velocity_estimated → iiwa_state_estimated → iiwa_torque_commanded → iiwa_torque_measured → iiwa_torque_external → wsg_state_measured → wsg_force_measured → camera_[NAME]_rgb_image → camera_[NAME]_depth_image → camera_[NAME]_label_image → camera_[NAME]_point_cloud → ... → camera_[NAME]_rgb_image → camera_[NAME]_depth_image → camera_[NAME]_label_image → camera_[NAME]_point_cloud → query_object → contact_results → plant_continuous_state → geometry_poses Each pixel in the output image from
depth_image
is a 16bit unsigned short in millimeters.Note that outputs in <b style=”color:orange”>orange</b> are available in the simulation, but not on the real robot. The distinction between q_measured and v_estimated is because the Kuka FRI reports positions directly, but we have estimated v in our code that wraps the FRI.
Warning
The “camera_[NAME]_point_cloud” data currently has registration errors per issue https://github.com/RobotLocomotion/drake/issues/12125.
Consider the robot dynamics M(q)vdot + C(q,v)v = τ_g(q) + τ_commanded + τ_joint_friction + τ_external, where q == position, v == velocity, and τ == torque.
This model of the IIWA internal controller in the FRI software’s
JointImpedanceControlMode
is:Click to expand C++ code...
τ_commanded = Mₑ(qₑ)vdot_desired + Cₑ(qₑ, vₑ)vₑ - τₑ_g(q) - τₑ_joint_friction + τ_feedforward vdot_desired = PID(q_commanded, qₑ, v_commanded, vₑ)
where Mₑ, Cₑ, τₑ_g, and τₑ_friction terms are now (Kuka’s) estimates of the true model, qₑ and vₑ are measured/estimation, and v_commanded must be obtained from an online (causal) derivative of q_commanded. The result is
Click to expand C++ code...
M(q)vdot ≈ Mₑ(q)vdot_desired + τ_feedforward + τ_external,
where the “approximately equal” comes from the differences due to the estimated model/state.
The model implemented in this System assumes that M, C, and τ_friction terms are perfect (except that they contain only a lumped mass approximation of the gripper), and that the measured signals are noise/bias free (e.g. q_measured = q, v_estimated = v, τ_measured = τ_commanded). What remains for τ_external is the generalized forces due to contact (note that they could also include the missing contributions from the gripper fingers, which the controller assumes are welded).
See also
lcmt_iiwa_status.lcm for additional details/documentation.
To add objects into the environment for the robot to manipulate, use, e.g.:
Click to expand C++ code...
ManipulationStation<double> station; Parser parser(&station.get_mutable_multibody_plant(), &station.get_mutable_scene_graph()); parser.AddModels("my.sdf"); ... // coming soon -- sugar API for adding additional objects. station.Finalize()
Note that you must call Finalize() before you can use this class as a System.
- __init__(self: pydrake.examples.ManipulationStation, time_step: float = 0.002) None
Construct the EMPTY station model.
- Parameter
time_step
: The time step used by MultibodyPlant<T>, and by the discrete derivative used to approximate velocity from the position command inputs.
- Parameter
- AddManipulandFromFile(self: pydrake.examples.ManipulationStation, model_file: str, X_WObject: pydrake.math.RigidTransform) None
Adds a single object for the robot to manipulate
Note
Must be called before Finalize().
- Parameter
model_file
: The path to the .sdf model file of the object.
- Parameter
X_WObject
: The pose of the object in world frame.
- Parameter
- Finalize(self: pydrake.examples.ManipulationStation) None
Users must call Finalize() after making any additions to the multibody plant and before using this class in the Systems framework. This should be called exactly once. This assumes an IIWA and WSG have been added to the MultibodyPlant, and RegisterIiwaControllerModel() and RegisterWsgControllerModel() have been called.
See also
multibody::MultibodyPlant<T>::Finalize()
- get_camera_names(self: pydrake.examples.ManipulationStation) list[str]
Get the camera names / unique ids.
- get_controller_plant(self: pydrake.examples.ManipulationStation) pydrake.multibody.plant.MultibodyPlant
Return a reference to the plant used by the inverse dynamics controller (which contains only a model of the iiwa + equivalent mass of the gripper).
- get_multibody_plant(self: pydrake.examples.ManipulationStation) pydrake.multibody.plant.MultibodyPlant
Returns a reference to the main plant responsible for the dynamics of the robot and the environment. This can be used to, e.g., add additional elements into the world before calling Finalize().
- get_mutable_multibody_plant(self: pydrake.examples.ManipulationStation) pydrake.multibody.plant.MultibodyPlant
Returns a mutable reference to the main plant responsible for the dynamics of the robot and the environment. This can be used to, e.g., add additional elements into the world before calling Finalize().
- get_mutable_scene_graph(self: pydrake.examples.ManipulationStation) pydrake.geometry.SceneGraph
Returns a mutable reference to the SceneGraph responsible for all of the geometry for the robot and the environment. This can be used to, e.g., add additional elements into the world before calling Finalize().
- get_scene_graph(self: pydrake.examples.ManipulationStation) pydrake.geometry.SceneGraph
Returns a reference to the SceneGraph responsible for all of the geometry for the robot and the environment. This can be used to, e.g., add additional elements into the world before calling Finalize().
- GetIiwaPosition(self: pydrake.examples.ManipulationStation, arg0: pydrake.systems.framework.Context) numpy.ndarray[numpy.float64[m, 1]]
Convenience method for getting all of the joint angles of the Kuka IIWA. This does not include the gripper.
- GetIiwaVelocity(self: pydrake.examples.ManipulationStation, arg0: pydrake.systems.framework.Context) numpy.ndarray[numpy.float64[m, 1]]
Convenience method for getting all of the joint velocities of the Kuka
- GetStaticCameraPosesInWorld(self: pydrake.examples.ManipulationStation) dict[str, pydrake.math.RigidTransform]
Returns a map from camera name to X_WCameraBody for all the static (rigidly attached to the world body) cameras that have been registered.
- GetWsgPosition(self: pydrake.examples.ManipulationStation, arg0: pydrake.systems.framework.Context) float
Convenience method for getting the position of the Schunk WSG. Note that the WSG position is the signed distance between the two fingers (not the state of the fingers individually).
- GetWsgVelocity(self: pydrake.examples.ManipulationStation, arg0: pydrake.systems.framework.Context) float
Convenience method for getting the velocity of the Schunk WSG.
- num_iiwa_joints(self: pydrake.examples.ManipulationStation) int
Gets the number of joints in the IIWA (only – does not include the gripper).
- Precondition:
must call one of the “setup” methods first to register an IIWA model.
- RegisterIiwaControllerModel(self: pydrake.examples.ManipulationStation, arg0: str, arg1: pydrake.multibody.tree.ModelInstanceIndex, arg2: pydrake.multibody.tree.Frame, arg3: pydrake.multibody.tree.Frame, arg4: pydrake.math.RigidTransform) None
- RegisterRgbdSensor(*args, **kwargs)
Overloaded function.
RegisterRgbdSensor(self: pydrake.examples.ManipulationStation, arg0: str, arg1: pydrake.multibody.tree.Frame, arg2: pydrake.math.RigidTransform, arg3: pydrake.geometry.DepthRenderCamera) -> None
Registers an RGBD sensor. Must be called before Finalize().
- Parameter
name
: Name for the camera.
- Parameter
parent_frame
: The parent frame (frame P). The body that
parent_frame
is attached to must have a corresponding geometry::FrameId. Otherwise, an exception will be thrown in Finalize().- Parameter
X_PCameraBody
: Transformation between frame P and the camera body. see systems::sensors:::RgbdSensor for descriptions about how the camera body, RGB, and depth image frames are related.
- Parameter
depth_camera
: Specification for the RGBD camera. The color render camera is inferred from the depth_camera. The color camera will share the RenderCameraCore and be configured to not show its window.
RegisterRgbdSensor(self: pydrake.examples.ManipulationStation, arg0: str, arg1: pydrake.multibody.tree.Frame, arg2: pydrake.math.RigidTransform, arg3: pydrake.geometry.ColorRenderCamera, arg4: pydrake.geometry.DepthRenderCamera) -> None
Registers an RGBD sensor with uniquely characterized color/label and depth cameras.
- RegisterWsgControllerModel(self: pydrake.examples.ManipulationStation, arg0: str, arg1: pydrake.multibody.tree.ModelInstanceIndex, arg2: pydrake.multibody.tree.Frame, arg3: pydrake.multibody.tree.Frame, arg4: pydrake.math.RigidTransform) None
- SetIiwaIntegralGains(self: pydrake.examples.ManipulationStation, arg0: numpy.ndarray[numpy.float64[m, 1]]) None
Set the integral gains for the IIWA controller.
- Raises
RuntimeError if Finalize() has been called. –
- SetIiwaPosition(self: pydrake.examples.ManipulationStation, station_context: pydrake.systems.framework.Context, q: numpy.ndarray[numpy.float64[m, 1]]) None
Convenience method for setting all of the joint angles of the Kuka IIWA. Also sets the position history in the velocity command generator.
q
must have size num_iiwa_joints().
- SetIiwaPositionGains(self: pydrake.examples.ManipulationStation, arg0: numpy.ndarray[numpy.float64[m, 1]]) None
Set the position gains for the IIWA controller.
- Raises
RuntimeError if Finalize() has been called. –
- SetIiwaVelocity(self: pydrake.examples.ManipulationStation, station_context: pydrake.systems.framework.Context, v: numpy.ndarray[numpy.float64[m, 1]]) None
Convenience method for setting all of the joint velocities of the Kuka IIWA. @v must have size num_iiwa_joints().
- SetIiwaVelocityGains(self: pydrake.examples.ManipulationStation, arg0: numpy.ndarray[numpy.float64[m, 1]]) None
Set the velocity gains for the IIWA controller.
- Raises
RuntimeError if Finalize() has been called. –
- SetupClutterClearingStation(self: pydrake.examples.ManipulationStation, X_WCameraBody: Optional[pydrake.math.RigidTransform] = None, collision_model: pydrake.examples.IiwaCollisionModel = <IiwaCollisionModel.kNoCollision: 0>, schunk_model: pydrake.examples.SchunkCollisionModel = <SchunkCollisionModel.kBox: 0>) None
Adds a default iiwa, wsg, two bins, and a camera, then calls RegisterIiwaControllerModel() and RegisterWsgControllerModel() with the appropriate arguments.
Note
Must be called before Finalize().
Note
Only one of the
Setup___()
methods should be called.- Parameter
X_WCameraBody
: Transformation between the world and the camera body.
- Parameter
collision_model
: Determines which sdf is loaded for the IIWA.
- Parameter
schunk_model
: Determines which sdf is loaded for the Schunk.
- Parameter
- SetupManipulationClassStation(self: pydrake.examples.ManipulationStation, collision_model: pydrake.examples.IiwaCollisionModel = <IiwaCollisionModel.kNoCollision: 0>, schunk_model: pydrake.examples.SchunkCollisionModel = <SchunkCollisionModel.kBox: 0>) None
Adds a default iiwa, wsg, cupboard, and 80/20 frame for the MIT Intelligent Robot Manipulation class, then calls RegisterIiwaControllerModel() and RegisterWsgControllerModel() with the appropriate arguments.
Note
Must be called before Finalize().
Note
Only one of the
Setup___()
methods should be called.- Parameter
collision_model
: Determines which sdf is loaded for the IIWA.
- Parameter
schunk_model
: Determines which sdf is loaded for the Schunk.
- Parameter
- SetupPlanarIiwaStation(self: pydrake.examples.ManipulationStation, schunk_model: pydrake.examples.SchunkCollisionModel = <SchunkCollisionModel.kBox: 0>) None
Adds a version of the iiwa with joints that would result in out-of-plane rotations welded in a fixed orientation, reducing the total degrees of freedom of the arm to 3. This arm lives in the X-Z plane. Also adds the WSG planar gripper and two tables to form the workspace. Note that additional floating base objects (aka manipulands) will still potentially move in 3D.
Note
Must be called before Finalize().
Note
Only one of the
Setup___()
methods should be called.- Parameter
schunk_model
: Determines which sdf is loaded for the Schunk.
- Parameter
- SetWsgGains(self: pydrake.examples.ManipulationStation, arg0: float, arg1: float) None
Set the gains for the WSG controller.
- Raises
RuntimeError if Finalize() has been called. –
- SetWsgPosition(self: pydrake.examples.ManipulationStation, station_context: pydrake.systems.framework.Context, q: float) None
Convenience method for setting the position of the Schunk WSG. Also sets the position history in the velocity interpolator. Note that the WSG position is the signed distance between the two fingers (not the state of the fingers individually).
- SetWsgVelocity(self: pydrake.examples.ManipulationStation, station_context: pydrake.systems.framework.Context, v: float) None
Convenience method for setting the velocity of the Schunk WSG.
- class pydrake.examples.ManipulationStationHardwareInterface
Bases:
pydrake.systems.framework.Diagram
A System that connects via message-passing to the hardware manipulation station.
Note: Users must call Connect() after initialization.
iiwa_position→ iiwa_feedforward_torque→ wsg_position→ wsg_force_limit (optional)→ ManipulationStationHardwareInterface → iiwa_position_commanded → iiwa_position_measured → iiwa_velocity_estimated → iiwa_torque_commanded → iiwa_torque_measured → iiwa_torque_external → wsg_state_measured → wsg_force_measured → camera_[NAME]_rgb_image → camera_[NAME]_depth_image → ... → camera_[NAME]_rgb_image → camera_[NAME]_depth_image - __init__(self: pydrake.examples.ManipulationStationHardwareInterface, camera_names: list[str] = []) None
Subscribes to an incoming camera message on the channel DRAKE_RGBD_CAMERA_IMAGES_<camera_id> where
camera_name
contains the names/unique ids, typically serial numbers, and declares the output ports camera_%s_rgb_image and camera_%s_depth_image, where s is the camera name.
- Connect(self: pydrake.examples.ManipulationStationHardwareInterface, wait_for_cameras: bool = True) None
Starts a thread to receive network messages, and blocks execution until the first messages have been received.
- get_camera_names(self: pydrake.examples.ManipulationStationHardwareInterface) list[str]
- get_controller_plant(self: pydrake.examples.ManipulationStationHardwareInterface) pydrake.multibody.plant.MultibodyPlant
For parity with ManipulationStation, we maintain a MultibodyPlant of the IIWA arm, with the lumped-mass equivalent spatial inertia of the Schunk WSG gripper.
- num_iiwa_joints(self: pydrake.examples.ManipulationStationHardwareInterface) int
Gets the number of joints in the IIWA (only – does not include the gripper).
- class pydrake.examples.PendulumGeometry
Bases:
pydrake.systems.framework.LeafSystem
Expresses a PendulumPlants’s geometry to a SceneGraph.
state→ PendulumGeometry → geometry_pose This class has no public constructor; instead use the AddToBuilder() static method to create and add it to a DiagramBuilder directly.
- __init__(*args, **kwargs)
- static AddToBuilder(builder: pydrake.systems.framework.DiagramBuilder, pendulum_state_port: pydrake.systems.framework.OutputPort, scene_graph: pydrake.geometry.SceneGraph) pydrake.examples.PendulumGeometry
Creates, adds, and connects a PendulumGeometry system into the given
builder
. Both thependulum_state.get_system()
andscene_graph
systems must have been added to the givenbuilder
already.The
scene_graph
pointer is not retained by the PendulumGeometry system. The return value pointer is an alias of the new PendulumGeometry system that is owned by thebuilder
.
- class pydrake.examples.PendulumInput
Bases:
pydrake.systems.framework.BasicVector
Specializes BasicVector with specific getters and setters.
- __init__(self: pydrake.examples.PendulumInput) None
Default constructor. Sets all rows to their default value:
tau
defaults to 0.0 Newton-meters.
- set_tau(self: pydrake.examples.PendulumInput, tau: float) None
Setter that matches tau().
- tau(self: pydrake.examples.PendulumInput) float
Torque at the joint.
Note
tau
is expressed in units of Newton-meters.
- with_tau(self: pydrake.examples.PendulumInput, tau: float) pydrake.examples.PendulumInput
Fluent setter that matches tau(). Returns a copy of
this
with tau set to a new value.
- class pydrake.examples.PendulumParams
Bases:
pydrake.systems.framework.BasicVector
Specializes BasicVector with specific getters and setters.
- __init__(self: pydrake.examples.PendulumParams) None
Default constructor. Sets all rows to their default value:
mass
defaults to 1.0 kg.length
defaults to 0.5 m.damping
defaults to 0.1 kg m^2/s.gravity
defaults to 9.81 m/s^2.
- damping(self: pydrake.examples.PendulumParams) float
The damping friction coefficient relating angular velocity to torque.
Note
damping
is expressed in units of kg m^2/s.Note
damping
has a limited domain of [0.0, +Inf].
- gravity(self: pydrake.examples.PendulumParams) float
An approximate value for gravitational acceleration.
Note
gravity
is expressed in units of m/s^2.Note
gravity
has a limited domain of [0.0, +Inf].
- length(self: pydrake.examples.PendulumParams) float
The length of the pendulum arm.
Note
length
is expressed in units of m.Note
length
has a limited domain of [0.0, +Inf].
- mass(self: pydrake.examples.PendulumParams) float
The simple pendulum has a single point mass at the end of the arm.
Note
mass
is expressed in units of kg.Note
mass
has a limited domain of [0.0, +Inf].
- set_damping(self: pydrake.examples.PendulumParams, damping: float) None
Setter that matches damping().
- set_gravity(self: pydrake.examples.PendulumParams, gravity: float) None
Setter that matches gravity().
- set_length(self: pydrake.examples.PendulumParams, length: float) None
Setter that matches length().
- set_mass(self: pydrake.examples.PendulumParams, mass: float) None
Setter that matches mass().
- with_damping(self: pydrake.examples.PendulumParams, damping: float) pydrake.examples.PendulumParams
Fluent setter that matches damping(). Returns a copy of
this
with damping set to a new value.
- with_gravity(self: pydrake.examples.PendulumParams, gravity: float) pydrake.examples.PendulumParams
Fluent setter that matches gravity(). Returns a copy of
this
with gravity set to a new value.
- with_length(self: pydrake.examples.PendulumParams, length: float) pydrake.examples.PendulumParams
Fluent setter that matches length(). Returns a copy of
this
with length set to a new value.
- with_mass(self: pydrake.examples.PendulumParams, mass: float) pydrake.examples.PendulumParams
Fluent setter that matches mass(). Returns a copy of
this
with mass set to a new value.
- class pydrake.examples.PendulumPlant
Bases:
pydrake.systems.framework.LeafSystem
A model of a simple pendulum
\[ml^2 \ddot\theta + b\dot\theta + mgl\sin\theta = \tau\]name: PendulumPlant input_ports: - tau (optional) output_ports: - state
Note: If the tau input port is not connected, then the torque is taken to be zero.
- __init__(self: pydrake.examples.PendulumPlant) None
Constructs a default plant.
- get_mutable_parameters(self: pydrake.examples.PendulumPlant, context: pydrake.systems.framework.Context) drake::examples::pendulum::PendulumParams<double>
- static get_mutable_state(context: pydrake.systems.framework.Context) drake::examples::pendulum::PendulumState<double>
- get_parameters(self: pydrake.examples.PendulumPlant, context: pydrake.systems.framework.Context) drake::examples::pendulum::PendulumParams<double>
- static get_state(context: pydrake.systems.framework.Context) drake::examples::pendulum::PendulumState<double>
- get_state_output_port(self: pydrake.examples.PendulumPlant) pydrake.systems.framework.OutputPort
Returns the port to output state.
- class pydrake.examples.PendulumState
Bases:
pydrake.systems.framework.BasicVector
Specializes BasicVector with specific getters and setters.
- __init__(self: pydrake.examples.PendulumState) None
Default constructor. Sets all rows to their default value:
theta
defaults to 0.0 radians.thetadot
defaults to 0.0 radians/sec.
- set_theta(self: pydrake.examples.PendulumState, theta: float) None
Setter that matches theta().
- set_thetadot(self: pydrake.examples.PendulumState, thetadot: float) None
Setter that matches thetadot().
- theta(self: pydrake.examples.PendulumState) float
The angle of the pendulum.
Note
theta
is expressed in units of radians.
- thetadot(self: pydrake.examples.PendulumState) float
The angular velocity of the pendulum.
Note
thetadot
is expressed in units of radians/sec.
- with_theta(self: pydrake.examples.PendulumState, theta: float) pydrake.examples.PendulumState
Fluent setter that matches theta(). Returns a copy of
this
with theta set to a new value.
- with_thetadot(self: pydrake.examples.PendulumState, thetadot: float) pydrake.examples.PendulumState
Fluent setter that matches thetadot(). Returns a copy of
this
with thetadot set to a new value.
- class pydrake.examples.QuadrotorGeometry
Bases:
pydrake.systems.framework.LeafSystem
Expresses a QuadrotorPlant’s geometry to a SceneGraph.
state→ QuadrotorGeometry → geometry_pose This class has no public constructor; instead use the AddToBuilder() static method to create and add it to a DiagramBuilder directly.
- __init__(*args, **kwargs)
- static AddToBuilder(builder: pydrake.systems.framework.DiagramBuilder, quadrotor_state_port: pydrake.systems.framework.OutputPort, scene_graph: pydrake.geometry.SceneGraph) pydrake.examples.QuadrotorGeometry
Creates, adds, and connects a QuadrotorGeometry system into the given
builder
. Both thequadrotor_state.get_system()
andscene_graph
systems must have been added to the givenbuilder
already.The
scene_graph
pointer is not retained by the QuadrotorGeometry system. The return value pointer is an alias of the new QuadrotorGeometry system that is owned by thebuilder
.
- get_frame_id(self: pydrake.examples.QuadrotorGeometry) pydrake.geometry.FrameId
Returns the frame of the geometry registered with a SceneGraph. This can be useful, e.g., if one would like to add a camera to the quadrotor.
- class pydrake.examples.QuadrotorPlant
Bases:
pydrake.systems.framework.LeafSystem
The Quadrotor - an underactuated aerial vehicle. This version of the Quadrotor is implemented to match the dynamics of the plant specified in the
package://drake_models/skydio_2/quadrotor.urdf
model file.propeller_force (optional)→ QuadrotorPlant → state Note: If the propeller_force input port is not connected, then the force is taken to be zero.
- __init__(*args, **kwargs)
Overloaded function.
__init__(self: pydrake.examples.QuadrotorPlant) -> None
__init__(self: pydrake.examples.QuadrotorPlant, m_arg: float, L_arg: float, I_arg: numpy.ndarray[numpy.float64[3, 3]], kF_arg: float, kM_arg: float) -> None
- force_constant(self: pydrake.examples.QuadrotorPlant) float
- g(self: pydrake.examples.QuadrotorPlant) float
- inertia(self: pydrake.examples.QuadrotorPlant) numpy.ndarray[numpy.float64[3, 3]]
- length(self: pydrake.examples.QuadrotorPlant) float
- m(self: pydrake.examples.QuadrotorPlant) float
- moment_constant(self: pydrake.examples.QuadrotorPlant) float
- class pydrake.examples.RimlessWheel
Bases:
pydrake.systems.framework.LeafSystem
Dynamical representation of the idealized hybrid dynamics of a “rimless wheel”, as described in http://underactuated.mit.edu/underactuated.html?chapter=simple_legs In addition, this model has two additional (discrete) state variables that are not required in the mathematical model:
the position of the stance toe along the ramp (helpful for outputting a floating-base model coordinate, e.g. for visualization),
a boolean indicator for “double support” (to avoid the numerical challenges of simulation around the Zeno phenomenon at the standing fixed point).
RimlessWheel → minimal_state → floating_base_state Continuous States: theta, thetadot (emitted at
minimal_state
port). Discrete States: stance toe position (emitted atfloating_base_state
port), double support indicator. Parameters: mass, length, number of spokes, etc, are all set as Context parameters using RimlessWheelParams.- __init__(self: pydrake.examples.RimlessWheel) None
Constructs the plant.
- static calc_alpha(params: drake::examples::rimless_wheel::RimlessWheelParams<double>) float
Alpha is half the interleg angle, and is used frequently.
- get_floating_base_state_output_port(self: pydrake.examples.RimlessWheel) pydrake.systems.framework.OutputPort
Returns reference to the output port that provides a 12 dimensional state (FloatingBaseType::kRollPitchYaw positions then velocities). This is useful, e.g., for visualization. θ of the rimless wheel is the pitch of the floating base (rotation around global y), and downhill moves toward positive x. As always, we use vehicle coordinates (x-y on the ground, z is up).
- get_minimal_state_output_port(self: pydrake.examples.RimlessWheel) pydrake.systems.framework.OutputPort
Return reference to the output port that publishes only [theta, thetatdot].
- class pydrake.examples.RimlessWheelContinuousState
Bases:
pydrake.systems.framework.BasicVector
Specializes BasicVector with specific getters and setters.
- __init__(self: pydrake.examples.RimlessWheelContinuousState) None
Default constructor. Sets all rows to their default value:
theta
defaults to 0.0 radians.thetadot
defaults to 0.0 rad/sec.
- set_theta(self: pydrake.examples.RimlessWheelContinuousState, arg0: float) None
Setter that matches theta().
- set_thetadot(self: pydrake.examples.RimlessWheelContinuousState, arg0: float) None
Setter that matches thetadot().
- theta(self: pydrake.examples.RimlessWheelContinuousState) float
The orientation of the stance leg, measured clockwise from the vertical axis.
Note
theta
is expressed in units of radians.
- thetadot(self: pydrake.examples.RimlessWheelContinuousState) float
The angular velocity of the stance leg.
Note
thetadot
is expressed in units of rad/sec.
- class pydrake.examples.RimlessWheelGeometry
Bases:
pydrake.systems.framework.LeafSystem
Expresses a RimlessWheel’s geometry to a SceneGraph.
floating_base_state→ RimlessWheelGeometry → geometry_pose This class has no public constructor; instead use the AddToBuilder() static method to create and add it to a DiagramBuilder directly.
- __init__(*args, **kwargs)
- static AddToBuilder(*args, **kwargs)
Overloaded function.
AddToBuilder(builder: pydrake.systems.framework.DiagramBuilder, floating_base_state_port: pydrake.systems.framework.OutputPort, rimless_wheel_params: pydrake.examples.RimlessWheelParams, scene_graph: pydrake.geometry.SceneGraph) -> pydrake.examples.RimlessWheelGeometry
Creates, adds, and connects a RimlessWheelGeometry system into the given
builder
. Both thefloating_base_state_port.get_system()
andscene_graph
systems must have been added to the givenbuilder
already. Therimless_wheel_params
sets the parameters of the geometry registered withscene_graph
.The
scene_graph
pointer is not retained by the RimlessWheelGeometry system. The return value pointer is an alias of the new RimlessWheelGeometry system that is owned by thebuilder
.AddToBuilder(builder: pydrake.systems.framework.DiagramBuilder, floating_base_state_port: pydrake.systems.framework.OutputPort, scene_graph: pydrake.geometry.SceneGraph) -> pydrake.examples.RimlessWheelGeometry
Creates, adds, and connects a RimlessWheelGeometry system into the given
builder
. Both thefloating_base_state_port.get_system()
andscene_graph
systems must have been added to the givenbuilder
already. RimlessWheelParams are set to their default values.The
scene_graph
pointer is not retained by the RimlessWheelGeometry system. The return value pointer is an alias of the new RimlessWheelGeometry system that is owned by thebuilder
.
- class pydrake.examples.RimlessWheelParams
Bases:
pydrake.systems.framework.BasicVector
Specializes BasicVector with specific getters and setters.
- __init__(self: pydrake.examples.RimlessWheelParams) None
Default constructor. Sets all rows to their default value:
mass
defaults to 1.0 kg.length
defaults to 1.0 m.gravity
defaults to 9.81 m/s^2.number_of_spokes
defaults to 8 integer.slope
defaults to 0.08 radians.
- gravity(self: pydrake.examples.RimlessWheelParams) float
An approximate value for gravitational acceleration.
Note
gravity
is expressed in units of m/s^2.Note
gravity
has a limited domain of [0.0, +Inf].
- length(self: pydrake.examples.RimlessWheelParams) float
The length of each spoke.
Note
length
is expressed in units of m.Note
length
has a limited domain of [0.0, +Inf].
- mass(self: pydrake.examples.RimlessWheelParams) float
The rimless wheel has a single point mass at the hub.
Note
mass
is expressed in units of kg.Note
mass
has a limited domain of [0.0, +Inf].
- number_of_spokes(self: pydrake.examples.RimlessWheelParams) float
Total number of spokes on the wheel
Note
number_of_spokes
is expressed in units of integer.Note
number_of_spokes
has a limited domain of [4, +Inf].
- set_gravity(self: pydrake.examples.RimlessWheelParams, arg0: float) None
Setter that matches gravity().
- set_length(self: pydrake.examples.RimlessWheelParams, arg0: float) None
Setter that matches length().
- set_mass(self: pydrake.examples.RimlessWheelParams, arg0: float) None
Setter that matches mass().
- set_number_of_spokes(self: pydrake.examples.RimlessWheelParams, arg0: float) None
Setter that matches number_of_spokes().
- set_slope(self: pydrake.examples.RimlessWheelParams, arg0: float) None
Setter that matches slope().
- slope(self: pydrake.examples.RimlessWheelParams) float
The angle of the ramp on which the rimless wheel is walking.
Note
slope
is expressed in units of radians.
- class pydrake.examples.SchunkCollisionModel
Determines which schunk model is used for the ManipulationStation. - kBox loads a model with a box collision geometry. This model is for those who want simplified collision behavior. - kBoxPlusFingertipSpheres loads a Schunk model with collision spheres that models the indentations at tip of the fingers, in addition to the box collision geometry on the fingers.
Members:
kBox :
kBoxPlusFingertipSpheres :
- __init__(self: pydrake.examples.SchunkCollisionModel, value: int) None
- kBox = <SchunkCollisionModel.kBox: 0>
- kBoxPlusFingertipSpheres = <SchunkCollisionModel.kBoxPlusFingertipSpheres: 1>
- property name
- property value
- class pydrake.examples.SpongControllerParams
Bases:
pydrake.systems.framework.BasicVector
Specializes BasicVector with specific getters and setters.
- __init__(self: pydrake.examples.SpongControllerParams) None
Default constructor. Sets all rows to their default value:
k_e
defaults to 5.0 s.k_p
defaults to 50.0 s^-2.k_d
defaults to 5.0 s^-1.balancing_threshold
defaults to 1e3 None.
- balancing_threshold(self: pydrake.examples.SpongControllerParams) float
Cost value at which to switch from swing up to balancing.
Note
balancing_threshold
is expressed in units of None.Note
balancing_threshold
has a limited domain of [0.0, +Inf].
- k_d(self: pydrake.examples.SpongControllerParams) float
Partial feedback linearization derivative gain.
Note
k_d
is expressed in units of s^-1.Note
k_d
has a limited domain of [0.0, +Inf].
- k_e(self: pydrake.examples.SpongControllerParams) float
Energy shaping gain.
Note
k_e
is expressed in units of s.Note
k_e
has a limited domain of [0.0, +Inf].
- k_p(self: pydrake.examples.SpongControllerParams) float
Partial feedback linearization proportional gain.
Note
k_p
is expressed in units of s^-2.Note
k_p
has a limited domain of [0.0, +Inf].
- set_balancing_threshold(self: pydrake.examples.SpongControllerParams, arg0: float) None
Setter that matches balancing_threshold().
- set_k_d(self: pydrake.examples.SpongControllerParams, arg0: float) None
Setter that matches k_d().
- set_k_e(self: pydrake.examples.SpongControllerParams, arg0: float) None
Setter that matches k_e().
- set_k_p(self: pydrake.examples.SpongControllerParams, arg0: float) None
Setter that matches k_p().
- pydrake.examples.StabilizingLQRController(quadrotor_plant: pydrake.examples.QuadrotorPlant, nominal_position: numpy.ndarray[numpy.float64[3, 1]]) pydrake.systems.primitives.AffineSystem
Generates an LQR controller to move to
nominal_position
. Internally computes the nominal input corresponding to a hover at positionx0
.See also
systems::LinearQuadraticRegulator.
- class pydrake.examples.VanDerPolOscillator
Bases:
pydrake.systems.framework.LeafSystem
van der Pol oscillator
The van der Pol oscillator, governed by the following equations: q̈ + μ(q² - 1)q̇ + q = 0, μ > 0 y₀ = q y₁ = [q,q̇]’ is a canonical example of a nonlinear system that exhibits a limit cycle stability. As such it serves as an important for examining nonlinear stability and stochastic stability.
(Examples involving region of attraction analysis and analyzing the stationary distribution of the oscillator under process noise are coming soon).
VanDerPolOscillator → y0 → y1 - __init__(self: pydrake.examples.VanDerPolOscillator) None
Constructs a default oscillator.
- static CalcLimitCycle() numpy.ndarray[numpy.float64[2, n]]
Returns a 2-row matrix containing the result of simulating the oscillator with the default mu=1 from (approximately) one point on the limit cycle for (approximately) one period. The first row is q, and the second row is q̇.
- get_full_state_output_port(self: pydrake.examples.VanDerPolOscillator) pydrake.systems.framework.OutputPort
Returns the output port containing the full state. This is provided primarily as a tool for debugging/visualization.
- get_position_output_port(self: pydrake.examples.VanDerPolOscillator) pydrake.systems.framework.OutputPort
Returns the output port containing the output configuration (only).