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.LeafSystemExpresses 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_graphsystems must have been added to the givenbuilderalready.- Parameter
acrobot_params: sets the parameters of the geometry registered with
scene_graph.
The
scene_graphpointer 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_graphsystems must have been added to the givenbuilderalready.Acrobot parameters are set to their default values.
The
scene_graphpointer 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.BasicVectorSpecializes BasicVector with specific getters and setters.
- __init__(self: pydrake.examples.AcrobotInput) None
Default constructor. Sets all rows to their default value:
taudefaults 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
tauis expressed in units of Nm.
- class pydrake.examples.AcrobotParams
Bases:
pydrake.systems.framework.BasicVectorSpecializes BasicVector with specific getters and setters.
- __init__(self: pydrake.examples.AcrobotParams) None
Default constructor. Sets all rows to their default value:
m1defaults to 1.0 kg.m2defaults to 1.0 kg.l1defaults to 1.0 m.l2defaults to 2.0 m.lc1defaults to 0.5 m.lc2defaults to 1.0 m.Ic1defaults to 0.083 kg*m^2.Ic2defaults to 0.33 kg*m^2.b1defaults to 0.1 kg*m^2/s.b2defaults to 0.1 kg*m^2/s.gravitydefaults to 9.81 m/s^2.
- b1(self: pydrake.examples.AcrobotParams) float
Damping coefficient of the shoulder joint.
Note
b1is expressed in units of kg*m^2/s.Note
b1has a limited domain of [0.0, +Inf].
- b2(self: pydrake.examples.AcrobotParams) float
Damping coefficient of the elbow joint.
Note
b2is expressed in units of kg*m^2/s.Note
b2has a limited domain of [0.0, +Inf].
- gravity(self: pydrake.examples.AcrobotParams) float
Gravitational constant.
Note
gravityis expressed in units of m/s^2.Note
gravityhas 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
Ic1is expressed in units of kg*m^2.Note
Ic1has 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
Ic2is expressed in units of kg*m^2.Note
Ic2has a limited domain of [0.0, +Inf].
- l1(self: pydrake.examples.AcrobotParams) float
Length of link 1.
Note
l1is expressed in units of m.Note
l1has 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
lc1is expressed in units of m.Note
lc1has 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
lc2is expressed in units of m.Note
lc2has a limited domain of [0.0, +Inf].
- m1(self: pydrake.examples.AcrobotParams) float
Mass of link 1.
Note
m1is expressed in units of kg.Note
m1has a limited domain of [0.0, +Inf].
- m2(self: pydrake.examples.AcrobotParams) float
Mass of link 2.
Note
m2is expressed in units of kg.Note
m2has 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.LeafSystemThe 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) pydrake.examples.AcrobotParams
- static get_mutable_state(context: pydrake.systems.framework.Context) pydrake.examples.AcrobotState
- get_parameters(self: pydrake.examples.AcrobotPlant, context: pydrake.systems.framework.Context) pydrake.examples.AcrobotParams
- static get_state(context: pydrake.systems.framework.Context) pydrake.examples.AcrobotState
- MassMatrix(self: pydrake.examples.AcrobotPlant, arg0: pydrake.systems.framework.Context) numpy.ndarray[numpy.float64[2, 2]]
- SetMitAcrobotParameters(self: pydrake.examples.AcrobotPlant, arg0: pydrake.examples.AcrobotParams) None
Sets the parameters to describe MIT Robot Locomotion Group’s hardware acrobot.
- class pydrake.examples.AcrobotSpongController
Bases:
pydrake.systems.framework.LeafSystemThe 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) pydrake.examples.SpongControllerParams
- get_parameters(self: pydrake.examples.AcrobotSpongController, context: pydrake.systems.framework.Context) pydrake.examples.SpongControllerParams
- class pydrake.examples.AcrobotState
Bases:
pydrake.systems.framework.BasicVectorSpecializes BasicVector with specific getters and setters.
- __init__(self: pydrake.examples.AcrobotState) None
Default constructor. Sets all rows to their default value:
theta1defaults to 0.0 rad.theta2defaults to 0.0 rad.theta1dotdefaults to 0.0 rad/s.theta2dotdefaults 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
theta1is expressed in units of rad.
- theta1dot(self: pydrake.examples.AcrobotState) float
The shoulder joint velocity
Note
theta1dotis expressed in units of rad/s.
- theta2(self: pydrake.examples.AcrobotState) float
The elbow joint angle
Note
theta2is expressed in units of rad.
- theta2dot(self: pydrake.examples.AcrobotState) float
The elbow joint velocity
Note
theta2dotis expressed in units of rad/s.
- class pydrake.examples.AcrobotWEncoder
Bases:
pydrake.systems.framework.DiagramConstructs the Acrobot with (only) encoder outputs.
elbow_torque→ AcrobotWEncoder → measured_joint_positions → acrobot_state The
acrobot_stateoutput port is present only if the construction parameteracrobot_state_as_second_outputis 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) pydrake.examples.AcrobotState
- class pydrake.examples.CompassGait
Bases:
pydrake.systems.framework.LeafSystemDynamical 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.BasicVectorSpecializes BasicVector with specific getters and setters.
- __init__(self: pydrake.examples.CompassGaitContinuousState) None
Default constructor. Sets all rows to their default value:
stancedefaults to 0.0 radians.swingdefaults to 0.0 radians.stancedotdefaults to 0.0 rad/sec.swingdotdefaults 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
stanceis expressed in units of radians.
- stancedot(self: pydrake.examples.CompassGaitContinuousState) float
The angular velocity of the stance leg.
Note
stancedotis 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
swingis expressed in units of radians.
- swingdot(self: pydrake.examples.CompassGaitContinuousState) float
The angular velocity of the swing leg.
Note
swingdotis expressed in units of rad/sec.
- class pydrake.examples.CompassGaitGeometry
Bases:
pydrake.systems.framework.LeafSystemExpresses 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_graphsystems must have been added to the givenbuilderalready. Thecompass_gait_paramssets 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_graphpointer 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_graphsystems must have been added to the givenbuilderalready. CompassGaitParams are set to their default values.The
scene_graphpointer 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.BasicVectorSpecializes BasicVector with specific getters and setters.
- __init__(self: pydrake.examples.CompassGaitParams) None
Default constructor. Sets all rows to their default value:
mass_hipdefaults to 10.0 kg.mass_legdefaults to 5.0 kg.length_legdefaults to 1.0 m.center_of_mass_legdefaults to 0.5 m.gravitydefaults to 9.81 m/s^2.slopedefaults 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_legis expressed in units of m.Note
center_of_mass_leghas a limited domain of [0.0, +Inf].
- gravity(self: pydrake.examples.CompassGaitParams) float
An approximate value for gravitational acceleration.
Note
gravityis expressed in units of m/s^2.Note
gravityhas a limited domain of [0.0, +Inf].
- length_leg(self: pydrake.examples.CompassGaitParams) float
The length of each leg.
Note
length_legis expressed in units of m.Note
length_leghas a limited domain of [0.0, +Inf].
- mass_hip(self: pydrake.examples.CompassGaitParams) float
Point mass at the hip.
Note
mass_hipis expressed in units of kg.Note
mass_hiphas 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_legis expressed in units of kg.Note
mass_leghas 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
slopeis expressed in units of radians.Note
slopehas a limited domain of [0.0, 1.5707].
- class pydrake.examples.PendulumGeometry
Bases:
pydrake.systems.framework.LeafSystemExpresses 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_graphsystems must have been added to the givenbuilderalready.The
scene_graphpointer 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.BasicVectorSpecializes BasicVector with specific getters and setters.
- __init__(self: pydrake.examples.PendulumInput) None
Default constructor. Sets all rows to their default value:
taudefaults 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
tauis 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
thiswith tau set to a new value.
- class pydrake.examples.PendulumParams
Bases:
pydrake.systems.framework.BasicVectorSpecializes BasicVector with specific getters and setters.
- __init__(self: pydrake.examples.PendulumParams) None
Default constructor. Sets all rows to their default value:
massdefaults to 1.0 kg.lengthdefaults to 0.5 m.dampingdefaults to 0.1 kg m^2/s.gravitydefaults to 9.81 m/s^2.
- damping(self: pydrake.examples.PendulumParams) float
The damping friction coefficient relating angular velocity to torque.
Note
dampingis expressed in units of kg m^2/s.Note
dampinghas a limited domain of [0.0, +Inf].
- gravity(self: pydrake.examples.PendulumParams) float
An approximate value for gravitational acceleration.
Note
gravityis expressed in units of m/s^2.Note
gravityhas a limited domain of [0.0, +Inf].
- length(self: pydrake.examples.PendulumParams) float
The length of the pendulum arm.
Note
lengthis expressed in units of m.Note
lengthhas 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
massis expressed in units of kg.Note
masshas 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
thiswith 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
thiswith 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
thiswith 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
thiswith mass set to a new value.
- class pydrake.examples.PendulumPlant
Bases:
pydrake.systems.framework.LeafSystemA 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) pydrake.examples.PendulumParams
- static get_mutable_state(context: pydrake.systems.framework.Context) pydrake.examples.PendulumState
- get_parameters(self: pydrake.examples.PendulumPlant, context: pydrake.systems.framework.Context) pydrake.examples.PendulumParams
- static get_state(context: pydrake.systems.framework.Context) pydrake.examples.PendulumState
- 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.BasicVectorSpecializes BasicVector with specific getters and setters.
- __init__(self: pydrake.examples.PendulumState) None
Default constructor. Sets all rows to their default value:
thetadefaults to 0.0 radians.thetadotdefaults 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
thetais expressed in units of radians.
- thetadot(self: pydrake.examples.PendulumState) float
The angular velocity of the pendulum.
Note
thetadotis 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
thiswith 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
thiswith thetadot set to a new value.
- class pydrake.examples.QuadrotorGeometry
Bases:
pydrake.systems.framework.LeafSystemExpresses 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_graphsystems must have been added to the givenbuilderalready.The
scene_graphpointer 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.LeafSystemThe 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.urdfmodel 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.LeafSystemDynamical 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_stateport). Discrete States: stance toe position (emitted atfloating_base_stateport), 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: pydrake.examples.RimlessWheelParams) 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.BasicVectorSpecializes BasicVector with specific getters and setters.
- __init__(self: pydrake.examples.RimlessWheelContinuousState) None
Default constructor. Sets all rows to their default value:
thetadefaults to 0.0 radians.thetadotdefaults 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
thetais expressed in units of radians.
- thetadot(self: pydrake.examples.RimlessWheelContinuousState) float
The angular velocity of the stance leg.
Note
thetadotis expressed in units of rad/sec.
- class pydrake.examples.RimlessWheelGeometry
Bases:
pydrake.systems.framework.LeafSystemExpresses 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_graphsystems must have been added to the givenbuilderalready. Therimless_wheel_paramssets the parameters of the geometry registered withscene_graph.The
scene_graphpointer 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_graphsystems must have been added to the givenbuilderalready. RimlessWheelParams are set to their default values.The
scene_graphpointer 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.BasicVectorSpecializes BasicVector with specific getters and setters.
- __init__(self: pydrake.examples.RimlessWheelParams) None
Default constructor. Sets all rows to their default value:
massdefaults to 1.0 kg.lengthdefaults to 1.0 m.gravitydefaults to 9.81 m/s^2.number_of_spokesdefaults to 8 integer.slopedefaults to 0.08 radians.
- gravity(self: pydrake.examples.RimlessWheelParams) float
An approximate value for gravitational acceleration.
Note
gravityis expressed in units of m/s^2.Note
gravityhas a limited domain of [0.0, +Inf].
- length(self: pydrake.examples.RimlessWheelParams) float
The length of each spoke.
Note
lengthis expressed in units of m.Note
lengthhas 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
massis expressed in units of kg.Note
masshas 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_spokesis expressed in units of integer.Note
number_of_spokeshas 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
slopeis expressed in units of radians.
- class pydrake.examples.SpongControllerParams
Bases:
pydrake.systems.framework.BasicVectorSpecializes BasicVector with specific getters and setters.
- __init__(self: pydrake.examples.SpongControllerParams) None
Default constructor. Sets all rows to their default value:
k_edefaults to 5.0 s.k_pdefaults to 50.0 s^-2.k_ddefaults to 5.0 s^-1.balancing_thresholddefaults to 1e3 None.
- balancing_threshold(self: pydrake.examples.SpongControllerParams) float
Cost value at which to switch from swing up to balancing.
Note
balancing_thresholdis expressed in units of None.Note
balancing_thresholdhas a limited domain of [0.0, +Inf].
- k_d(self: pydrake.examples.SpongControllerParams) float
Partial feedback linearization derivative gain.
Note
k_dis expressed in units of s^-1.Note
k_dhas a limited domain of [0.0, +Inf].
- k_e(self: pydrake.examples.SpongControllerParams) float
Energy shaping gain.
Note
k_eis expressed in units of s.Note
k_ehas a limited domain of [0.0, +Inf].
- k_p(self: pydrake.examples.SpongControllerParams) float
Partial feedback linearization proportional gain.
Note
k_pis expressed in units of s^-2.Note
k_phas 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.LeafSystemvan 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).