pydrake.multibody.plant
Bindings for MultibodyPlant and related classes.
- pydrake.multibody.plant.AddMultibodyPlant(*args, **kwargs)
Overloaded function.
AddMultibodyPlant(config: pydrake.multibody.plant.MultibodyPlantConfig, builder: pydrake.systems.framework.DiagramBuilder) -> tuple
Adds a new MultibodyPlant and SceneGraph to the given
builder
. The plant’s settings such astime_step
are set using the givenconfig
.AddMultibodyPlant(plant_config: pydrake.multibody.plant.MultibodyPlantConfig, scene_graph_config: pydrake.geometry.SceneGraphConfig, builder: pydrake.systems.framework.DiagramBuilder) -> tuple
Adds a new MultibodyPlant and SceneGraph to the given
builder
. The plant’s settings such astime_step
are set using the givenplant_config
. The scene graph’s settings are set using the givenscene_graph_config
.
- pydrake.multibody.plant.AddMultibodyPlantSceneGraph(*args, **kwargs)
Overloaded function.
AddMultibodyPlantSceneGraph(builder: pydrake.systems.framework.DiagramBuilder, plant: pydrake.multibody.plant.MultibodyPlant, scene_graph: pydrake.geometry.SceneGraph = None) -> tuple
Adds a MultibodyPlant and a SceneGraph instance to a diagram builder, connecting the geometry ports.
Note
Usage examples in add_multibody_plant_scene_graph “AddMultibodyPlantSceneGraph”.
- Parameter
builder
: Builder to add to.
- Parameter
plant
: Plant to be added to the builder.
- Parameter
scene_graph
: (optional) Constructed scene graph. If none is provided, one will be created and used.
- Returns
Pair of the registered plant and scene graph.
- Precondition:
builder
andplant
must be non-null.
AddMultibodyPlantSceneGraph(builder: pydrake.systems.framework.DiagramBuilder, time_step: float, scene_graph: pydrake.geometry.SceneGraph = None) -> tuple
Makes a new MultibodyPlant with discrete update period
time_step
and adds it to a diagram builder together with the provided SceneGraph instance, connecting the geometry ports.Note
Usage examples in add_multibody_plant_scene_graph “AddMultibodyPlantSceneGraph”.
- Parameter
builder
: Builder to add to.
- Parameter
time_step
: The discrete update period for the new MultibodyPlant to be added. Please refer to the documentation provided in MultibodyPlant::MultibodyPlant(double) for further details on the parameter
time_step
.- Parameter
scene_graph
: (optional) Constructed scene graph. If none is provided, one will be created and used.
- Returns
Pair of the registered plant and scene graph.
- Precondition:
builder
must be non-null.
AddMultibodyPlantSceneGraph(builder: pydrake.systems.framework.DiagramBuilder_[AutoDiffXd], plant: pydrake.multibody.plant.MultibodyPlant_[AutoDiffXd], scene_graph: pydrake.geometry.SceneGraph_[AutoDiffXd] = None) -> tuple
Adds a MultibodyPlant and a SceneGraph instance to a diagram builder, connecting the geometry ports.
Note
Usage examples in add_multibody_plant_scene_graph “AddMultibodyPlantSceneGraph”.
- Parameter
builder
: Builder to add to.
- Parameter
plant
: Plant to be added to the builder.
- Parameter
scene_graph
: (optional) Constructed scene graph. If none is provided, one will be created and used.
- Returns
Pair of the registered plant and scene graph.
- Precondition:
builder
andplant
must be non-null.
AddMultibodyPlantSceneGraph(builder: pydrake.systems.framework.DiagramBuilder_[AutoDiffXd], time_step: float, scene_graph: pydrake.geometry.SceneGraph_[AutoDiffXd] = None) -> tuple
Makes a new MultibodyPlant with discrete update period
time_step
and adds it to a diagram builder together with the provided SceneGraph instance, connecting the geometry ports.Note
Usage examples in add_multibody_plant_scene_graph “AddMultibodyPlantSceneGraph”.
- Parameter
builder
: Builder to add to.
- Parameter
time_step
: The discrete update period for the new MultibodyPlant to be added. Please refer to the documentation provided in MultibodyPlant::MultibodyPlant(double) for further details on the parameter
time_step
.- Parameter
scene_graph
: (optional) Constructed scene graph. If none is provided, one will be created and used.
- Returns
Pair of the registered plant and scene graph.
- Precondition:
builder
must be non-null.
AddMultibodyPlantSceneGraph(builder: pydrake.systems.framework.DiagramBuilder_[Expression], plant: pydrake.multibody.plant.MultibodyPlant_[Expression], scene_graph: pydrake.geometry.SceneGraph_[Expression] = None) -> tuple
Adds a MultibodyPlant and a SceneGraph instance to a diagram builder, connecting the geometry ports.
Note
Usage examples in add_multibody_plant_scene_graph “AddMultibodyPlantSceneGraph”.
- Parameter
builder
: Builder to add to.
- Parameter
plant
: Plant to be added to the builder.
- Parameter
scene_graph
: (optional) Constructed scene graph. If none is provided, one will be created and used.
- Returns
Pair of the registered plant and scene graph.
- Precondition:
builder
andplant
must be non-null.
AddMultibodyPlantSceneGraph(builder: pydrake.systems.framework.DiagramBuilder_[Expression], time_step: float, scene_graph: pydrake.geometry.SceneGraph_[Expression] = None) -> tuple
Makes a new MultibodyPlant with discrete update period
time_step
and adds it to a diagram builder together with the provided SceneGraph instance, connecting the geometry ports.Note
Usage examples in add_multibody_plant_scene_graph “AddMultibodyPlantSceneGraph”.
- Parameter
builder
: Builder to add to.
- Parameter
time_step
: The discrete update period for the new MultibodyPlant to be added. Please refer to the documentation provided in MultibodyPlant::MultibodyPlant(double) for further details on the parameter
time_step
.- Parameter
scene_graph
: (optional) Constructed scene graph. If none is provided, one will be created and used.
- Returns
Pair of the registered plant and scene graph.
- Precondition:
builder
must be non-null.
- pydrake.multibody.plant.ApplyMultibodyPlantConfig(config: pydrake.multibody.plant.MultibodyPlantConfig, plant: pydrake.multibody.plant.MultibodyPlant) None
Applies settings given in
config
to an existingplant
. Thetime_step
is the one value inconfig
that cannot be updated – it can only be set in the MultibodyPlant constructor. Consider using AddMultibodyPlant() or manually passingconfig.time_step
when you construct the MultibodyPlant.This method must be called pre-Finalize.
- Raises
RuntimeError if plant is finalized or if time_step is changed. –
- pydrake.multibody.plant.CalcContactFrictionFromSurfaceProperties(*args, **kwargs)
Overloaded function.
CalcContactFrictionFromSurfaceProperties(surface_properties1: pydrake.multibody.plant.CoulombFriction, surface_properties2: pydrake.multibody.plant.CoulombFriction) -> pydrake.multibody.plant.CoulombFriction
Given the surface properties of two different surfaces, this method computes the Coulomb’s law coefficients of friction characterizing the interaction by friction of the given surface pair. The surface properties are specified by individual Coulomb’s law coefficients of friction. As outlined in the class’s documentation for CoulombFriction, friction coefficients characterize a surface pair and not individual surfaces. However, we find it useful in practice to associate the abstract idea of friction coefficients to a single surface. Please refer to the documentation for CoulombFriction for details on this topic.
More specifically, this method computes the contact coefficients for the given surface pair as:
Click to expand C++ code...
μ = 2μₘμₙ/(μₘ + μₙ)
where the operation above is performed separately on the static and dynamic friction coefficients.
- Parameter
surface_properties1
: Surface properties for surface 1. Specified as an individual set of Coulomb’s law coefficients of friction.
- Parameter
surface_properties2
: Surface properties for surface 2. Specified as an individual set of Coulomb’s law coefficients of friction.
- Returns
the combined friction coefficients for the interacting surfaces.
CalcContactFrictionFromSurfaceProperties(surface_properties1: pydrake.multibody.plant.CoulombFriction_[AutoDiffXd], surface_properties2: pydrake.multibody.plant.CoulombFriction_[AutoDiffXd]) -> pydrake.multibody.plant.CoulombFriction_[AutoDiffXd]
Given the surface properties of two different surfaces, this method computes the Coulomb’s law coefficients of friction characterizing the interaction by friction of the given surface pair. The surface properties are specified by individual Coulomb’s law coefficients of friction. As outlined in the class’s documentation for CoulombFriction, friction coefficients characterize a surface pair and not individual surfaces. However, we find it useful in practice to associate the abstract idea of friction coefficients to a single surface. Please refer to the documentation for CoulombFriction for details on this topic.
More specifically, this method computes the contact coefficients for the given surface pair as:
Click to expand C++ code...
μ = 2μₘμₙ/(μₘ + μₙ)
where the operation above is performed separately on the static and dynamic friction coefficients.
- Parameter
surface_properties1
: Surface properties for surface 1. Specified as an individual set of Coulomb’s law coefficients of friction.
- Parameter
surface_properties2
: Surface properties for surface 2. Specified as an individual set of Coulomb’s law coefficients of friction.
- Returns
the combined friction coefficients for the interacting surfaces.
CalcContactFrictionFromSurfaceProperties(surface_properties1: pydrake.multibody.plant.CoulombFriction_[Expression], surface_properties2: pydrake.multibody.plant.CoulombFriction_[Expression]) -> pydrake.multibody.plant.CoulombFriction_[Expression]
Given the surface properties of two different surfaces, this method computes the Coulomb’s law coefficients of friction characterizing the interaction by friction of the given surface pair. The surface properties are specified by individual Coulomb’s law coefficients of friction. As outlined in the class’s documentation for CoulombFriction, friction coefficients characterize a surface pair and not individual surfaces. However, we find it useful in practice to associate the abstract idea of friction coefficients to a single surface. Please refer to the documentation for CoulombFriction for details on this topic.
More specifically, this method computes the contact coefficients for the given surface pair as:
Click to expand C++ code...
μ = 2μₘμₙ/(μₘ + μₙ)
where the operation above is performed separately on the static and dynamic friction coefficients.
- Parameter
surface_properties1
: Surface properties for surface 1. Specified as an individual set of Coulomb’s law coefficients of friction.
- Parameter
surface_properties2
: Surface properties for surface 2. Specified as an individual set of Coulomb’s law coefficients of friction.
- Returns
the combined friction coefficients for the interacting surfaces.
- pydrake.multibody.plant.ConnectContactResultsToDrakeVisualizer(builder: pydrake.systems.framework.DiagramBuilder, plant: drake::multibody::MultibodyPlant<double>, scene_graph: pydrake.geometry.SceneGraph, lcm: pydrake.lcm.DrakeLcmInterface = None, publish_period: Optional[float] = None) pydrake.systems.lcm.LcmPublisherSystem
MultibodyPlant-connecting overload.
- class pydrake.multibody.plant.ContactModel
Enumeration for contact model options.
Members:
kHydroelastic : Contact forces are computed using the Hydroelastic model. Contact
between unsupported geometries will cause a runtime exception.
kPoint : Contact forces are computed using a point contact model, see
compliant_point_contact.
kHydroelasticWithFallback : Contact forces are computed using the hydroelastic model, where
possible. For most other unsupported colliding pairs, the point model from kPoint is used. See geometry::QueryObject::ComputeContactSurfacesWithFallback for more details.
kHydroelasticsOnly : Legacy alias. TODO(jwnimmer-tri) Deprecate this constant.
kPointContactOnly : Legacy alias. TODO(jwnimmer-tri) Deprecate this constant.
- __init__(self: pydrake.multibody.plant.ContactModel, value: int) None
- kHydroelastic = <ContactModel.kHydroelastic: 0>
- kHydroelasticsOnly = <ContactModel.kHydroelastic: 0>
- kHydroelasticWithFallback = <ContactModel.kHydroelasticWithFallback: 2>
- kPoint = <ContactModel.kPoint: 1>
- kPointContactOnly = <ContactModel.kPoint: 1>
- property name
- property value
- class pydrake.multibody.plant.ContactResults
A container class storing the contact results information for each contact pair for a given state of the simulation.
This class is immutable, so can be efficiently copied and moved.
Note
This class is templated; see
ContactResults_
for the list of instantiations.- __init__(self: pydrake.multibody.plant.ContactResults) None
Constructs an empty ContactResults.
- hydroelastic_contact_info(self: pydrake.multibody.plant.ContactResults, i: int) pydrake.multibody.plant.HydroelasticContactInfo
Retrieves the ith HydroelasticContactInfo instance. The input index i must be in the range [0,
num_hydroelastic_contacts()
) or this method throws.
- num_hydroelastic_contacts(self: pydrake.multibody.plant.ContactResults) int
Returns the number of hydroelastic contacts.
- num_point_pair_contacts(self: pydrake.multibody.plant.ContactResults) int
Returns the number of point pair contacts.
- plant(self: pydrake.multibody.plant.ContactResults) drake::multibody::MultibodyPlant<double>
Returns the plant that produced these contact results. In most cases the result will be non-null, but default-constructed results might have nulls.
- point_pair_contact_info(self: pydrake.multibody.plant.ContactResults, i: int) pydrake.multibody.plant.PointPairContactInfo
Retrieves the ith PointPairContactInfo instance. The input index i must be in the range [0,
num_point_pair_contacts()
) or this method throws.
- SelectHydroelastic(self: pydrake.multibody.plant.ContactResults, selector: Callable[[pydrake.multibody.plant.HydroelasticContactInfo], bool]) pydrake.multibody.plant.ContactResults
Returns a selective copy of this object. Only HydroelasticContactInfo instances satisfying the selection criterion are copied; all other contacts (point_pair and deformable) are unconditionally copied.
- Parameter
selector
: Boolean predicate that returns true to select which HydroelasticContactInfo.
Note
It uses deep copy (unless the operation is trivially identifiable as being vacuous, e.g., when num_hydroelastic_contacts() == 0).
- Parameter
- template pydrake.multibody.plant.ContactResults_
Instantiations:
ContactResults_[float]
,ContactResults_[AutoDiffXd]
,ContactResults_[Expression]
- class pydrake.multibody.plant.ContactResults_[AutoDiffXd]
A container class storing the contact results information for each contact pair for a given state of the simulation.
This class is immutable, so can be efficiently copied and moved.
- __init__(self: pydrake.multibody.plant.ContactResults_[AutoDiffXd]) None
Constructs an empty ContactResults.
- hydroelastic_contact_info(self: pydrake.multibody.plant.ContactResults_[AutoDiffXd], i: int) pydrake.multibody.plant.HydroelasticContactInfo_[AutoDiffXd]
Retrieves the ith HydroelasticContactInfo instance. The input index i must be in the range [0,
num_hydroelastic_contacts()
) or this method throws.
- num_hydroelastic_contacts(self: pydrake.multibody.plant.ContactResults_[AutoDiffXd]) int
Returns the number of hydroelastic contacts.
- num_point_pair_contacts(self: pydrake.multibody.plant.ContactResults_[AutoDiffXd]) int
Returns the number of point pair contacts.
- plant(self: pydrake.multibody.plant.ContactResults_[AutoDiffXd]) drake::multibody::MultibodyPlant<Eigen::AutoDiffScalar<Eigen::Matrix<double, -1, 1, 0, -1, 1> > >
Returns the plant that produced these contact results. In most cases the result will be non-null, but default-constructed results might have nulls.
- point_pair_contact_info(self: pydrake.multibody.plant.ContactResults_[AutoDiffXd], i: int) pydrake.multibody.plant.PointPairContactInfo_[AutoDiffXd]
Retrieves the ith PointPairContactInfo instance. The input index i must be in the range [0,
num_point_pair_contacts()
) or this method throws.
- SelectHydroelastic(self: pydrake.multibody.plant.ContactResults_[AutoDiffXd], selector: Callable[[pydrake.multibody.plant.HydroelasticContactInfo_[AutoDiffXd]], bool]) pydrake.multibody.plant.ContactResults_[AutoDiffXd]
Returns a selective copy of this object. Only HydroelasticContactInfo instances satisfying the selection criterion are copied; all other contacts (point_pair and deformable) are unconditionally copied.
- Parameter
selector
: Boolean predicate that returns true to select which HydroelasticContactInfo.
Note
It uses deep copy (unless the operation is trivially identifiable as being vacuous, e.g., when num_hydroelastic_contacts() == 0).
- Parameter
- class pydrake.multibody.plant.ContactResults_[Expression]
A container class storing the contact results information for each contact pair for a given state of the simulation.
This class is immutable, so can be efficiently copied and moved.
- __init__(self: pydrake.multibody.plant.ContactResults_[Expression]) None
Constructs an empty ContactResults.
- hydroelastic_contact_info(self: pydrake.multibody.plant.ContactResults_[Expression], i: int) pydrake.multibody.plant.HydroelasticContactInfo_[Expression]
Retrieves the ith HydroelasticContactInfo instance. The input index i must be in the range [0,
num_hydroelastic_contacts()
) or this method throws.
- num_hydroelastic_contacts(self: pydrake.multibody.plant.ContactResults_[Expression]) int
Returns the number of hydroelastic contacts.
- num_point_pair_contacts(self: pydrake.multibody.plant.ContactResults_[Expression]) int
Returns the number of point pair contacts.
- plant(self: pydrake.multibody.plant.ContactResults_[Expression]) drake::multibody::MultibodyPlant<drake::symbolic::Expression>
Returns the plant that produced these contact results. In most cases the result will be non-null, but default-constructed results might have nulls.
- point_pair_contact_info(self: pydrake.multibody.plant.ContactResults_[Expression], i: int) pydrake.multibody.plant.PointPairContactInfo_[Expression]
Retrieves the ith PointPairContactInfo instance. The input index i must be in the range [0,
num_point_pair_contacts()
) or this method throws.
- SelectHydroelastic(self: pydrake.multibody.plant.ContactResults_[Expression], selector: Callable[[pydrake.multibody.plant.HydroelasticContactInfo_[Expression]], bool]) pydrake.multibody.plant.ContactResults_[Expression]
Returns a selective copy of this object. Only HydroelasticContactInfo instances satisfying the selection criterion are copied; all other contacts (point_pair and deformable) are unconditionally copied.
- Parameter
selector
: Boolean predicate that returns true to select which HydroelasticContactInfo.
Note
It uses deep copy (unless the operation is trivially identifiable as being vacuous, e.g., when num_hydroelastic_contacts() == 0).
- Parameter
- class pydrake.multibody.plant.ContactResultsToLcmSystem
Bases:
pydrake.systems.framework.LeafSystem
A System that encodes ContactResults into a lcmt_contact_results_for_viz message. It has a single input port with type ContactResults<T> and a single output port with lcmt_contact_results_for_viz.
Although this class can be instantiated on all default scalars, its functionality will be limited for
T
= symbolic::Expression. If there are any symbolic::Variable instances in the expression, attempting to evaluate the output port will throw an exception. The support is sufficient that a systems::Diagram with a ContactResultsToLcmSystem can be scalar converted to symbolic::Expression without error, but not necessarily evaluated.Constructing instances
Generally, you shouldn’t construct ContactResultsToLcmSystem instances directly. We recommend using one of the overloaded contact_result_vis_creation “ConnectContactResultsToDrakeVisualizer()” functions to add contact visualization to your diagram.
How contacts are described in visualization
In the visualizer, each contact between two bodies is uniquely characterized by two triples of names: (model instance name, body name, geometry name). These triples help distinguish contacts which might otherwise be ambiguous (e.g., contact with two bodies, both called “box” but part of different model instances).
ContactResultsToLcmSystem gets the model instance and body names from an instance of MultibodyPlant, but geometry names are not available from the plant. By default, ContactResultsToLcmSystem will generate a unique name based on a geometry’s unique id (e.g., “Id(7)”). For many applications (those cases where each body has only a single collision geometry), this is perfectly acceptable. However, in cases where a body has multiple collision geometries, those default names may not be helpful when viewing the visualized results. Instead, ContactResultsToLcmSystem can use the names associated with the id in a geometry::SceneGraph instance. The only method for doing this is via the contact_result_vis_creation “ConnectContactResultsToDrakeVisualizer()” functions and requires the diagram to be instantiated as double valued. If a diagram with a different scalar type is required, it should subsequently be scalar converted.
u0→ ContactResultsToLcmSystem → y0 - __init__(self: pydrake.multibody.plant.ContactResultsToLcmSystem, plant: drake::multibody::MultibodyPlant<double>) None
Constructs an instance with default geometry names (e.g., “Id(7)”).
- Parameter
plant
: The MultibodyPlant that the ContactResults are generated from.
- Precondition:
The
plant
parameter (or a fully equivalent plant) connects tothis
system’s input port.- Precondition:
The
plant
parameter is finalized.
- Parameter
- get_contact_result_input_port(self: pydrake.multibody.plant.ContactResultsToLcmSystem) pydrake.systems.framework.InputPort
- get_lcm_message_output_port(self: pydrake.multibody.plant.ContactResultsToLcmSystem) pydrake.systems.framework.OutputPort
- class pydrake.multibody.plant.CoulombFriction
Parameters for Coulomb’s Law of Friction, namely:
Static friction coefficient, for a pair of surfaces at rest relative to each other.
Dynamic (or kinematic) friction coefficient, for a pair of surfaces in relative motion.
These coefficients are an empirical property characterizing the interaction by friction between a pair of contacting surfaces. Friction coefficients depend upon the mechanical properties of the surfaces’ materials and on the roughness of the surfaces. They are determined experimentally.
Even though the Coulomb’s law coefficients of friction characterize a pair of surfaces interacting by friction, we associate the abstract idea of friction coefficients to a single surface by considering the coefficients for contact between two identical surfaces. For this case of two identical surfaces, the friction coefficients that describe the surface pair are taken to equal those of one of the identical surfaces. We extend this idea to the case of different surfaces by defining a combination law that allow us to obtain the Coulomb’s law coefficients of friction characterizing the pair of surfaces, given the individual friction coefficients of each surface. We would like this combination law to satisfy:
The friction coefficient of two identical surfaces is the friction coefficient of one of the surfaces.
The combination law is commutative. That is, surface A combined with surface B gives the same results as surface B combined with surface A.
For two surfaces M and N with very different friction coefficients, say
μₘ ≪ μₙ
, the combined friction coefficient should be in the order of magnitude of the smallest friction coefficient (in the example μₘ). To understand this requirement, consider rubber (high friction coefficient) sliding on ice (low friction coefficient). We’d like the surface pair to be defined by a friction coefficient close to that of ice, since rubber will easily slide on ice.
These requirements are met by the following ad-hoc combination law:
Click to expand C++ code...
μ = 2μₘμₙ/(μₘ + μₙ)
See CalcContactFrictionFromSurfaceProperties(), which implements this law. More complex combination laws could also be a function of other parameters such as the mechanical properties of the interacting surfaces or even their roughnesses. For instance, if the rubber surface above has metal studs (somehow making the surface “rougher”), it will definitely have a better grip on an ice surface. Therefore this new variable should be taken into account in the combination law. Notice that in this example, this new combination law model for tires, will have a different set of requirements from the ones stated above.
Note
This class is templated; see
CoulombFriction_
for the list of instantiations.- __init__(*args, **kwargs)
Overloaded function.
__init__(self: pydrake.multibody.plant.CoulombFriction) -> None
Default constructor for a frictionless surface, i.e. with zero static and dynamic coefficients of friction.
__init__(self: pydrake.multibody.plant.CoulombFriction, static_friction: float, dynamic_friction: float) -> None
Specifies both the static and dynamic friction coefficients for a given surface.
- Raises
RuntimeError if any of the friction coefficients are negative or –
if dynamic_friction > static_friction (they can be equal.) –
- dynamic_friction(self: pydrake.multibody.plant.CoulombFriction) float
Returns the coefficient of dynamic friction.
- static_friction(self: pydrake.multibody.plant.CoulombFriction) float
Returns the coefficient of static friction.
- template pydrake.multibody.plant.CoulombFriction_
Instantiations:
CoulombFriction_[float]
,CoulombFriction_[AutoDiffXd]
,CoulombFriction_[Expression]
- class pydrake.multibody.plant.CoulombFriction_[AutoDiffXd]
Parameters for Coulomb’s Law of Friction, namely:
Static friction coefficient, for a pair of surfaces at rest relative to each other.
Dynamic (or kinematic) friction coefficient, for a pair of surfaces in relative motion.
These coefficients are an empirical property characterizing the interaction by friction between a pair of contacting surfaces. Friction coefficients depend upon the mechanical properties of the surfaces’ materials and on the roughness of the surfaces. They are determined experimentally.
Even though the Coulomb’s law coefficients of friction characterize a pair of surfaces interacting by friction, we associate the abstract idea of friction coefficients to a single surface by considering the coefficients for contact between two identical surfaces. For this case of two identical surfaces, the friction coefficients that describe the surface pair are taken to equal those of one of the identical surfaces. We extend this idea to the case of different surfaces by defining a combination law that allow us to obtain the Coulomb’s law coefficients of friction characterizing the pair of surfaces, given the individual friction coefficients of each surface. We would like this combination law to satisfy:
The friction coefficient of two identical surfaces is the friction coefficient of one of the surfaces.
The combination law is commutative. That is, surface A combined with surface B gives the same results as surface B combined with surface A.
For two surfaces M and N with very different friction coefficients, say
μₘ ≪ μₙ
, the combined friction coefficient should be in the order of magnitude of the smallest friction coefficient (in the example μₘ). To understand this requirement, consider rubber (high friction coefficient) sliding on ice (low friction coefficient). We’d like the surface pair to be defined by a friction coefficient close to that of ice, since rubber will easily slide on ice.
These requirements are met by the following ad-hoc combination law:
Click to expand C++ code...
μ = 2μₘμₙ/(μₘ + μₙ)
See CalcContactFrictionFromSurfaceProperties(), which implements this law. More complex combination laws could also be a function of other parameters such as the mechanical properties of the interacting surfaces or even their roughnesses. For instance, if the rubber surface above has metal studs (somehow making the surface “rougher”), it will definitely have a better grip on an ice surface. Therefore this new variable should be taken into account in the combination law. Notice that in this example, this new combination law model for tires, will have a different set of requirements from the ones stated above.
- __init__(*args, **kwargs)
Overloaded function.
__init__(self: pydrake.multibody.plant.CoulombFriction_[AutoDiffXd]) -> None
Default constructor for a frictionless surface, i.e. with zero static and dynamic coefficients of friction.
__init__(self: pydrake.multibody.plant.CoulombFriction_[AutoDiffXd], static_friction: pydrake.autodiffutils.AutoDiffXd, dynamic_friction: pydrake.autodiffutils.AutoDiffXd) -> None
Specifies both the static and dynamic friction coefficients for a given surface.
- Raises
RuntimeError if any of the friction coefficients are negative or –
if dynamic_friction > static_friction (they can be equal.) –
- dynamic_friction(self: pydrake.multibody.plant.CoulombFriction_[AutoDiffXd]) pydrake.autodiffutils.AutoDiffXd
Returns the coefficient of dynamic friction.
- static_friction(self: pydrake.multibody.plant.CoulombFriction_[AutoDiffXd]) pydrake.autodiffutils.AutoDiffXd
Returns the coefficient of static friction.
- class pydrake.multibody.plant.CoulombFriction_[Expression]
Parameters for Coulomb’s Law of Friction, namely:
Static friction coefficient, for a pair of surfaces at rest relative to each other.
Dynamic (or kinematic) friction coefficient, for a pair of surfaces in relative motion.
These coefficients are an empirical property characterizing the interaction by friction between a pair of contacting surfaces. Friction coefficients depend upon the mechanical properties of the surfaces’ materials and on the roughness of the surfaces. They are determined experimentally.
Even though the Coulomb’s law coefficients of friction characterize a pair of surfaces interacting by friction, we associate the abstract idea of friction coefficients to a single surface by considering the coefficients for contact between two identical surfaces. For this case of two identical surfaces, the friction coefficients that describe the surface pair are taken to equal those of one of the identical surfaces. We extend this idea to the case of different surfaces by defining a combination law that allow us to obtain the Coulomb’s law coefficients of friction characterizing the pair of surfaces, given the individual friction coefficients of each surface. We would like this combination law to satisfy:
The friction coefficient of two identical surfaces is the friction coefficient of one of the surfaces.
The combination law is commutative. That is, surface A combined with surface B gives the same results as surface B combined with surface A.
For two surfaces M and N with very different friction coefficients, say
μₘ ≪ μₙ
, the combined friction coefficient should be in the order of magnitude of the smallest friction coefficient (in the example μₘ). To understand this requirement, consider rubber (high friction coefficient) sliding on ice (low friction coefficient). We’d like the surface pair to be defined by a friction coefficient close to that of ice, since rubber will easily slide on ice.
These requirements are met by the following ad-hoc combination law:
Click to expand C++ code...
μ = 2μₘμₙ/(μₘ + μₙ)
See CalcContactFrictionFromSurfaceProperties(), which implements this law. More complex combination laws could also be a function of other parameters such as the mechanical properties of the interacting surfaces or even their roughnesses. For instance, if the rubber surface above has metal studs (somehow making the surface “rougher”), it will definitely have a better grip on an ice surface. Therefore this new variable should be taken into account in the combination law. Notice that in this example, this new combination law model for tires, will have a different set of requirements from the ones stated above.
- __init__(*args, **kwargs)
Overloaded function.
__init__(self: pydrake.multibody.plant.CoulombFriction_[Expression]) -> None
Default constructor for a frictionless surface, i.e. with zero static and dynamic coefficients of friction.
__init__(self: pydrake.multibody.plant.CoulombFriction_[Expression], static_friction: pydrake.symbolic.Expression, dynamic_friction: pydrake.symbolic.Expression) -> None
Specifies both the static and dynamic friction coefficients for a given surface.
- Raises
RuntimeError if any of the friction coefficients are negative or –
if dynamic_friction > static_friction (they can be equal.) –
- dynamic_friction(self: pydrake.multibody.plant.CoulombFriction_[Expression]) pydrake.symbolic.Expression
Returns the coefficient of dynamic friction.
- static_friction(self: pydrake.multibody.plant.CoulombFriction_[Expression]) pydrake.symbolic.Expression
Returns the coefficient of static friction.
- class pydrake.multibody.plant.DeformableBodyId
Uniquely identifies a deformable body. It is valid before and after Finalize().
- __init__(*args, **kwargs)
- static get_new_id() pydrake.multibody.plant.DeformableBodyId
Generates a new identifier for this id type. This new identifier will be different from all previous identifiers created. This method does not make any guarantees about the values of ids from successive invocations. This method is guaranteed to be thread safe.
- get_value(self: pydrake.multibody.plant.DeformableBodyId) int
Extracts the underlying representation from the identifier. This is considered invalid for invalid ids and is strictly enforced in Debug builds.
- is_valid(self: pydrake.multibody.plant.DeformableBodyId) bool
Reports if the id is valid.
- class pydrake.multibody.plant.DeformableModel
Bases:
pydrake.multibody.plant.PhysicalModel
DeformableModel implements the interface in PhysicalModel and provides the functionalities to specify deformable bodies. Unlike rigid bodies, the shape of deformable bodies can change in a simulation. Each deformable body is modeled as a volumetric mesh with persisting topology, changing vertex positions, and an approximated signed distance field. A finite element model is built for each registered deformable body that is used to evaluate the dynamics of the body.
Warning
This feature is considered to be experimental and may change or be removed at any time, without any deprecation notice ahead of time.
- __init__(self: pydrake.multibody.plant.DeformableModel, arg0: drake::multibody::MultibodyPlant<double>) None
(Internal only) Constructs a DeformableModel to be owned by the given MultibodyPlant. This constructor is only intended to be called internally by MultibodyPlant.
- Precondition:
plant != nullptr.
- Precondition:
Finalize() has not been called on
plant
.
- AddFixedConstraint(self: pydrake.multibody.plant.DeformableModel, body_A_id: pydrake.multibody.plant.DeformableBodyId, body_B: pydrake.multibody.tree.RigidBody, X_BA: pydrake.math.RigidTransform, shape: pydrake.geometry.Shape, X_BG: pydrake.math.RigidTransform) pydrake.multibody.tree.MultibodyConstraintId
Defines a fixed constraint between a deformable body A and a rigid body B. Such a fixed constraint is modeled as distance holonomic constraints:
p_PᵢQᵢ(q) = 0 for each constrained vertex Pᵢ
where Pᵢ is the i-th vertex of the deformable body under constraint and Qᵢ is a point rigidly affixed to the rigid body B. To specify the constraint, we put the reference mesh M of the deformable body A in B’s body frame with the given pose
X_BA
and prescribe a shape G with poseX_BG
in B’s body frame. All vertices Pᵢ in M that are inside (or on the surface of) G are subject to the fixed constraints with Qᵢ being coincident with Pᵢ when M is in pose X_BA. p_PᵢQᵢ(q) denotes the relative position of point Qᵢ with respect to point Pᵢ as a function of the configuration of the model q. Imposing this constraint forces Pᵢ and Qᵢ to be coincident for each vertex i of the deformable body specified to be under constraint.- Parameter
body_A_id
: The unique id of the deformable body under the fixed constraint.
- Parameter
body_B
: The rigid body under constraint.
- Parameter
X_BA
: The pose of deformable body A’s reference mesh in B’s body frame
- Parameter
shape
: The prescribed geometry shape, attached to rigid body B, used to determine which vertices of the deformable body A is under constraint.
- Parameter
X_BG
: The fixed pose of the geometry frame of the given
shape
in body B’s frame.
- Returns
the unique id of the newly added constraint.
- Raises
RuntimeError if no deformable body with the given body_A_id –
has been registered. –
RuntimeError unless body_B is registered with the same –
multibody plant owning this deformable model. –
RuntimeError if shape is not supported by –
QueryObject::ComputeSignedDistanceToPoint() Currently, supported –
shapes include Box, Capsule, Cylinder, Ellipsoid, HalfSpace, and –
Sphere. –
RuntimeError if Finalize() has been called on the multibody plant –
owning this deformable model. –
RuntimeError if this DeformableModel is not of scalar type –
double. –
RuntimeError if no constraint is added (i.e. no vertex of the –
deformable body is inside the given shape with the given –
poses) –
- Parameter
- GetBodyId(self: pydrake.multibody.plant.DeformableModel, geometry_id: pydrake.geometry.GeometryId) pydrake.multibody.plant.DeformableBodyId
Returns the DeformableBodyId associated with the given
geometry_id
.- Raises
RuntimeError if the given geometry_id does not correspond to a –
deformable body registered with this model. –
- GetDiscreteStateIndex(self: pydrake.multibody.plant.DeformableModel, id: pydrake.multibody.plant.DeformableBodyId) pydrake.systems.framework.DiscreteStateIndex
Returns the discrete state index of the deformable body identified by the given
id
.- Raises
RuntimeError if MultibodyPlant::Finalize() has not been called –
yet. or if no deformable body with the given id has been –
registered in this model. –
- GetGeometryId(self: pydrake.multibody.plant.DeformableModel, id: pydrake.multibody.plant.DeformableBodyId) pydrake.geometry.GeometryId
Returns the GeometryId of the geometry associated with the body with the given
id
.- Raises
RuntimeError if no body with the given id has been registered. –
- GetReferencePositions(self: pydrake.multibody.plant.DeformableModel, id: pydrake.multibody.plant.DeformableBodyId) numpy.ndarray[numpy.float64[m, 1]]
Returns the reference positions of the vertices of the deformable body identified by the given
id
. The reference positions are represented as a VectorX with 3N values where N is the number of vertices. The x-, y-, and z-positions (measured and expressed in the world frame) of the j-th vertex are 3j, 3j + 1, and 3j + 2 in the VectorX.- Raises
RuntimeError if no deformable body with the given id has been –
registered in this model. –
- num_bodies(self: pydrake.multibody.plant.DeformableModel) int
Returns the number of deformable bodies registered with this DeformableModel.
- RegisterDeformableBody(self: pydrake.multibody.plant.DeformableModel, geometry_instance: pydrake.geometry.GeometryInstance, config: pydrake.multibody.fem.DeformableBodyConfig, resolution_hint: float) pydrake.multibody.plant.DeformableBodyId
Registers a deformable body in
this
DeformableModel with the given GeometryInstance. The body is represented in the world frame and simulated with FEM with linear elements and a first order quadrature rule that integrates linear functions exactly. See FemModel for details. Returns a unique identifier for the added geometry.- Parameter
geometry_instance
: The geometry to be registered with the model.
- Parameter
config
: The physical properties of deformable body.
- Parameter
resolution_hint
: The parameter that guides the level of mesh refinement of the deformable geometry. It has length units (in meters) and roughly corresponds to a typical edge length in the resulting mesh for a primitive shape.
- Precondition:
resolution_hint > 0.
- Raises
RuntimeError if this DeformableModel is not of scalar type –
double. –
RuntimeError if Finalize() has been called on the multibody plant –
owning this deformable model. –
- Parameter
- SetWallBoundaryCondition(self: pydrake.multibody.plant.DeformableModel, id: pydrake.multibody.plant.DeformableBodyId, p_WQ: numpy.ndarray[numpy.float64[3, 1]], n_W: numpy.ndarray[numpy.float64[3, 1]]) None
Sets wall boundary conditions for the body with the given
id
. All vertices of the mesh of the deformable body whose reference positions are inside the prescribed open half space are put under zero displacement boundary conditions. The open half space is defined by a plane with outward normal n_W. A vertex V is considered to be subject to the boundary condition if n̂ ⋅ p_QV < 0 where Q is a point on the plane and n̂ is normalized n_W.- Parameter
id
: The body to be put under boundary condition.
- Parameter
p_WQ
: The position of a point Q on the plane in the world frame.
- Parameter
n_W
: Outward normal to the half space expressed in the world frame.
- Precondition:
n_W.norm() > 1e-10.
Warning
Be aware of round-off errors in floating computations when placing a vertex very close to the plane defining the half space.
- Raises
RuntimeError if Finalize() has been called on the multibody plant –
owning this deformable model or if no deformable body with the –
given id has been registered in this model. –
- Parameter
- class pydrake.multibody.plant.DiscreteContactApproximation
The type of the contact approximation used for a discrete MultibodyPlant model.
kTamsi, kSimilar and kLagged are all approximations to the same contact model – Compliant contact with regularized friction, refer to mbp_contact_modeling “Contact Modeling” for further details. The key difference however, is that the kSimilar and kLagged approximations are convex and therefore our contact solver has both theoretical and practical convergence guarantees — the solver will always succeed. Conversely, being non-convex, kTamsi can fail to find a solution.
kSap is also a convex model of compliant contact with regularized friction. There are a couple of key differences however: - Dissipation is modeled using a linear Kelvin–Voigt model, parameterized by a relaxation time constant. See accessing_contact_properties “contact parameters”. - Unlike kTamsi, kSimilar and kLagged where regularization of friction is parameterized by a stiction tolerance (see set_stiction_tolerance()), SAP determines regularization automatically solely based on numerics. Users have no control on the amount of regularization.
How to choose an approximation
The Hunt & Crossley model is based on physics, it is continuous and has been experimentally validated. Therefore it is the preferred model to capture the physics of contact.
Being approximations, kSap and kSimilar introduce a spurious effect of “gliding” in sliding contact, see [Castro et al., 2023]. This artifact is 𝒪(δt) but can be significant at large time steps and/or large slip velocities. kLagged does not suffer from this, but introduces a “weak” coupling of friction that can introduce non-negligible effects in the dynamics during impacts or strong transients.
Summarizing, kLagged is the preferred approximation when strong transients are not expected or don’t need to be accurately resolved. If strong transients do need to be accurately resolved (unusual for robotics applications), kSimilar is the preferred approximation.
References
[Castro et al., 2019] Castro A., Qu A., Kuppuswamy N., Alspach A., Sherman M, 2019. A Transition-Aware Method for the Simulation of Compliant Contact with Regularized Friction. Available online at https://arxiv.org/abs/1909.05700.
[Castro et al., 2022] Castro A., Permenter F. and Han X., 2022. An Unconstrained Convex Formulation of Compliant Contact. Available online at https://arxiv.org/abs/2110.10107.
[Castro et al., 2023] Castro A., Han X., and Masterjohn J., 2023. A Theory of Irrotational Contact Fields. Available online at https://arxiv.org/abs/2312.03908
Members:
kTamsi : TAMSI solver approximation, see [Castro et al., 2019].
kSap : SAP solver model approximation, see [Castro et al., 2022].
kSimilar : Similarity approximation found in [Castro et al., 2023].
kLagged : Approximation in which the normal force is lagged in Coulomb’s law,
such that ‖γₜ‖ ≤ μ γₙ₀, [Castro et al., 2023].
- __init__(self: pydrake.multibody.plant.DiscreteContactApproximation, value: int) None
- kLagged = <DiscreteContactApproximation.kLagged: 3>
- kSap = <DiscreteContactApproximation.kSap: 1>
- kSimilar = <DiscreteContactApproximation.kSimilar: 2>
- kTamsi = <DiscreteContactApproximation.kTamsi: 0>
- property name
- property value
- class pydrake.multibody.plant.DiscreteContactSolver
The type of the contact solver used for a discrete MultibodyPlant model.
Note: the SAP solver only fully supports scalar type
double
. For scalar typeAutoDiffXd
, the SAP solver throws if any constraint (including contact) is detected. As a consequence, one can only run dynamic simulations without any constraints under the combination of SAP andAutoDiffXd
. The SAP solver does not support symbolic calculations.References
[Castro et al., 2019] Castro, A.M, Qu, A., Kuppuswamy, N., Alspach, A., Sherman, M.A., 2019. A Transition-Aware Method for the Simulation of Compliant Contact with Regularized Friction. Available online at https://arxiv.org/abs/1909.05700.
[Castro et al., 2022] Castro A., Permenter F. and Han X., 2022. An Unconstrained Convex Formulation of Compliant Contact. Available online at https://arxiv.org/abs/2110.10107.
Members:
kTamsi : TAMSI solver, see [Castro et al., 2019].
kSap : SAP solver, see [Castro et al., 2022].
- __init__(self: pydrake.multibody.plant.DiscreteContactSolver, value: int) None
- kSap = <DiscreteContactSolver.kSap: 1>
- kTamsi = <DiscreteContactSolver.kTamsi: 0>
- property name
- property value
- class pydrake.multibody.plant.ExternallyAppliedSpatialForce
Note
This class is templated; see
ExternallyAppliedSpatialForce_
for the list of instantiations.- __init__(self: pydrake.multibody.plant.ExternallyAppliedSpatialForce) None
- property body_index
The index of the body that the force is to be applied to.
- property F_Bq_W
A spatial force applied to Body B at point Bq, expressed in the world frame.
- property p_BoBq_B
A position vector from Body B’s origin (Bo) to a point Bq (a point of B), expressed in B’s frame.
- template pydrake.multibody.plant.ExternallyAppliedSpatialForce_
Instantiations:
ExternallyAppliedSpatialForce_[float]
,ExternallyAppliedSpatialForce_[AutoDiffXd]
,ExternallyAppliedSpatialForce_[Expression]
- class pydrake.multibody.plant.ExternallyAppliedSpatialForce_[AutoDiffXd]
- __init__(self: pydrake.multibody.plant.ExternallyAppliedSpatialForce_[AutoDiffXd]) None
- property body_index
The index of the body that the force is to be applied to.
- property F_Bq_W
A spatial force applied to Body B at point Bq, expressed in the world frame.
- property p_BoBq_B
A position vector from Body B’s origin (Bo) to a point Bq (a point of B), expressed in B’s frame.
- class pydrake.multibody.plant.ExternallyAppliedSpatialForce_[Expression]
- __init__(self: pydrake.multibody.plant.ExternallyAppliedSpatialForce_[Expression]) None
- property body_index
The index of the body that the force is to be applied to.
- property F_Bq_W
A spatial force applied to Body B at point Bq, expressed in the world frame.
- property p_BoBq_B
A position vector from Body B’s origin (Bo) to a point Bq (a point of B), expressed in B’s frame.
- class pydrake.multibody.plant.ExternallyAppliedSpatialForceMultiplexer
Bases:
pydrake.systems.framework.LeafSystem
Concatenates multiple std::vector<>’s of ExternallyAppliedSpatialForce<T>.
u0→ ...→ u(N-1)→ ExternallyAppliedSpatialForceMultiplexer → y0 Note
This class is templated; see
ExternallyAppliedSpatialForceMultiplexer_
for the list of instantiations.- __init__(self: pydrake.multibody.plant.ExternallyAppliedSpatialForceMultiplexer, num_inputs: int) None
Constructor.
- Parameter
num_inputs
: Number of input ports to be added.
- Parameter
- template pydrake.multibody.plant.ExternallyAppliedSpatialForceMultiplexer_
Instantiations:
ExternallyAppliedSpatialForceMultiplexer_[float]
,ExternallyAppliedSpatialForceMultiplexer_[AutoDiffXd]
,ExternallyAppliedSpatialForceMultiplexer_[Expression]
- class pydrake.multibody.plant.ExternallyAppliedSpatialForceMultiplexer_[AutoDiffXd]
Bases:
pydrake.systems.framework.LeafSystem_[AutoDiffXd]
Concatenates multiple std::vector<>’s of ExternallyAppliedSpatialForce<T>.
u0→ ...→ u(N-1)→ ExternallyAppliedSpatialForceMultiplexer → y0 - __init__(self: pydrake.multibody.plant.ExternallyAppliedSpatialForceMultiplexer_[AutoDiffXd], num_inputs: int) None
Constructor.
- Parameter
num_inputs
: Number of input ports to be added.
- Parameter
- class pydrake.multibody.plant.ExternallyAppliedSpatialForceMultiplexer_[Expression]
Bases:
pydrake.systems.framework.LeafSystem_[Expression]
Concatenates multiple std::vector<>’s of ExternallyAppliedSpatialForce<T>.
u0→ ...→ u(N-1)→ ExternallyAppliedSpatialForceMultiplexer → y0 - __init__(self: pydrake.multibody.plant.ExternallyAppliedSpatialForceMultiplexer_[Expression], num_inputs: int) None
Constructor.
- Parameter
num_inputs
: Number of input ports to be added.
- Parameter
- class pydrake.multibody.plant.HydroelasticContactInfo
A class containing information regarding contact and contact response between two geometries attached to a pair of bodies. This class provides the output from the Hydroelastic contact model and includes:
The shared contact surface between the two geometries, which includes
the virtual pressures acting at every point on the contact surface. - The spatial force from the integrated tractions that is applied at the centroid of the contact surface.
The two geometries, denoted M and N (and obtainable via
contact_surface().id_M()
andcontact_surface().id_N()
) are attached to bodies A and B, respectively.When T = Expression, the class is specialized to not contain any member data, because ContactSurface doesn’t support Expression.
Note
This class is templated; see
HydroelasticContactInfo_
for the list of instantiations.- __init__(*args, **kwargs)
- contact_surface(self: pydrake.multibody.plant.HydroelasticContactInfo) pydrake.geometry.ContactSurface
Returns a reference to the ContactSurface data structure. Note that the mesh and gradient vector fields are expressed in the world frame.
- F_Ac_W(self: pydrake.multibody.plant.HydroelasticContactInfo) pydrake.multibody.math.SpatialForce
Gets the spatial force applied on body A, at the centroid point C of the surface mesh M, and expressed in the world frame W. The position
p_WC
of the centroid point C in the world frame W can be obtained withcontact_surface().centroid()
.
- template pydrake.multibody.plant.HydroelasticContactInfo_
Instantiations:
HydroelasticContactInfo_[float]
,HydroelasticContactInfo_[AutoDiffXd]
,HydroelasticContactInfo_[Expression]
- class pydrake.multibody.plant.HydroelasticContactInfo_[AutoDiffXd]
A class containing information regarding contact and contact response between two geometries attached to a pair of bodies. This class provides the output from the Hydroelastic contact model and includes:
The shared contact surface between the two geometries, which includes
the virtual pressures acting at every point on the contact surface. - The spatial force from the integrated tractions that is applied at the centroid of the contact surface.
The two geometries, denoted M and N (and obtainable via
contact_surface().id_M()
andcontact_surface().id_N()
) are attached to bodies A and B, respectively.When T = Expression, the class is specialized to not contain any member data, because ContactSurface doesn’t support Expression.
- __init__(*args, **kwargs)
- contact_surface(self: pydrake.multibody.plant.HydroelasticContactInfo_[AutoDiffXd]) pydrake.geometry.ContactSurface_[AutoDiffXd]
Returns a reference to the ContactSurface data structure. Note that the mesh and gradient vector fields are expressed in the world frame.
- F_Ac_W(self: pydrake.multibody.plant.HydroelasticContactInfo_[AutoDiffXd]) pydrake.multibody.math.SpatialForce_[AutoDiffXd]
Gets the spatial force applied on body A, at the centroid point C of the surface mesh M, and expressed in the world frame W. The position
p_WC
of the centroid point C in the world frame W can be obtained withcontact_surface().centroid()
.
- class pydrake.multibody.plant.HydroelasticContactInfo_[Expression]
A class containing information regarding contact and contact response between two geometries attached to a pair of bodies. This class provides the output from the Hydroelastic contact model and includes:
The shared contact surface between the two geometries, which includes
the virtual pressures acting at every point on the contact surface. - The spatial force from the integrated tractions that is applied at the centroid of the contact surface.
The two geometries, denoted M and N (and obtainable via
contact_surface().id_M()
andcontact_surface().id_N()
) are attached to bodies A and B, respectively.When T = Expression, the class is specialized to not contain any member data, because ContactSurface doesn’t support Expression.
- __init__(*args, **kwargs)
- class pydrake.multibody.plant.MultibodyPlant
Bases:
pydrake.systems.framework.LeafSystem
MultibodyPlant is a Drake system framework representation (see systems::System) for the model of a physical system consisting of a collection of interconnected bodies. See multibody for an overview of concepts/notation.
actuation→ applied_generalized_force→ applied_spatial_force→ model_instance_name[i]_actuation→ model_instance_name[i]_desired_state→ geometry_query→ MultibodyPlant → state → body_poses → body_spatial_velocities → body_spatial_accelerations → generalized_acceleration → net_actuation → reaction_forces → contact_results → model_instance_name[i]_state → model_instance_name[i]_generalized_acceleration → model_instance_name[i]_generalized_contact_forces → model_instance_name[i]_net_actuation → geometry_pose → deformable_body_configuration The ports whose names begin with <em style=”color:gray”> model_instance_name[i]</em> represent groups of ports, one for each of the model_instances “model instances”, with i ∈ {0, …, N-1} for the N model instances. If a model instance does not contain any data of the indicated type the port will still be present but its value will be a zero-length vector. (Model instances
world_model_instance()
anddefault_model_instance()
always exist.)The ports shown in <span style=”color:green”>green</span> are for communication with Drake’s geometry::SceneGraph “SceneGraph” system for dealing with geometry.
MultibodyPlant provides a user-facing API for:
mbp_input_and_output_ports “Ports”:
Access input and output ports. - mbp_construction “Construction”: Add bodies, joints, frames, force elements, and actuators. - mbp_geometry “Geometry”: Register geometries to a provided SceneGraph instance. - mbp_contact_modeling “Contact modeling”: Select and parameterize contact models. - mbp_state_accessors_and_mutators “State access and modification”: Obtain and manipulate position and velocity state variables. - mbp_parameters “Parameters” Working with system parameters for various multibody elements. - mbp_working_with_free_bodies “Free bodies”: Work conveniently with free (floating) bodies. - mbp_kinematic_and_dynamic_computations “Kinematics and dynamics”: Perform systems::Context “Context”-dependent kinematic and dynamic queries. - mbp_system_matrix_computations “System matrices”: Explicitly form matrices that appear in the equations of motion. - mbp_introspection “Introspection”: Perform introspection to find out what’s in the MultibodyPlant.
**** Model Instances
A MultiBodyPlant may contain multiple model instances. Each model instance corresponds to a set of bodies and their connections (joints). Model instances provide methods to get or set the state of the set of bodies (e.g., through GetPositionsAndVelocities() and SetPositionsAndVelocities()), connecting controllers (through get_state_output_port() and get_actuation_input_port()), and organizing duplicate models (read through a parser). In fact, many MultibodyPlant methods are overloaded to allow operating on the entire plant or just the subset corresponding to the model instance; for example, one GetPositions() method obtains the generalized positions for the entire plant while another GetPositions() method obtains the generalized positions for model instance.
Model instances are frequently defined through SDFormat files (using the
model
tag) and are automatically created when SDFormat files are parsed (by Parser). There are two special multibody::ModelInstanceIndex values. The world body is always multibody::ModelInstanceIndex 0. multibody::ModelInstanceIndex 1 is reserved for all elements with no explicit model instance and is generally only relevant for elements created programmatically (and only when a model instance is not explicitly specified). Note that Parser creates model instances (resulting in a multibody::ModelInstanceIndex ≥ 2) as needed.See num_model_instances(), num_positions(), num_velocities(), num_actuated_dofs(), AddModelInstance() GetPositionsAndVelocities(), GetPositions(), GetVelocities(), SetPositionsAndVelocities(), SetPositions(), SetVelocities(), GetPositionsFromArray(), GetVelocitiesFromArray(), SetPositionsInArray(), SetVelocitiesInArray(), SetActuationInArray(), HasModelInstanceNamed(), GetModelInstanceName(), get_state_output_port(), get_actuation_input_port().
**** System dynamics
The state of a multibody system
x = [q; v]
is given by its generalized positions vector q, of sizenq
(see num_positions()), and by its generalized velocities vector v, of sizenv
(see num_velocities()).A MultibodyPlant can be constructed to be either continuous or discrete. The choice is indicated by the time_step passed to the constructor – a non-zero time_step indicates a discrete plant, while a zero time_step indicates continuous. A systems::Simulator “Simulator” will step a discrete plant using the indicated time_step, but will allow a numerical integrator to choose how to advance time for a continuous MultibodyPlant.
We’ll discuss continuous plant dynamics in this section. Discrete dynamics is more complicated and gets its own section below.
As a Drake systems::System “System”, MultibodyPlant implements the governing equations for a multibody dynamical system in the form
ẋ = f(t, x, u)
with t being time and u external inputs such as actuation forces. The governing equations for the dynamics of a multibody system modeled with MultibodyPlant are [Featherstone 2008, Jain 2010]:Click to expand C++ code...
q̇ = N(q)v (1) M(q)v̇ + C(q, v)v = τ
where
M(q)
is the mass matrix of the multibody system (including rigid body mass properties and reflected_inertia “reflected inertias”),C(q, v)v
contains Coriolis, centripetal, and gyroscopic terms andN(q)
is the kinematic coupling matrix describing the relationship between q̇ (the time derivatives of the generalized positions) and the generalized velocities v, [Seth 2010].N(q)
is annq x nv
matrix. The vectorτ ∈ ℝⁿᵛ
on the right hand side of Eq. (1) is the system’s generalized forces. These incorporate gravity, springs, externally applied body forces, constraint forces, and contact forces.**** Discrete system dynamics
We’ll start with the basic difference equation interpretation of a discrete plant and then explain some Drake-specific subtleties.
Note
We use “kinematics” here to refer to quantities that involve only position or velocity, and “dynamics” to refer to quantities that also involve forces.
By default, a discrete MultibodyPlant has these update dynamics:
x[0] = initial kinematics state variables x (={q, v}), s s[0] = empty (no sample yet)
s[n+1] = g(t[n], x[n], u[n]) record sample x[n+1] = f(t[n], x[n], u[n]) update kinematics yd[n+1] = gd(s) dynamic outputs use sampled values yk[n+1] = gk(x) kinematic outputs use current x
Optionally, output port sampling can be disabled. In that case we have:
x[n+1] = f(t[n], x[n], u[n]) update kinematics yd[n+1] = gd(g(t, x, u)) dynamic outputs use current values yk[n+1] = gk(x) kinematic outputs use current x
We’re using
yd
andyk
above to represent the calculated values of dynamic and kinematic output ports, resp. Kinematic output ports are those that depend only on position and velocity:state
, body_poses,body_spatial_velocities
. Everything else depends on forces so is a dynamic output port:body_spatial_accelerations
, generalized_acceleration,net_actuation
, reaction_forces, andcontact_results
.Use the function SetUseSampledOutputPorts() to choose which dynamics you prefer. The default behavior (output port sampling) is more efficient for simulation, but use slightly-different kinematics for the dynamic output port computations versus the kinematic output ports. Disabling output port sampling provides “live” output port results that are recalculated from the current state and inputs whenever changes occur. It also eliminates the sampling state variable (s above). Note that kinematic output ports (that is, those depending only on position and velocity) are always “live” – they are calculated as needed from the current (updated) state.
The reason that the default mode is more efficient for simulation is that the sample variable s records expensive-to-compute results (such as hydroelastic contact forces) that are needed to advance the state x. Those results are thus available for free at the start of step n. If instead we wait until after the state is updated to n+1, we would have to recalculate those expensive results at the new state in order to report them. Thus sampling means the output ports show the results that were calculated using kinematics values x[n], although the Context has been updated to kinematics values x[n+1]. If that isn’t tolerable you should disable output port sampling. You can also force an update to occur using ExecuteForcedEvents().
See output_port_sampling “Output port sampling” below for more practical considerations.
Minor details most users won’t care about:
The sample variable s is a Drake Abstract state variable. When it is
present, the plant update is performed using an Unrestricted update; when it is absent we are able to use a Discrete update. Some Drake features (e.g. linearization of discrete systems) may be restricted to systems that use only Discrete (numeric) state variables and Discrete update. - The sample variable s is used only by output ports. It does not affect the behavior of any MultibodyPlant “Calc” or “Eval” functions – those are always calculated using the current values of time, kinematic state, and input port values.
**** Output port sampling
As described in mbp_discrete_dynamics “Discrete system dynamics” above, the semantics of certain MultibodyPlant output ports depends on whether the plant is configured to advance using continuous time integration or discrete time steps (see is_discrete()). This section explains the details, focusing on the practical aspects moreso than the equations.
Output ports that only depend on the [q, v] kinematic state (such as get_body_poses_output_port() or get_body_spatial_velocities_output_port()) do not change semantics for continuous vs discrete time. In all cases, the output value is a function of the kinematic state in the context.
Output ports that incorporate dynamics (i.e., forces) do change semantics based on the plant mode. Imagine that the get_applied_spatial_force_input_port() provides a continuously time-varying input force. The get_body_spatial_accelerations_output_port() output is dependent on that force. We could return a snapshot of the acceleration that was used in the last time step, or we could recalculate the acceleration to immediately reflect the changing forces. We call the former a “sampled” port and the latter a “live” port.
For a continuous-time plant, there is no distinction – the output port is always live – it immediately reflects the instantaneous input value. It is a “direct feedthrough” output port (see SystemBase::GetDirectFeedthroughs()).
For a discrete-time plant, the user can choose whether the output should be sampled or live: Use the function SetUseSampledOutputPorts() to change whether output ports are sampled or not, and has_sampled_output_ports() to check the current setting. When sampling is disabled, the only state in the context is the kinematic [q, v], so dynamics output ports will always reflect the instantaneous answer (i.e., direct feedthrough). When sampling is enabled (the default), the plant state incorporates a snapshot of the most recent step’s kinematics and dynamics, and the output ports will reflect that sampled state (i.e., not direct feedthrough). For a detailed discussion, see mbp_discrete_dynamics “Discrete system dynamics”.
For a discrete-time plant, the sampled outputs are generally much faster to calculate than the feedthrough outputs when any inputs ports are changing values faster than the discrete time step, e.g., during a simulation. When input ports are fixed, or change at the time step rate (e.g., during motion planning), sampled vs feedthrough will have similar computational performance.
Direct plant API function calls (e.g., EvalBodySpatialAccelerationInWorld()) that depend on forces always use the instantaneous (not sampled) accelerations.
Here are some practical tips that might help inform your particular situation:
(1) If you need a minimal-state representation for motion planning, mathematical optimization, or similar, then you can either use a continuous-time plant or set the config option
use_sampled_output_ports=false
on a discrete-time plant.(2) By default, setting the positions of a discrete-time plant in the Context will not have any effect on the dynamics-related output ports, e.g., the contact results will not change. If you need to see changes to outputs without running the plant in a Simulator, then you can either use a continuous-time plant, set the config option
use_sampled_output_ports=false
, or use ExecuteForcedEvents() to force a dynamics step and then the outputs (and positions) will change.**** Actuation
In a MultibodyPlant model an actuator can be added as a JointActuator, see AddJointActuator(). The plant declares actuation input ports to provide feedforward actuation, both for the MultibodyPlant as a whole (see get_actuation_input_port()) and for each individual model_instances “model instance” in the MultibodyPlant (see get_actuation_input_port(ModelInstanceIndex)const “get_actuation_input_port(ModelInstanceIndex)”). Any actuation input ports not connected are assumed to be zero. Actuation values from the full MultibodyPlant model port (get_actuation_input_port()) and from the per model-instance ports ( get_actuation_input_port(ModelInstanceIndex)const “get_actuation_input_port(ModelInstanceIndex)”) are summed up.
Note
A JointActuator’s index into the vector data supplied to MultibodyPlant’s actuation input port for all actuators (get_actuation_input_port()) is given by JointActuator::input_start(), NOT by its JointActuatorIndex. That is, the vector element data for a JointActuator at index JointActuatorIndex(i) in the full input port vector is found at index: MultibodyPlant::get_joint_actuator(JointActuatorIndex(i)).input_start(). For the get_actuation_input_port(ModelInstanceIndex)const “get_actuation_input_port(ModelInstanceIndex)” specific to a model index, the vector data is ordered by monotonically increasing JointActuatorIndex for the actuators within that model instance: the 0ᵗʰ vector element corresponds to the lowest-numbered JointActuatorIndex of that instance, the 1ˢᵗ vector element corresponds to the second-lowest-numbered JointActuatorIndex of that instance, etc.
Note
The following snippet shows how per model instance actuation can be set:
Click to expand C++ code...
ModelInstanceIndex model_instance_index = ...; VectorX<T> u_instance(plant.num_actuated_dofs(model_instance_index)); int offset = 0; for (JointActuatorIndex joint_actuator_index : plant.GetJointActuatorIndices(model_instance_index)) { const JointActuator<T>& actuator = plant.get_joint_actuator( joint_actuator_index); const Joint<T>& joint = actuator.joint(); VectorX<T> u_joint = ... my_actuation_logic_for(joint) ...; ASSERT(u_joint.size() == joint_actuator.num_inputs()); u_instance.segment(offset, u_joint.size()) = u_joint; offset += u_joint.size(); } plant.get_actuation_input_port(model_instance_index).FixValue( plant_context, u_instance);
Note
To inter-operate between the whole plant actuation vector and sets of per-model instance actuation vectors, see SetActuationInArray() to gather the model instance vectors into a whole plant vector and GetActuationFromArray() to scatter the whole plant vector into per-model instance vectors.
Warning
Effort limits (JointActuator::effort_limit()) are not enforced, unless PD controllers are defined. See pd_controllers “Using PD controlled actuators”.
** Using PD controlled actuators
While PD controllers can be modeled externally and be connected to the MultibodyPlant model via the get_actuation_input_port(), simulation stability at discrete-time steps can be compromised for high controller gains. For such cases, simulation stability and robustness can be improved significantly by moving your PD controller into the plant where the discrete solver can strongly couple controller and model dynamics.
Warning
Currently, this feature is only supported for discrete models (is_discrete() is true) using the SAP solver (get_discrete_contact_solver() returns DiscreteContactSolver::kSap.)
PD controlled joint actuators can be defined by setting PD gains for each joint actuator, see JointActuator::set_controller_gains(). Unless these gains are specified, joint actuators will not be PD controlled and JointActuator::has_controller() will return
False
.Warning
For PD controlled models, all joint actuators in a model instance are required to have PD controllers defined. That is, partially PD controlled model instances are not supported. An exception will be thrown when evaluating the actuation input ports if only a subset of the actuators in a model instance is PD controlled.
For models with PD controllers, the actuation torque per actuator is computed according to:
Click to expand C++ code...
ũ = -Kp⋅(q − qd) - Kd⋅(v − vd) + u_ff u = max(−e, min(e, ũ))
where qd and vd are desired configuration and velocity (see get_desired_state_input_port()) for the actuated joint (see JointActuator::joint()), Kp and Kd are the proportional and derivative gains of the actuator (see JointActuator::get_controller_gains()),
u_ff
is the feed-forward actuation specified with get_actuation_input_port(), ande
corresponds to effort limit (see JointActuator::effort_limit()).Notice that actuation through get_actuation_input_port() and PD control are not mutually exclusive, and they can be used together. This is better explained through examples: 1. PD controlled gripper. In this case, only PD control is used to drive the opening and closing of the fingers. The feed-forward term is assumed to be zero and the actuation input port is not required to be connected. 2. Robot arm. A typical configuration consists on applying gravity compensation in the feed-forward term plus PD control to drive the robot to a given desired state.
** Actuation input ports requirements
The following table specifies whether actuation ports are required to be connected or not:
Port | without PD control | with PD control | |- ——————————
- :——————-: |
- ————-
- | get_actuation_input_port() | yes | no¹ | |
get_desired_state_input_port() | no² | yes |
¹ Feed-forward actuation is not required for models with PD controlled actuators. This simplifies the diagram wiring for models that only rely on PD controllers.
² This port is always declared, though it will be zero sized for model instances with no PD controllers.
** Net actuation
The total joint actuation applied via the actuation input port (get_actuation_input_port()) and applied by the PD controllers is reported by the net actuation port (get_net_actuation_output_port()). That is, the net actuation port reports the total actuation applied by a given actuator.
Note
PD controllers are ignored when a joint is locked (see Joint::Lock()), and thus they have no effect on the actuation output.
**** Loading models from SDFormat files
Drake has the capability to load multibody models from SDFormat and URDF files. Consider the example below which loads an acrobot model:
Click to expand C++ code...
MultibodyPlant<T> acrobot; SceneGraph<T> scene_graph; Parser parser(&acrobot, &scene_graph); const std::string url = "package://drake/multibody/benchmarks/acrobot/acrobot.sdf"; parser.AddModelsFromUrl(url);
As in the example above, for models including visual geometry, collision geometry or both, the user must specify a SceneGraph for geometry handling. You can find a full example of the LQR controlled acrobot in examples/multibody/acrobot/run_lqr.cc.
AddModelFromFile() can be invoked multiple times on the same plant in order to load multiple model instances. Other methods are available on Parser such as AddModels() which allows creating model instances per each
<model>
tag found in the file. Please refer to each of these methods’ documentation for further details.**** Working with SceneGraph
** Adding a MultibodyPlant connected to a SceneGraph to your Diagram
Probably the simplest way to add and wire up a MultibodyPlant with a SceneGraph in your Diagram is using AddMultibodyPlantSceneGraph().
Recommended usages:
Assign to a MultibodyPlant reference (ignoring the SceneGraph):
Click to expand C++ code...
MultibodyPlant<double>& plant = AddMultibodyPlantSceneGraph(&builder, 0.0 /+ time_step +/); plant.DoFoo(...);
This flavor is the simplest, when the SceneGraph is not explicitly needed. (It can always be retrieved later via GetSubsystemByName(“scene_graph”).)
Assign to auto, and use the named public fields:
Click to expand C++ code...
auto items = AddMultibodyPlantSceneGraph(&builder, 0.0 /+ time_step +/); items.plant.DoFoo(...); items.scene_graph.DoBar(...);
or taking advantage of C++’s structured binding:
Click to expand C++ code...
auto [plant, scene_graph] = AddMultibodyPlantSceneGraph(&builder, 0.0); ... plant.DoFoo(...); scene_graph.DoBar(...);
This is the easiest way to use both the plant and scene_graph.
Assign to already-declared pointer variables:
Click to expand C++ code...
MultibodyPlant<double>* plant{}; SceneGraph<double>* scene_graph{}; std::tie(plant, scene_graph) = AddMultibodyPlantSceneGraph(&builder, 0.0 /+ time_step +/); plant->DoFoo(...); scene_graph->DoBar(...);
This flavor is most useful when the pointers are class member fields (and so perhaps cannot be references).
** Registering geometry with a SceneGraph
MultibodyPlant users can register geometry with a SceneGraph for essentially two purposes; a) visualization and, b) contact modeling.
Before any geometry registration takes place, a user must first make a call to RegisterAsSourceForSceneGraph() in order to register the MultibodyPlant as a client of a SceneGraph instance, point at which the plant will have assigned a valid geometry::SourceId. At Finalize(), MultibodyPlant will declare input/output ports as appropriate to communicate with the SceneGraph instance on which registrations took place. All geometry registration must be performed pre-finalize.
Multibodyplant declares an input port for geometric queries, see get_geometry_query_input_port(). If MultibodyPlant registers geometry with a SceneGraph via calls to RegisterCollisionGeometry(), users may use this port for geometric queries. The port must be connected to the same SceneGraph used for registration. The preferred mechanism is to use AddMultibodyPlantSceneGraph() as documented above.
In extraordinary circumstances, this can be done by hand and the setup process will include:
Call to RegisterAsSourceForSceneGraph().
Calls to RegisterCollisionGeometry(), as many as needed.
Call to Finalize(), user is done specifying the model.
4. Connect geometry::SceneGraph::get_query_output_port() to get_geometry_query_input_port(). 5. Connect get_geometry_pose_output_port() to geometry::SceneGraph::get_source_pose_port()
Refer to the documentation provided in each of the methods above for further details.
** Accessing point contact parameters MultibodyPlant’s point contact model looks for model parameters stored as geometry::ProximityProperties by geometry::SceneGraph. These properties can be obtained before or after context creation through geometry::SceneGraphInspector APIs as outlined below. MultibodyPlant expects the following properties for point contact modeling:
|Group name|Property Name|Required|Property Type|Property Description| |:--------:|:———–:|:------:|:—————-:|:-------------------| |material|coulomb_friction|yes¹|CoulombFriction<T>|Static and Dynamic friction.| |material|point_contact_stiffness|no²|T| Compliant point contact stiffness.| |material|hunt_crossley_dissipation |no²⁴|T| Compliant contact dissipation.| |material|relaxation_time|yes³⁴|T|Linear Kelvin–Voigt model parameter.|
¹ Collision geometry is required to be registered with a geometry::ProximityProperties object that contains the (“material”, “coulomb_friction”) property. If the property is missing, MultibodyPlant will throw an exception.
² If the property is missing, MultibodyPlant will use a heuristic value as the default. Refer to the section point_contact_defaults “Point Contact Default Parameters” for further details.
³ When using a linear Kelvin–Voigt model of dissipation (for instance when selecting the SAP solver), collision geometry is required to be registered with a geometry::ProximityProperties object that contains the (“material”, “relaxation_time”) property. If the property is missing, an exception will be thrown.
⁴ We allow to specify both hunt_crossley_dissipation and relaxation_time for a given geometry. However only one of these will get used, depending on the configuration of the MultibodyPlant. As an example, if the SAP contact approximation is specified (see set_discrete_contact_approximation()) only the relaxation_time is used while hunt_crossley_dissipation is ignored. Conversely, if the TAMSI, Similar or Lagged approximation is used (see set_discrete_contact_approximation()) only hunt_crossley_dissipation is used while relaxation_time is ignored. Currently, a continuous MultibodyPlant model will always use the Hunt & Crossley model and relaxation_time will be ignored.
Accessing and modifying contact properties requires interfacing with geometry::SceneGraph’s model inspector. Interfacing with a model inspector obtained from geometry::SceneGraph will provide the default registered values for a given parameter. These are the values that will initially appear in a systems::Context created by CreateDefaultContext(). Subsequently, true system parameters can be accessed and changed through a systems::Context once available. For both of the above cases, proximity properties are accessed through geometry::SceneGraphInspector APIs.
Before context creation an inspector can be retrieved directly from SceneGraph as:
Click to expand C++ code...
// For a SceneGraph<T> instance called scene_graph. const geometry::SceneGraphInspector<T>& inspector = scene_graph.model_inspector();
After context creation, an inspector can be retrieved from the state stored in the context:
Click to expand C++ code...
// For a MultibodyPlant<T> instance called mbp and a Context<T> called // context. const geometry::SceneGraphInspector<T>& inspector = mbp.EvalSceneGraphInspector(context);
Once an inspector is available, proximity properties can be retrieved as:
Click to expand C++ code...
// For a body with GeometryId called geometry_id const geometry::ProximityProperties* props = inspector.GetProximityProperties(geometry_id); const CoulombFriction<T>& geometry_friction = props->GetProperty<CoulombFriction<T>>("material", "coulomb_friction");
**** Working with MultibodyElement parameters Several MultibodyElements expose parameters, allowing the user flexible modification of some aspects of the plant’s model, post systems::Context creation. For details, refer to the documentation for the MultibodyElement whose parameters you are trying to modify/access (e.g. RigidBody, FixedOffsetFrame, etc.)
As an example, here is how to access and modify rigid body mass parameters:
Click to expand C++ code...
MultibodyPlant<double> plant; // ... Code to add bodies, finalize plant, and to obtain a context. const RigidBody<double>& body = plant.GetRigidBodyByName("BodyName"); const SpatialInertia<double> M_BBo_B = body.GetSpatialInertiaInBodyFrame(context); // .. logic to determine a new SpatialInertia parameter for body. const SpatialInertia<double>& M_BBo_B_new = .... // Modify the body parameter for spatial inertia. body.SetSpatialInertiaInBodyFrame(&context, M_BBo_B_new);
Another example, working with automatic differentiation in order to take derivatives with respect to one of the bodies’ masses:
Click to expand C++ code...
MultibodyPlant<double> plant; // ... Code to add bodies, finalize plant, and to obtain a // context and a body's spatial inertia M_BBo_B. // Scalar convert the plant. unique_ptr<MultibodyPlant<AutoDiffXd>> plant_autodiff = systems::System<double>::ToAutoDiffXd(plant); unique_ptr<Context<AutoDiffXd>> context_autodiff = plant_autodiff->CreateDefaultContext(); context_autodiff->SetTimeStateAndParametersFrom(context); const RigidBody<AutoDiffXd>& body = plant_autodiff->GetRigidBodyByName("BodyName"); // Modify the body parameter for mass. const AutoDiffXd mass_autodiff(mass, Vector1d(1)); body.SetMass(context_autodiff.get(), mass_autodiff); // M_autodiff(i, j).derivatives()(0), contains the derivatives of // M(i, j) with respect to the body's mass. MatrixX<AutoDiffXd> M_autodiff(plant_autodiff->num_velocities(), plant_autodiff->num_velocities()); plant_autodiff->CalcMassMatrix(*context_autodiff, &M_autodiff);
**** Adding modeling elements
Add multibody elements to a MultibodyPlant with methods like:
Bodies: AddRigidBody()
Joints: AddJoint()
see mbp_construction “Construction” for more.
All modeling elements must be added before Finalize() is called. See mbp_finalize_stage “Finalize stage” for a discussion.
**** Modeling contact
Please refer to drake_contacts “Contact Modeling in Drake” for details on the available approximations, setup, and considerations for a multibody simulation with frictional contact.
**** Energy and Power
MultibodyPlant implements the System energy and power methods, with some limitations. - Kinetic energy: fully implemented. - Potential energy and conservative power: currently include only gravity and contributions from ForceElement objects; potential energy from compliant contact and joint limits are not included. - Nonconservative power: currently includes only contributions from ForceElement objects; actuation and input port forces, joint damping, and dissipation from joint limits, friction, and contact dissipation are not included.
See Drake issue #12942 for more discussion.
**** Finalize() stage
Once the user is done adding modeling elements and registering geometry, a call to Finalize() must be performed. This call will: - Build the underlying tree structure of the multibody model, - declare the plant’s state, - declare the plant’s input and output ports, - declare collision filters to ignore collisions among rigid bodies: - between rigid bodies connected by a joint, - within subgraphs of welded rigid bodies. Note that MultibodyPlant will not introduce any collision filters on deformable bodies.
**** References
[Featherstone 2008] Featherstone, R., 2008.
Rigid body dynamics algorithms. Springer. - [Jain 2010] Jain, A., 2010. Robot and multibody dynamics: analysis and algorithms. Springer Science & Business Media. - [Seth 2010] Seth, A., Sherman, M., Eastman, P. and Delp, S., 2010. Minimal formulation of joint motion for biomechanisms. Nonlinear dynamics, 62(1), pp.291-303.
Note
This class is templated; see
MultibodyPlant_
for the list of instantiations.- __init__(self: pydrake.multibody.plant.MultibodyPlant, time_step: float) None
This constructor creates a plant with a single “world” body. Therefore, right after creation, num_bodies() returns one.
MultibodyPlant offers two different modalities to model mechanical systems in time. These are: 1. As a discrete system with periodic updates,
time_step
is strictly greater than zero. 2. As a continuous system,time_step
equals exactly zero.Currently the discrete model is preferred for simulation given its robustness and speed in problems with frictional contact. However this might change as we work towards developing better strategies to model contact. See multibody_simulation for further details.
Warning
Users should be aware of current limitations in either modeling modality. While the discrete model is often the preferred option for problems with frictional contact given its robustness and speed, it might become unstable when using large feedback gains, high damping or large external forcing. MultibodyPlant will throw an exception whenever the discrete solver is detected to fail. Conversely, the continuous modality has the potential to leverage the robustness and accuracy control provide by Drake’s integrators. However thus far this has proved difficult in practice and especially due to poor performance.
- Parameter
time_step
: Indicates whether
this
plant is modeled as a continuous system (time_step = 0
) or as a discrete system with periodic updates of periodtime_step > 0
. See multibody_simulation for further details.
Warning
Currently the continuous modality with
time_step = 0
does not support joint limits for simulation, these are ignored. MultibodyPlant prints a warning to console if joint limits are provided. If your simulation requires joint limits currently you must use a discrete MultibodyPlant model.- Raises
RuntimeError if time_step is negative. –
- Parameter
- AddBallConstraint(self: pydrake.multibody.plant.MultibodyPlant, body_A: pydrake.multibody.tree.RigidBody, p_AP: numpy.ndarray[numpy.float64[3, 1]], body_B: pydrake.multibody.tree.RigidBody, p_BQ: Optional[numpy.ndarray[numpy.float64[3, 1]]] = None) pydrake.multibody.tree.MultibodyConstraintId
Defines a constraint such that point P affixed to body A is coincident at all times with point Q affixed to body B, effectively modeling a ball-and-socket joint.
- Parameter
body_A
: RigidBody to which point P is rigidly attached.
- Parameter
p_AP
: Position of point P in body A’s frame.
- Parameter
body_B
: RigidBody to which point Q is rigidly attached.
- Parameter
p_BQ
: (optional) Position of point Q in body B’s frame. If p_BQ is std::nullopt, then p_BQ will be computed so that the constraint is satisfied for the default configuration at Finalize() time; subsequent changes to the default configuration will not change the computed p_BQ.
- Returns
the id of the newly added constraint.
- Raises
RuntimeError if bodies A and B are the same body. –
RuntimeError if the MultibodyPlant has already been finalized. –
RuntimeError if this MultibodyPlant is not a discrete model –
(is_discrete() == false) –
RuntimeError if this MultibodyPlant's underlying contact –
solver is not SAP. (i.e. get_discrete_contact_solver() != –
DiscreteContactSolver::kSap) –
- Parameter
- AddCouplerConstraint(self: pydrake.multibody.plant.MultibodyPlant, joint0: pydrake.multibody.tree.Joint, joint1: pydrake.multibody.tree.Joint, gear_ratio: float, offset: float = 0.0) pydrake.multibody.tree.MultibodyConstraintId
Defines a holonomic constraint between two single-dof joints
joint0
andjoint1
with positions q₀ and q₁, respectively, such that q₀ = ρ⋅q₁ + Δq, where ρ is the gear ratio and Δq is a fixed offset. The gear ratio can have units if the units of q₀ and q₁ are different. For instance, between a prismatic and a revolute joint the gear ratio will specify the “pitch” of the resulting mechanism. As defined,offset
has units ofq₀
.Note
joint0 and/or joint1 can still be actuated, regardless of whether we have coupler constraint among them. That is, one or both of these joints can have external actuation applied to them.
Note
Generally, to couple (q0, q1, q2), the user would define a coupler between (q0, q1) and a second coupler between (q1, q2), or any combination therein.
- Raises
if joint0 and joint1 are not both single-dof joints. –
RuntimeError if the MultibodyPlant has already been finalized. –
RuntimeError if this MultibodyPlant is not a discrete model –
(is_discrete() == false) –
RuntimeError if this MultibodyPlant's underlying contact –
solver is not SAP. (i.e. get_discrete_contact_solver() != –
DiscreteContactSolver::kSap) –
- AddDistanceConstraint(self: pydrake.multibody.plant.MultibodyPlant, body_A: pydrake.multibody.tree.RigidBody, p_AP: numpy.ndarray[numpy.float64[3, 1]], body_B: pydrake.multibody.tree.RigidBody, p_BQ: numpy.ndarray[numpy.float64[3, 1]], distance: float, stiffness: float = inf, damping: float = 0.0) pydrake.multibody.tree.MultibodyConstraintId
Defines a distance constraint between a point P on a body A and a point Q on a body B.
This constraint can be compliant, modeling a spring with free length
distance
and givenstiffness
anddamping
parameters between points P and Q. For d = ‖p_PQ‖, then a compliant distance constraint models a spring with force along p_PQ given by:f = −stiffness ⋅ d − damping ⋅ ḋ
- Parameter
body_A
: RigidBody to which point P is rigidly attached.
- Parameter
p_AP
: Position of point P in body A’s frame.
- Parameter
body_B
: RigidBody to which point Q is rigidly attached.
- Parameter
p_BQ
: Position of point Q in body B’s frame.
- Parameter
distance
: Fixed length of the distance constraint, in meters. It must be strictly positive.
- Parameter
stiffness
: For modeling a spring with free length equal to
distance
, the stiffness parameter in N/m. Optional, with its default value being infinite to model a rigid massless rod of lengthdistance
connecting points A and B.- Parameter
damping
: For modeling a spring with free length equal to
distance
, damping parameter in N⋅s/m. Optional, with its default value being zero for a non-dissipative constraint.
- Returns
the id of the newly added constraint.
Warning
Currently, it is the user’s responsibility to initialize the model’s context in a configuration compatible with the newly added constraint.
Warning
A distance constraint is the wrong modeling choice if the distance needs to go through zero. To constrain two points to be coincident we need a 3-dof ball constraint, the 1-dof distance constraint is singular in this case. Therefore we require the distance parameter to be strictly positive.
- Raises
RuntimeError if bodies A and B are the same body. –
RuntimeError if distance is not strictly positive. –
RuntimeError if stiffness is not positive or zero. –
RuntimeError if damping is not positive or zero. –
RuntimeError if the MultibodyPlant has already been finalized. –
RuntimeError if this MultibodyPlant is not a discrete model –
(is_discrete() == false) –
RuntimeError if this MultibodyPlant's underlying contact –
solver is not SAP. (i.e. get_discrete_contact_solver() != –
DiscreteContactSolver::kSap) –
- Parameter
- AddForceElement(self: pydrake.multibody.plant.MultibodyPlant, force_element: pydrake.multibody.tree.ForceElement) pydrake.multibody.tree.ForceElement
Adds a new force element model of type
ForceElementType
tothis
MultibodyPlant. The arguments to this methodargs
are forwarded to ``ForceElementType`’s constructor.- Parameter
args
: Zero or more parameters provided to the constructor of the new force element. It must be the case that ForceElementType<T>(args)` is a valid constructor.
- Template parameter
ForceElementType
: The type of the ForceElement to add. As there is always a UniformGravityFieldElement present (accessible through gravity_field()), an exception will be thrown if this function is called to add another UniformGravityFieldElement.
- Returns
A constant reference to the new ForceElement just added, of type
ForceElementType<T>
specialized on the scalar type T ofthis
MultibodyPlant. It will remain valid for the lifetime ofthis
MultibodyPlant.
See also
The ForceElement class’s documentation for further details on how a force element is defined.
- Parameter
- AddFrame(self: pydrake.multibody.plant.MultibodyPlant, frame: pydrake.multibody.tree.Frame) pydrake.multibody.tree.Frame
This method adds a Frame of type
FrameType<T>
. For more information, please see the corresponding constructor ofFrameType
.- Template parameter
FrameType
: Template which will be instantiated on
T
.- Parameter
frame
: Unique pointer frame instance.
- Returns
A constant reference to the new Frame just added, which will remain valid for the lifetime of
this
MultibodyPlant.
- Template parameter
- AddJoint(self: pydrake.multibody.plant.MultibodyPlant, joint: pydrake.multibody.tree.Joint) pydrake.multibody.tree.Joint
This method adds a Joint of type
JointType
between two bodies. For more information, see the below overload ofAddJoint<>
.
- AddJointActuator(self: pydrake.multibody.plant.MultibodyPlant, name: str, joint: pydrake.multibody.tree.Joint, effort_limit: float = inf) pydrake.multibody.tree.JointActuator
Creates and adds a JointActuator model for an actuator acting on a given
joint
. This method returns a constant reference to the actuator just added, which will remain valid for the lifetime ofthis
plant.- Parameter
name
: A string that uniquely identifies the new actuator to be added to
this
model. A RuntimeError is thrown if an actuator with the same name already exists in the model. See HasJointActuatorNamed().- Parameter
joint
: The Joint to be actuated by the new JointActuator.
- Parameter
effort_limit
: The maximum effort for the actuator. It must be strictly positive, otherwise an RuntimeError is thrown. If +∞, the actuator has no limit, which is the default. The effort limit has physical units in accordance to the joint type it actuates. For instance, it will have units of N⋅m (torque) for revolute joints while it will have units of N (force) for prismatic joints.
Note
The effort limit is unused by MultibodyPlant and is simply provided here for bookkeeping purposes. It will not, for instance, saturate external actuation inputs based on this value. If, for example, a user intends to saturate the force/torque that is applied to the MultibodyPlant via this actuator, the user-level code (e.g., a controller) should query this effort limit and impose the saturation there.
- Returns
A constant reference to the new JointActuator just added, which will remain valid for the lifetime of
this
plant or until the JointActuator has been removed from the plant with RemoveJointActuator().- Raises
RuntimeError if joint.num_velocities() > 1 since for now we –
only support actuators for single dof joints. –
See also
RemoveJointActuator()
- Parameter
- AddModelInstance(self: pydrake.multibody.plant.MultibodyPlant, name: str) pydrake.multibody.tree.ModelInstanceIndex
Creates a new model instance. Returns the index for the model instance.
- Parameter
name
: A string that uniquely identifies the new instance to be added to
this
model. An exception is thrown if an instance with the same name already exists in the model. See HasModelInstanceNamed().
- Parameter
- AddRigidBody(*args, **kwargs)
Overloaded function.
AddRigidBody(self: pydrake.multibody.plant.MultibodyPlant, name: str, M_BBo_B: pydrake.multibody.tree.SpatialInertia = SpatialInertia.Zero()) -> pydrake.multibody.tree.RigidBody
Creates a rigid body with the provided name and spatial inertia. This method returns a constant reference to the body just added, which will remain valid for the lifetime of
this
MultibodyPlant. The body will use the default model instance (model_instance “more on model instances”).Example of usage:
Click to expand C++ code...
MultibodyPlant<T> plant; // ... Code to define spatial_inertia, a SpatialInertia<T> object ... const RigidBody<T>& body = plant.AddRigidBody("BodyName", spatial_inertia);
- Parameter
name
: A string that identifies the new body to be added to
this
model. A RuntimeError is thrown if a body namedname
already is part of the model in the default model instance. See HasBodyNamed(), RigidBody::name().- Parameter
M_BBo_B
: The SpatialInertia of the new rigid body to be added to
this
MultibodyPlant, computed about the body frame originBo
and expressed in the body frame B. When not provided, defaults to zero.
- Returns
A constant reference to the new RigidBody just added, which will remain valid for the lifetime of
this
MultibodyPlant.- Raises
RuntimeError if additional model instances have been created –
beyond the world and default instances. –
AddRigidBody(self: pydrake.multibody.plant.MultibodyPlant, name: str, model_instance: pydrake.multibody.tree.ModelInstanceIndex, M_BBo_B: pydrake.multibody.tree.SpatialInertia = SpatialInertia.Zero()) -> pydrake.multibody.tree.RigidBody
Creates a rigid body with the provided name and spatial inertia. This method returns a constant reference to the body just added, which will remain valid for the lifetime of
this
MultibodyPlant.Example of usage:
Click to expand C++ code...
MultibodyPlant<T> plant; // ... Code to define spatial_inertia, a SpatialInertia<T> object ... ModelInstanceIndex model_instance = plant.AddModelInstance("instance"); const RigidBody<T>& body = plant.AddRigidBody("BodyName", model_instance, spatial_inertia);
- Parameter
name
: A string that identifies the new body to be added to
this
model. A RuntimeError is thrown if a body namedname
already is part ofmodel_instance
. See HasBodyNamed(), RigidBody::name().- Parameter
model_instance
: A model instance index which this body is part of.
- Parameter
M_BBo_B
: The SpatialInertia of the new rigid body to be added to
this
MultibodyPlant, computed about the body frame originBo
and expressed in the body frame B. When not provided, defaults to zero.
- Returns
A constant reference to the new RigidBody just added, which will remain valid for the lifetime of
this
MultibodyPlant.
- AddWeldConstraint(self: pydrake.multibody.plant.MultibodyPlant, body_A: pydrake.multibody.tree.RigidBody, X_AP: pydrake.math.RigidTransform, body_B: pydrake.multibody.tree.RigidBody, X_BQ: pydrake.math.RigidTransform) pydrake.multibody.tree.MultibodyConstraintId
Defines a constraint such that frame P affixed to body A is coincident at all times with frame Q affixed to body B, effectively modeling a weld joint.
- Parameter
body_A
: RigidBody to which frame P is rigidly attached.
- Parameter
X_AP
: Pose of frame P in body A’s frame.
- Parameter
body_B
: RigidBody to which frame Q is rigidly attached.
- Parameter
X_BQ
: Pose of frame Q in body B’s frame.
- Returns
the id of the newly added constraint.
- Raises
RuntimeError if bodies A and B are the same body. –
RuntimeError if the MultibodyPlant has already been finalized. –
RuntimeError if this MultibodyPlant is not a discrete model –
(is_discrete() == false) –
RuntimeError if this MultibodyPlant's underlying contact –
solver is not SAP. (i.e. get_discrete_contact_solver() != –
DiscreteContactSolver::kSap) –
- Parameter
- CalcBiasCenterOfMassTranslationalAcceleration(*args, **kwargs)
Overloaded function.
CalcBiasCenterOfMassTranslationalAcceleration(self: pydrake.multibody.plant.MultibodyPlant, context: pydrake.systems.framework.Context, with_respect_to: pydrake.multibody.tree.JacobianWrtVariable, frame_A: pydrake.multibody.tree.Frame, frame_E: pydrake.multibody.tree.Frame) -> numpy.ndarray[numpy.float64[3, 1]]
For the system S of all bodies other than the world body, calculates a𝑠Bias_AScm_E, Scm’s translational acceleration bias in frame A with respect to “speeds” 𝑠, expressed in frame E, where Scm is the center of mass of S and speeds 𝑠 is either q̇ or v.
- Parameter
context
: Contains the state of the multibody system.
- Parameter
with_respect_to
: Enum equal to JacobianWrtVariable::kQDot or JacobianWrtVariable::kV, indicating whether the accceleration bias is with respect to 𝑠 = q̇ or 𝑠 = v. Currently, an exception is thrown if with_respect_to is JacobianWrtVariable::kQDot.
- Parameter
frame_A
: The frame in which a𝑠Bias_AScm is measured.
- Parameter
frame_E
: The frame in which a𝑠Bias_AScm is expressed on output.
- Returns
a𝑠Bias_AScm_E Point Scm’s translational acceleration bias in frame A with respect to speeds 𝑠 (𝑠 = q̇ or 𝑠 = v), expressed in frame E.
- Raises
RuntimeError if this has no body except world_body() –
RuntimeError if mₛ ≤ 0, where mₛ is the mass of system S. –
RuntimeError if with_respect_to is JacobianWrtVariable::kQDot. –
See also
CalcJacobianCenterOfMassTranslationalVelocity() to compute J𝑠_v_Scm, point Scm’s translational velocity Jacobian in frame A with respect to 𝑠.
Note
The world_body() is ignored. asBias_AScm_E = ∑ (mᵢ aᵢ) / mₛ, where mₛ = ∑ mᵢ is the mass of system S, mᵢ is the mass of the iᵗʰ body, and aᵢ is the translational bias acceleration of Bᵢcm in frame A expressed in frame E for speeds 𝑠 (Bᵢcm is the center of mass of the iᵗʰ body).
Note
See bias_acceleration_functions “Bias acceleration functions” for theory and details.
CalcBiasCenterOfMassTranslationalAcceleration(self: pydrake.multibody.plant.MultibodyPlant, context: pydrake.systems.framework.Context, model_instances: list[pydrake.multibody.tree.ModelInstanceIndex], with_respect_to: pydrake.multibody.tree.JacobianWrtVariable, frame_A: pydrake.multibody.tree.Frame, frame_E: pydrake.multibody.tree.Frame) -> numpy.ndarray[numpy.float64[3, 1]]
For the system S containing the selected model instances, calculates a𝑠Bias_AScm_E, Scm’s translational acceleration bias in frame A with respect to “speeds” 𝑠, expressed in frame E, where Scm is the center of mass of S and speeds 𝑠 is either q̇ or v.
- Parameter
context
: Contains the state of the multibody system.
- Parameter
model_instances
: Vector of selected model instances. If a model instance is repeated in the vector (unusual), it is only counted once.
- Parameter
with_respect_to
: Enum equal to JacobianWrtVariable::kQDot or JacobianWrtVariable::kV, indicating whether the accceleration bias is with respect to 𝑠 = q̇ or 𝑠 = v. Currently, an exception is thrown if with_respect_to is JacobianWrtVariable::kQDot.
- Parameter
frame_A
: The frame in which a𝑠Bias_AScm is measured.
- Parameter
frame_E
: The frame in which a𝑠Bias_AScm is expressed on output.
- Returns
a𝑠Bias_AScm_E Point Scm’s translational acceleration bias in frame A with respect to speeds 𝑠 (𝑠 = q̇ or 𝑠 = v), expressed in frame E.
- Raises
RuntimeError if this has no body except world_body() –
RuntimeError if mₛ ≤ 0, where mₛ is the mass of system S. –
RuntimeError if with_respect_to is JacobianWrtVariable::kQDot. –
See also
CalcJacobianCenterOfMassTranslationalVelocity() to compute J𝑠_v_Scm, point Scm’s translational velocity Jacobian in frame A with respect to 𝑠.
Note
The world_body() is ignored. asBias_AScm_E = ∑ (mᵢ aᵢ) / mₛ, where mₛ = ∑ mᵢ is the mass of system S, mᵢ is the mass of the iᵗʰ body, and aᵢ is the translational bias acceleration of Bᵢcm in frame A expressed in frame E for speeds 𝑠 (Bᵢcm is the center of mass of the iᵗʰ body).
Note
See bias_acceleration_functions “Bias acceleration functions” for theory and details.
- CalcBiasSpatialAcceleration(self: pydrake.multibody.plant.MultibodyPlant, context: pydrake.systems.framework.Context, with_respect_to: pydrake.multibody.tree.JacobianWrtVariable, frame_B: pydrake.multibody.tree.Frame, p_BoBp_B: numpy.ndarray[numpy.float64[3, 1]], frame_A: pydrake.multibody.tree.Frame, frame_E: pydrake.multibody.tree.Frame) pydrake.multibody.math.SpatialAcceleration
For one point Bp affixed/welded to a frame B, calculates A𝑠Bias_ABp, Bp’s spatial acceleration bias in frame A with respect to “speeds” 𝑠, expressed in frame E, where speeds 𝑠 is either q̇ or v.
- Parameter
context
: Contains the state of the multibody system.
- Parameter
with_respect_to
: Enum equal to JacobianWrtVariable::kQDot or JacobianWrtVariable::kV, indicating whether the spatial accceleration bias is with respect to 𝑠 = q̇ or 𝑠 = v. Currently, an exception is thrown if with_respect_to is JacobianWrtVariable::kQDot.
- Parameter
frame_B
: The frame on which point Bp is affixed/welded.
- Parameter
p_BoBp_B
: Position vector from Bo (frame_B’s origin) to point Bp (regarded as affixed/welded to B), expressed in frame_B.
- Parameter
frame_A
: The frame in which A𝑠Bias_ABp is measured.
- Parameter
frame_E
: The frame in which A𝑠Bias_ABp is expressed on output.
- Returns
A𝑠Bias_ABp_E Point Bp’s spatial acceleration bias in frame A with respect to speeds 𝑠 (𝑠 = q̇ or 𝑠 = v), expressed in frame E.
See also
CalcJacobianSpatialVelocity() to compute J𝑠_V_ABp, point Bp’s spatial velocity Jacobian in frame A with respect to 𝑠.
- Raises
RuntimeError if with_respect_to is JacobianWrtVariable::kQDot. –
Note
Use CalcBiasTranslationalAcceleration() to efficiently calculate bias translational accelerations for a list of points (each fixed to frame B). This function returns only one bias spatial acceleration, which contains both frame B’s bias angular acceleration and point Bp’s bias translational acceleration.
Note
See bias_acceleration_functions “Bias acceleration functions” for theory and details.
- Parameter
- CalcBiasTerm(self: pydrake.multibody.plant.MultibodyPlant, context: pydrake.systems.framework.Context) numpy.ndarray[numpy.float64[m, 1]]
Computes the bias term
C(q, v) v
containing Coriolis, centripetal, and gyroscopic effects in the multibody equations of motion:Click to expand C++ code...
M(q) v̇ + C(q, v) v = tau_app + ∑ (Jv_V_WBᵀ(q) ⋅ Fapp_Bo_W)
where
M(q)
is the multibody model’s mass matrix (including rigid body mass properties and reflected_inertia “reflected inertias”) andtau_app
is a vector of applied generalized forces. The last term is a summation over all bodies of the dot-product ofFapp_Bo_W
(applied spatial force on body B at Bo) withJv_V_WB(q)
(B’s spatial Jacobian in world W with respect to generalized velocities v). Note: B’s spatial velocity in W can be writtenV_WB = Jv_V_WB * v
.- Parameter
context
: Contains the state of the multibody system, including the generalized positions q and the generalized velocities v.
- Parameter
Cv
: On output,
Cv
will contain the productC(q, v)v
. It must be a valid (non-null) pointer to a column vector inℛⁿ
with n the number of generalized velocities (num_velocities()) of the model. This method aborts if Cv is nullptr or if it does not have the proper size.
- Parameter
- CalcBiasTranslationalAcceleration(self: pydrake.multibody.plant.MultibodyPlant, context: pydrake.systems.framework.Context, with_respect_to: pydrake.multibody.tree.JacobianWrtVariable, frame_B: pydrake.multibody.tree.Frame, p_BoBi_B: numpy.ndarray[numpy.float64[3, n], flags.f_contiguous], frame_A: pydrake.multibody.tree.Frame, frame_E: pydrake.multibody.tree.Frame) numpy.ndarray[numpy.float64[3, n]]
For each point Bi affixed/welded to a frame B, calculates a𝑠Bias_ABi, Bi’s translational acceleration bias in frame A with respect to “speeds” 𝑠, expressed in frame E, where speeds 𝑠 is either q̇ or v.
- Parameter
context
: Contains the state of the multibody system.
- Parameter
with_respect_to
: Enum equal to JacobianWrtVariable::kQDot or JacobianWrtVariable::kV, indicating whether the translational acceleration bias is with respect to 𝑠 = q̇ or 𝑠 = v. Currently, an exception is thrown if with_respect_to is JacobianWrtVariable::kQDot.
- Parameter
frame_B
: The frame on which points Bi are affixed/welded.
- Parameter
p_BoBi_B
: A position vector or list of p position vectors from Bo (frame_B’s origin) to points Bi (regarded as affixed to B), where each position vector is expressed in frame_B. Each column in the
3 x p
matrix p_BoBi_B corresponds to a position vector.- Parameter
frame_A
: The frame in which a𝑠Bias_ABi is measured.
- Parameter
frame_E
: The frame in which a𝑠Bias_ABi is expressed on output.
- Returns
a𝑠Bias_ABi_E Point Bi’s translational acceleration bias in frame A with respect to speeds 𝑠 (𝑠 = q̇ or 𝑠 = v), expressed in frame E. a𝑠Bias_ABi_E is a
3 x p
matrix, where p is the number of points Bi.
See also
CalcJacobianTranslationalVelocity() to compute J𝑠_v_ABi, point Bi’s translational velocity Jacobian in frame A with respect to 𝑠.
- Precondition:
p_BoBi_B must have 3 rows.
- Raises
RuntimeError if with_respect_to is JacobianWrtVariable::kQDot. –
Note
See bias_acceleration_functions “Bias acceleration functions” for theory and details.
- Parameter
- CalcCenterOfMassPositionInWorld(*args, **kwargs)
Overloaded function.
CalcCenterOfMassPositionInWorld(self: pydrake.multibody.plant.MultibodyPlant, context: pydrake.systems.framework.Context) -> numpy.ndarray[numpy.float64[3, 1]]
Calculates the position vector from the world origin Wo to the center of mass of all bodies in this MultibodyPlant, expressed in the world frame W.
- Parameter
context
: Contains the state of the model.
- Returns
p_WoScm_W
: position vector from Wo to Scm expressed in world frame W, where Scm is the center of mass of the system S stored by
this
plant.
- Raises
RuntimeError if this has no body except world_body() –
RuntimeError if mₛ ≤ 0 (where mₛ is the mass of system S) –
Note
The world_body() is ignored. p_WoScm_W = ∑ (mᵢ pᵢ) / mₛ, where mₛ = ∑ mᵢ, mᵢ is the mass of the iᵗʰ body, and pᵢ is Bᵢcm’s position from Wo expressed in frame W (Bᵢcm is the center of mass of the iᵗʰ body).
CalcCenterOfMassPositionInWorld(self: pydrake.multibody.plant.MultibodyPlant, context: pydrake.systems.framework.Context, model_instances: list[pydrake.multibody.tree.ModelInstanceIndex]) -> numpy.ndarray[numpy.float64[3, 1]]
Calculates the position vector from the world origin Wo to the center of mass of all non-world bodies contained in model_instances, expressed in the world frame W.
- Parameter
context
: Contains the state of the model.
- Parameter
model_instances
: Vector of selected model instances. If a model instance is repeated in the vector (unusual), it is only counted once.
- Returns
p_WoScm_W
: position vector from world origin Wo to Scm expressed in the world frame W, where Scm is the center of mass of the system S of non-world bodies contained in model_instances.
- Raises
RuntimeError if model_instances is empty or only has world body. –
RuntimeError if mₛ ≤ 0 (where mₛ is the mass of system S) –
Note
The world_body() is ignored. p_WoScm_W = ∑ (mᵢ pᵢ) / mₛ, where mₛ = ∑ mᵢ, mᵢ is the mass of the iᵗʰ body contained in model_instances, and pᵢ is Bᵢcm’s position vector from Wo expressed in frame W (Bᵢcm is the center of mass of the iᵗʰ body).
- CalcCenterOfMassTranslationalAccelerationInWorld(*args, **kwargs)
Overloaded function.
CalcCenterOfMassTranslationalAccelerationInWorld(self: pydrake.multibody.plant.MultibodyPlant, context: pydrake.systems.framework.Context) -> numpy.ndarray[numpy.float64[3, 1]]
For the system S contained in this MultibodyPlant, calculates Scm’s translational acceleration in the world frame W expressed in W, where Scm is the center of mass of S.
- Parameter
context
: The context contains the state of the model.
- Returns
a_WScm_W
: Scm’s translational acceleration in the world frame W expressed in the world frame W.
- Raises
RuntimeError if this has no body except world_body() –
RuntimeError if mₛ ≤ 0, where mₛ is the mass of system S. –
Note
The world_body() is ignored. a_WScm_W = ∑ (mᵢ aᵢ) / mₛ, where mₛ = ∑ mᵢ is the mass of system S, mᵢ is the mass of the iᵗʰ body, and aᵢ is the translational acceleration of Bᵢcm in world W expressed in W (Bᵢcm is the center of mass of the iᵗʰ body).
Note
When cached values are out of sync with the state stored in context, this method performs an expensive forward dynamics computation, whereas once evaluated, successive calls to this method are inexpensive.
CalcCenterOfMassTranslationalAccelerationInWorld(self: pydrake.multibody.plant.MultibodyPlant, context: pydrake.systems.framework.Context, model_instances: list[pydrake.multibody.tree.ModelInstanceIndex]) -> numpy.ndarray[numpy.float64[3, 1]]
For the system S containing the selected model instances, calculates Scm’s translational acceleration in the world frame W expressed in W, where Scm is the center of mass of S.
- Parameter
context
: The context contains the state of the model.
- Parameter
model_instances
: Vector of selected model instances. If a model instance is repeated in the vector (unusual), it is only counted once.
- Returns
a_WScm_W
: Scm’s translational acceleration in the world frame W expressed in the world frame W.
- Raises
RuntimeError if model_instances is empty or only has world body. –
RuntimeError if mₛ ≤ 0, where mₛ is the mass of system S. –
Note
The world_body() is ignored. a_WScm_W = ∑ (mᵢ aᵢ) / mₛ, where mₛ = ∑ mᵢ is the mass of system S, mᵢ is the mass of the iᵗʰ body in model_instances, and aᵢ is the translational acceleration of Bᵢcm in world W expressed in W (Bᵢcm is the center of mass of the iᵗʰ body).
Note
When cached values are out of sync with the state stored in context, this method performs an expensive forward dynamics computation, whereas once evaluated, successive calls to this method are inexpensive.
- CalcCenterOfMassTranslationalVelocityInWorld(*args, **kwargs)
Overloaded function.
CalcCenterOfMassTranslationalVelocityInWorld(self: pydrake.multibody.plant.MultibodyPlant, context: pydrake.systems.framework.Context) -> numpy.ndarray[numpy.float64[3, 1]]
Calculates system center of mass translational velocity in world frame W.
- Parameter
context
: The context contains the state of the model.
- Returns
v_WScm_W
: Scm’s translational velocity in frame W, expressed in W, where Scm is the center of mass of the system S stored by
this
plant.
- Raises
RuntimeError if this has no body except world_body() –
RuntimeError if mₛ ≤ 0 (where mₛ is the mass of system S) –
Note
The world_body() is ignored. v_WScm_W = ∑ (mᵢ vᵢ) / mₛ, where mₛ = ∑ mᵢ, mᵢ is the mass of the iᵗʰ body, and vᵢ is Bᵢcm’s velocity in world W (Bᵢcm is the center of mass of the iᵗʰ body).
CalcCenterOfMassTranslationalVelocityInWorld(self: pydrake.multibody.plant.MultibodyPlant, context: pydrake.systems.framework.Context, model_instances: list[pydrake.multibody.tree.ModelInstanceIndex]) -> numpy.ndarray[numpy.float64[3, 1]]
Calculates system center of mass translational velocity in world frame W.
- Parameter
context
: The context contains the state of the model.
- Parameter
model_instances
: Vector of selected model instances. If a model instance is repeated in the vector (unusual), it is only counted once.
- Returns
v_WScm_W
: Scm’s translational velocity in frame W, expressed in W, where Scm is the center of mass of the system S of non-world bodies contained in model_instances.
- Raises
RuntimeError if model_instances is empty or only has world body. –
RuntimeError if mₛ ≤ 0 (where mₛ is the mass of system S) –
Note
The world_body() is ignored. v_WScm_W = ∑ (mᵢ vᵢ) / mₛ, where mₛ = ∑ mᵢ, mᵢ is the mass of the iᵗʰ body contained in model_instances, and vᵢ is Bᵢcm’s velocity in world W expressed in frame W (Bᵢcm is the center of mass of the iᵗʰ body).
- CalcForceElementsContribution(self: pydrake.multibody.plant.MultibodyPlant, context: pydrake.systems.framework.Context, forces: pydrake.multibody.tree.MultibodyForces) None
Computes the combined force contribution of ForceElement objects in the model. A ForceElement can apply forces as a spatial force per body or as generalized forces, depending on the ForceElement model. ForceElement contributions are a function of the state and time only. The output from this method can immediately be used as input to CalcInverseDynamics() to include the effect of applied forces by force elements.
- Parameter
context
: The context containing the state of this model.
- Parameter
forces
: A pointer to a valid, non nullptr, multibody forces object. On output
forces
will store the forces exerted by all the ForceElement objects in the model.
- Raises
RuntimeError if forces is null or not compatible with this –
model, per MultibodyForces::CheckInvariants() –
- Parameter
- CalcGeneralizedForces(self: pydrake.multibody.plant.MultibodyPlant, context: pydrake.systems.framework.Context, forces: pydrake.multibody.tree.MultibodyForces) numpy.ndarray[numpy.float64[m, 1]]
Computes the generalized forces result of a set of MultibodyForces applied to this model.
MultibodyForces stores applied forces as both generalized forces τ and spatial forces F on each body, refer to documentation in MultibodyForces for details. Users of MultibodyForces will use MultibodyForces::mutable_generalized_forces() to mutate the stored generalized forces directly and will use RigidBody::AddInForceInWorld() to append spatial forces.
For a given set of forces stored as MultibodyForces, this method will compute the total generalized forces on this model. More precisely, if J_WBo is the Jacobian (with respect to velocities) for this model, including all bodies, then this method computes:
Click to expand C++ code...
τᵣₑₛᵤₗₜ = τ + J_WBo⋅F
- Parameter
context
: Context that stores the state of the model.
- Parameter
forces
: Set of multibody forces, including both generalized forces and per-body spatial forces.
- Parameter
generalized_forces
: The total generalized forces on the model that would result from applying
forces
. In other words,forces
can be replaced by the equivalentgeneralized_forces
. On output,generalized_forces
is resized to num_velocities().
- Raises
RuntimeError if forces is null or not compatible with this –
model. –
RuntimeError if generalized_forces is not a valid non-null –
pointer. –
- Parameter
- CalcGravityGeneralizedForces(self: pydrake.multibody.plant.MultibodyPlant, context: pydrake.systems.framework.Context) numpy.ndarray[numpy.float64[m, 1]]
Computes the generalized forces
tau_g(q)
due to gravity as a function of the generalized positionsq
stored in the inputcontext
. The vector of generalized forces due to gravitytau_g(q)
is defined such that it appears on the right hand side of the equations of motion together with any other generalized forces, like so:Click to expand C++ code...
Mv̇ + C(q, v)v = tau_g(q) + tau_app
where
tau_app
includes any other generalized forces applied on the system.- Parameter
context
: The context storing the state of the model.
- Returns
tau_g A vector containing the generalized forces due to gravity. The generalized forces are consistent with the vector of generalized velocities
v
forthis
so that the inner productv⋅tau_g
corresponds to the power applied by the gravity forces on the mechanical system. That is,v⋅tau_g > 0
corresponds to potential energy going into the system, as either mechanical kinetic energy, some other potential energy, or heat, and therefore to a decrease of the gravitational potential energy.
- Parameter
- CalcInverseDynamics(self: pydrake.multibody.plant.MultibodyPlant, context: pydrake.systems.framework.Context, known_vdot: numpy.ndarray[numpy.float64[m, 1]], external_forces: pydrake.multibody.tree.MultibodyForces) numpy.ndarray[numpy.float64[m, 1]]
Given the state of this model in
context
and a known vector of generalized accelerationsvdot
, this method computes the set of generalized forcestau
that would need to be applied in order to attain the specified generalized accelerations. Mathematically, this method computes:Click to expand C++ code...
tau = M(q)v̇ + C(q, v)v - tau_app - ∑ J_WBᵀ(q) Fapp_Bo_W
where
M(q)
is the model’s mass matrix (including rigid body mass properties and reflected_inertia “reflected inertias”),C(q, v)v
is the bias term for Coriolis and gyroscopic effects andtau_app
consists of a vector applied generalized forces. The last term is a summation over all bodies in the model whereFapp_Bo_W
is an applied spatial force on body B atBo
which gets projected into the space of generalized forces with the transpose ofJv_V_WB(q)
(whereJv_V_WB
is B’s spatial velocity Jacobian in W with respect to generalized velocities v). Note: B’s spatial velocity in W can be written asV_WB = Jv_V_WB * v
.This method does not compute explicit expressions for the mass matrix nor for the bias term, which would be of at least
O(n²)
complexity, but it implements anO(n)
Newton-Euler recursive algorithm, where n is the number of bodies in the model. The explicit formation of the mass matrixM(q)
would require the calculation ofO(n²)
entries while explicitly forming the productC(q, v) * v
could require up toO(n³)
operations (see [Featherstone 1987, §4]), depending on the implementation. The recursive Newton-Euler algorithm is the most efficient currently known general method for solving inverse dynamics [Featherstone 2008].- Parameter
context
: The context containing the state of the model.
- Parameter
known_vdot
: A vector with the known generalized accelerations
vdot
for the full model. Use the provided Joint APIs in order to access entries into this array.- Parameter
external_forces
: A set of forces to be applied to the system either as body spatial forces
Fapp_Bo_W
or generalized forcestau_app
, see MultibodyForces for details.
- Returns
the vector of generalized forces that would need to be applied to the mechanical system in order to achieve the desired acceleration given by
known_vdot
.
- Parameter
- CalcJacobianAngularVelocity(self: pydrake.multibody.plant.MultibodyPlant, context: pydrake.systems.framework.Context, with_respect_to: pydrake.multibody.tree.JacobianWrtVariable, frame_B: pydrake.multibody.tree.Frame, frame_A: pydrake.multibody.tree.Frame, frame_E: pydrake.multibody.tree.Frame) numpy.ndarray[numpy.float64[3, n]]
Calculates J𝑠_w_AB, a frame B’s angular velocity Jacobian in a frame A with respect to “speeds” 𝑠.
Click to expand C++ code...
J𝑠_w_AB ≜ [ ∂(w_AB)/∂𝑠₁, ... ∂(w_AB)/∂𝑠ₙ ] (n is j or k) w_AB = J𝑠_w_AB ⋅ 𝑠 w_AB is linear in 𝑠 ≜ [𝑠₁ ... 𝑠ₙ]ᵀ
w_AB
is B’s angular velocity in frame A and “speeds” 𝑠 is either q̇ ≜ [q̇₁ … q̇ⱼ]ᵀ (time-derivatives of j generalized positions) or v ≜ [v₁ … vₖ]ᵀ (k generalized velocities).- Parameter
context
: The state of the multibody system.
- Parameter
with_respect_to
: Enum equal to JacobianWrtVariable::kQDot or JacobianWrtVariable::kV, indicating whether the Jacobian
J𝑠_w_AB
is partial derivatives with respect to 𝑠 = q̇ (time-derivatives of generalized positions) or with respect to 𝑠 = v (generalized velocities).- Parameter
frame_B
: The frame B in
w_AB
(B’s angular velocity in A).- Parameter
frame_A
: The frame A in
w_AB
(B’s angular velocity in A).- Parameter
frame_E
: The frame in which
w_AB
is expressed on input and the frame in which the JacobianJ𝑠_w_AB
is expressed on output.- Parameter
J𝑠_w_AB_E
: Frame B’s angular velocity Jacobian in frame A with respect to speeds 𝑠 (which is either q̇ or v), expressed in frame E. The Jacobian is a function of only generalized positions q (which are pulled from the context). The previous definition shows
J𝑠_w_AB_E
is a matrix of size3 x n
, where n is the number of elements in 𝑠.
See also
See Jacobian_functions “Jacobian functions” for related functions.
- Raises
RuntimeError if J𝑠_w_AB_E is nullptr or not of size 3 x n. –
- Parameter
- CalcJacobianCenterOfMassTranslationalVelocity(*args, **kwargs)
Overloaded function.
CalcJacobianCenterOfMassTranslationalVelocity(self: pydrake.multibody.plant.MultibodyPlant, context: pydrake.systems.framework.Context, with_respect_to: pydrake.multibody.tree.JacobianWrtVariable, frame_A: pydrake.multibody.tree.Frame, frame_E: pydrake.multibody.tree.Frame) -> numpy.ndarray[numpy.float64[3, n]]
Calculates J𝑠_v_ACcm_E, point Ccm’s translational velocity Jacobian in frame A with respect to “speeds” 𝑠, expressed in frame E, where point CCm is the center of mass of the system of all non-world bodies contained in
this
MultibodyPlant.- Parameter
context
: contains the state of the model.
- Parameter
with_respect_to
: Enum equal to JacobianWrtVariable::kQDot or JacobianWrtVariable::kV, indicating whether the Jacobian
J𝑠_v_ACcm_E
is partial derivatives with respect to 𝑠 = q̇ (time-derivatives of generalized positions) or with respect to 𝑠 = v (generalized velocities).- Parameter
frame_A
: The frame in which the translational velocity v_ACcm and its Jacobian J𝑠_v_ACcm are measured.
- Parameter
frame_E
: The frame in which the Jacobian J𝑠_v_ACcm is expressed on output.
- Parameter
J𝑠_v_ACcm_E
: Point Ccm’s translational velocity Jacobian in frame A with respect to speeds 𝑠 (𝑠 = q̇ or 𝑠 = v), expressed in frame E. J𝑠_v_ACcm_E is a 3 x n matrix, where n is the number of elements in 𝑠. The Jacobian is a function of only generalized positions q (which are pulled from the context).
- Raises
RuntimeError if CCm does not exist, which occurs if there are no –
massive bodies in MultibodyPlant (except world_body()) –
RuntimeError if mₛ ≤ 0 (where mₛ is the mass of all non-world –
bodies contained in this MultibodyPlant) –
See also
See Jacobian_functions “Jacobian functions” for related functions.
CalcJacobianCenterOfMassTranslationalVelocity(self: pydrake.multibody.plant.MultibodyPlant, context: pydrake.systems.framework.Context, model_instances: list[pydrake.multibody.tree.ModelInstanceIndex], with_respect_to: pydrake.multibody.tree.JacobianWrtVariable, frame_A: pydrake.multibody.tree.Frame, frame_E: pydrake.multibody.tree.Frame) -> numpy.ndarray[numpy.float64[3, n]]
Calculates J𝑠_v_ACcm_E, point Ccm’s translational velocity Jacobian in frame A with respect to “speeds” 𝑠, expressed in frame E, where point CCm is the center of mass of the system of all non-world bodies contained in model_instances.
- Parameter
context
: contains the state of the model.
- Parameter
model_instances
: Vector of selected model instances. If a model instance is repeated in the vector (unusual), it is only counted once.
- Parameter
with_respect_to
: Enum equal to JacobianWrtVariable::kQDot or JacobianWrtVariable::kV, indicating whether the Jacobian
J𝑠_v_ACcm_E
is partial derivatives with respect to 𝑠 = q̇ (time-derivatives of generalized positions) or with respect to 𝑠 = v (generalized velocities).- Parameter
frame_A
: The frame in which the translational velocity v_ACcm and its Jacobian J𝑠_v_ACcm are measured.
- Parameter
frame_E
: The frame in which the Jacobian J𝑠_v_ACcm is expressed on output.
- Parameter
J𝑠_v_ACcm_E
: Point Ccm’s translational velocity Jacobian in frame A with respect to speeds 𝑠 (𝑠 = q̇ or 𝑠 = v), expressed in frame E. J𝑠_v_ACcm_E is a 3 x n matrix, where n is the number of elements in 𝑠. The Jacobian is a function of only generalized positions q (which are pulled from the context).
- Raises
RuntimeError if mₛ ≤ 0 (where mₛ is the mass of all non-world –
bodies contained in model_instances) –
RuntimeError if model_instances is empty or only has world body. –
Note
The world_body() is ignored. J𝑠_v_ACcm_ = ∑ (mᵢ Jᵢ) / mₛ, where mₛ = ∑ mᵢ, mᵢ is the mass of the iᵗʰ body contained in model_instances, and Jᵢ is Bᵢcm’s translational velocity Jacobian in frame A, expressed in frame E (Bᵢcm is the center of mass of the iᵗʰ body).
See also
See Jacobian_functions “Jacobian functions” for related functions.
- CalcJacobianPositionVector(self: pydrake.multibody.plant.MultibodyPlant, context: pydrake.systems.framework.Context, frame_B: pydrake.multibody.tree.Frame, p_BoBi_B: numpy.ndarray[numpy.float64[3, n], flags.f_contiguous], frame_A: pydrake.multibody.tree.Frame, frame_E: pydrake.multibody.tree.Frame) numpy.ndarray[numpy.float64[m, n]]
For each point Bi affixed/welded to a frame B, calculates Jq_p_AoBi, Bi’s position vector Jacobian in frame A with respect to the generalized positions q ≜ [q₁ … qₙ]ᵀ as
Click to expand C++ code...
Jq_p_AoBi ≜ [ ᴬ∂(p_AoBi)/∂q₁, ... ᴬ∂(p_AoBi)/∂qₙ ]
where p_AoBi is Bi’s position vector from point Ao (frame A’s origin) and ᴬ∂(p_AoBi)/∂qᵣ denotes the partial derivative in frame A of p_AoBi with respect to the generalized position qᵣ, where qᵣ is one of q₁ … qₙ.
- Parameter
context
: The state of the multibody system.
- Parameter
frame_B
: The frame on which point Bi is affixed/welded.
- Parameter
p_BoBi_B
: A position vector or list of k position vectors from Bo (frame_B’s origin) to points Bi (Bi is regarded as affixed to B), where each position vector is expressed in frame_B.
- Parameter
frame_A
: The frame in which partial derivatives are calculated and the frame in which point Ao is affixed.
- Parameter
frame_E
: The frame in which the Jacobian Jq_p_AoBi is expressed on output.
- Parameter
Jq_p_AoBi_E
: Point Bi’s position vector Jacobian in frame A with generalized positions q, expressed in frame E. Jq_p_AoBi_E is a
3*k x n
matrix, where k is the number of points Bi and n is the number of elements in q. The Jacobian is a function of only generalized positions q (which are pulled from the context).
- Raises
RuntimeError if Jq_p_AoBi_E is nullptr or not sized 3*k x n. –
Note
Jq̇_v_ABi = Jq_p_AoBi. In other words, point Bi’s velocity Jacobian in frame A with respect to q̇ is equal to point Bi’s position vector Jacobian in frame A with respect to q.
Click to expand C++ code...
[∂(v_ABi)/∂q̇₁, ... ∂(v_ABi)/∂q̇ₙ] = [ᴬ∂(p_AoBi)/∂q₁, ... ᴬ∂(p_AoBi)/∂qₙ]
See also
CalcJacobianTranslationalVelocity() for details on Jq̇_v_ABi. Note: Jq_p_AaBi = Jq_p_AoBi, where point Aa is any point fixed/welded to frame A, i.e., this calculation’s result is the same if point Ao is replaced with any point fixed on frame A.
See also
See Jacobian_functions “Jacobian functions” for related functions.
- Parameter
- CalcJacobianSpatialVelocity(self: pydrake.multibody.plant.MultibodyPlant, context: pydrake.systems.framework.Context, with_respect_to: pydrake.multibody.tree.JacobianWrtVariable, frame_B: pydrake.multibody.tree.Frame, p_BoBp_B: numpy.ndarray[numpy.float64[3, 1]], frame_A: pydrake.multibody.tree.Frame, frame_E: pydrake.multibody.tree.Frame) numpy.ndarray[numpy.float64[m, n]]
For one point Bp fixed/welded to a frame B, calculates J𝑠_V_ABp, Bp’s spatial velocity Jacobian in frame A with respect to “speeds” 𝑠.
Click to expand C++ code...
J𝑠_V_ABp ≜ [ ∂(V_ABp)/∂𝑠₁, ... ∂(V_ABp)/∂𝑠ₙ ] (n is j or k) V_ABp = J𝑠_V_ABp ⋅ 𝑠 V_ABp is linear in 𝑠 ≜ [𝑠₁ ... 𝑠ₙ]ᵀ
V_ABp
is Bp’s spatial velocity in frame A and “speeds” 𝑠 is either q̇ ≜ [q̇₁ … q̇ⱼ]ᵀ (time-derivatives of j generalized positions) or v ≜ [v₁ … vₖ]ᵀ (k generalized velocities).- Parameter
context
: The state of the multibody system.
- Parameter
with_respect_to
: Enum equal to JacobianWrtVariable::kQDot or JacobianWrtVariable::kV, indicating whether the Jacobian
J𝑠_V_ABp
is partial derivatives with respect to 𝑠 = q̇ (time-derivatives of generalized positions) or with respect to 𝑠 = v (generalized velocities).- Parameter
frame_B
: The frame on which point Bp is fixed/welded.
- Parameter
p_BoBp_B
: A position vector from Bo (frame_B’s origin) to point Bp (regarded as fixed/welded to B), expressed in frame_B.
- Parameter
frame_A
: The frame that measures
v_ABp
(Bp’s velocity in A). Note: It is natural to wonder why there is no parameter p_AoAp_A (similar to the parameter p_BoBp_B for frame_B). There is no need for p_AoAp_A because Bp’s velocity in A is defined as the derivative in frame A of Bp’s position vector from any point fixed to A.- Parameter
frame_E
: The frame in which
v_ABp
is expressed on input and the frame in which the JacobianJ𝑠_V_ABp
is expressed on output.- Parameter
J𝑠_V_ABp_E
: Point Bp’s spatial velocity Jacobian in frame A with respect to speeds 𝑠 (which is either q̇ or v), expressed in frame E.
J𝑠_V_ABp_E
is a6 x n
matrix, where n is the number of elements in 𝑠. The Jacobian is a function of only generalized positions q (which are pulled from the context).
Note
The returned
6 x n
matrix stores frame B’s angular velocity Jacobian in A in rows 1-3 and stores point Bp’s translational velocity Jacobian in A in rows 4-6, i.e.,Click to expand C++ code...
J𝑠_w_AB_E = J𝑠_V_ABp_E.topRows<3>(); J𝑠_v_ABp_E = J𝑠_V_ABp_E.bottomRows<3>();
Note
Consider CalcJacobianTranslationalVelocity() for multiple points fixed to frame B and consider CalcJacobianAngularVelocity() to calculate frame B’s angular velocity Jacobian.
See also
See Jacobian_functions “Jacobian functions” for related functions.
- Raises
RuntimeError if J𝑠_V_ABp_E is nullptr or not sized 6 x n. –
- Parameter
- CalcJacobianTranslationalVelocity(self: pydrake.multibody.plant.MultibodyPlant, context: pydrake.systems.framework.Context, with_respect_to: pydrake.multibody.tree.JacobianWrtVariable, frame_B: pydrake.multibody.tree.Frame, p_BoBi_B: numpy.ndarray[numpy.float64[3, n], flags.f_contiguous], frame_A: pydrake.multibody.tree.Frame, frame_E: pydrake.multibody.tree.Frame) numpy.ndarray[numpy.float64[m, n]]
For each point Bi affixed/welded to a frame B, calculates J𝑠_v_ABi, Bi’s translational velocity Jacobian in frame A with respect to “speeds” 𝑠.
Click to expand C++ code...
J𝑠_v_ABi ≜ [ ∂(v_ABi)/∂𝑠₁, ... ∂(v_ABi)/∂𝑠ₙ ] (n is j or k) v_ABi = J𝑠_v_ABi ⋅ 𝑠 v_ABi is linear in 𝑠 ≜ [𝑠₁ ... 𝑠ₙ]ᵀ
v_ABi
is Bi’s translational velocity in frame A and “speeds” 𝑠 is either q̇ ≜ [q̇₁ … q̇ⱼ]ᵀ (time-derivatives of j generalized positions) or v ≜ [v₁ … vₖ]ᵀ (k generalized velocities).- Parameter
context
: The state of the multibody system.
- Parameter
with_respect_to
: Enum equal to JacobianWrtVariable::kQDot or JacobianWrtVariable::kV, indicating whether the Jacobian
J𝑠_v_ABi
is partial derivatives with respect to 𝑠 = q̇ (time-derivatives of generalized positions) or with respect to 𝑠 = v (generalized velocities).- Parameter
frame_B
: The frame on which point Bi is affixed/welded.
- Parameter
p_BoBi_B
: A position vector or list of p position vectors from Bo (frame_B’s origin) to points Bi (regarded as affixed to B), where each position vector is expressed in frame_B.
- Parameter
frame_A
: The frame that measures
v_ABi
(Bi’s velocity in A). Note: It is natural to wonder why there is no parameter p_AoAi_A (similar to the parameter p_BoBi_B for frame_B). There is no need for p_AoAi_A because Bi’s velocity in A is defined as the derivative in frame A of Bi’s position vector from any point affixed to A.- Parameter
frame_E
: The frame in which
v_ABi
is expressed on input and the frame in which the JacobianJ𝑠_v_ABi
is expressed on output.- Parameter
J𝑠_v_ABi_E
: Point Bi’s velocity Jacobian in frame A with respect to speeds 𝑠 (which is either q̇ or v), expressed in frame E.
J𝑠_v_ABi_E
is a3*p x n
matrix, where p is the number of points Bi and n is the number of elements in 𝑠. The Jacobian is a function of only generalized positions q (which are pulled from the context).
- Raises
RuntimeError if J𝑠_v_ABi_E is nullptr or not sized ``3*p x –
n``. –
Note
When 𝑠 = q̇,
Jq̇_v_ABi = Jq_p_AoBi
. In other words, point Bi’s velocity Jacobian in frame A with respect to q̇ is equal to point Bi’s position Jacobian from Ao (A’s origin) in frame A with respect to q.Click to expand C++ code...
[∂(v_ABi)/∂q̇₁, ... ∂(v_ABi)/∂q̇ⱼ] = [∂(p_AoBi)/∂q₁, ... ∂(p_AoBi)/∂qⱼ]
Note: Each partial derivative of p_AoBi is taken in frame A.
See also
CalcJacobianPositionVector() for details on Jq_p_AoBi.
See also
See Jacobian_functions “Jacobian functions” for related functions.
- Parameter
- CalcMassMatrix(self: pydrake.multibody.plant.MultibodyPlant, context: pydrake.systems.framework.Context) numpy.ndarray[numpy.float64[m, n]]
Efficiently computes the mass matrix
M(q)
of the model. The generalized positions q are taken from the givencontext
. M includes the mass properties of rigid bodies and reflected_inertia “reflected inertias” as provided with JointActuator specifications.This method employs the Composite Body Algorithm, which we believe to be the fastest O(n²) algorithm to compute the mass matrix of a multibody system.
- Parameter
context
: The Context containing the state of the model from which generalized coordinates q are extracted.
- Parameter
M
: A pointer to a square matrix in
ℛⁿˣⁿ
with n the number of generalized velocities (num_velocities()) of the model. Although symmetric, the matrix is filled in completely on return.- Precondition:
M is non-null and has the right size.
Warning
This is an O(n²) algorithm. Avoid the explicit computation of the mass matrix whenever possible.
See also
CalcMassMatrixViaInverseDynamics() (slower)
- Parameter
- CalcMassMatrixViaInverseDynamics(self: pydrake.multibody.plant.MultibodyPlant, context: pydrake.systems.framework.Context) numpy.ndarray[numpy.float64[m, n]]
Computes the mass matrix
M(q)
of the model using a slow method (inverse dynamics). The generalized positions q are taken from the givencontext
. M includes the mass properties of rigid bodies and reflected_inertia “reflected inertias” as provided with JointActuator specifications.Use CalcMassMatrix() for a faster implementation using the Composite Body Algorithm.
- Parameter
context
: The Context containing the state of the model from which generalized coordinates q are extracted.
- Parameter
M
: A pointer to a square matrix in
ℛⁿˣⁿ
with n the number of generalized velocities (num_velocities()) of the model. Although symmetric, the matrix is filled in completely on return.- Precondition:
M is non-null and has the right size.
The algorithm used to build
M(q)
consists in computing one column ofM(q)
at a time using inverse dynamics. The result from inverse dynamics, with no applied forces, is the vector of generalized forces:Click to expand C++ code...
tau = M(q)v̇ + C(q, v)v
where q and v are the generalized positions and velocities, respectively. When
v = 0
the Coriolis and gyroscopic forces termC(q, v)v
is zero. Therefore thei-th
column ofM(q)
can be obtained performing inverse dynamics with an acceleration vectorv̇ = eᵢ
, witheᵢ
the standard (or natural) basis ofℛⁿ
with n the number of generalized velocities. We write this as:Click to expand C++ code...
M.ᵢ(q) = M(q) * e_i
where
M.ᵢ(q)
(notice the dot for the rows index) denotes thei-th
column in M(q).Warning
This is an O(n²) algorithm. Avoid the explicit computation of the mass matrix whenever possible.
See also
CalcMassMatrix(), CalcInverseDynamics()
- Parameter
- CalcPointsPositions(self: pydrake.multibody.plant.MultibodyPlant, context: pydrake.systems.framework.Context, frame_B: pydrake.multibody.tree.Frame, p_BQi: numpy.ndarray[numpy.float64[m, n], flags.f_contiguous], frame_A: pydrake.multibody.tree.Frame) numpy.ndarray[numpy.float64[m, n]]
Given the positions
p_BQi
for a set of pointsQi
measured and expressed in a frame B, this method computes the positionsp_AQi(q)
of each pointQi
in the set as measured and expressed in another frame A, as a function of the generalized positions q of the model.- Parameter
context
: The context containing the state of the model. It stores the generalized positions q of the model.
- Parameter
frame_B
: The frame B in which the positions
p_BQi
of a set of pointsQi
are given.- Parameter
p_BQi
: The input positions of each point
Qi
in frame B.p_BQi ∈ ℝ³ˣⁿᵖ
withnp
the number of points in the set. Each column ofp_BQi
corresponds to a vector in ℝ³ holding the position of one of the points in the set as measured and expressed in frame B.- Parameter
frame_A
: The frame A in which it is desired to compute the positions
p_AQi
of each pointQi
in the set.- Parameter
p_AQi
: The output positions of each point
Qi
now computed as measured and expressed in frame A. The outputp_AQi
must have the same size as the inputp_BQi
or otherwise this method aborts. That isp_AQi
must be inℝ³ˣⁿᵖ
.
Note
Both
p_BQi
andp_AQi
must have three rows. Otherwise this method will throw a RuntimeError. This method also throws a RuntimeError ifp_BQi
andp_AQi
differ in the number of columns.- Parameter
- CalcRelativeRotationMatrix(self: pydrake.multibody.plant.MultibodyPlant, context: pydrake.systems.framework.Context, frame_A: pydrake.multibody.tree.Frame, frame_B: pydrake.multibody.tree.Frame) pydrake.math.RotationMatrix
Calculates the rotation matrix
R_AB
relating frame A and frame B.- Parameter
context
: The state of the multibody system, which includes the system’s generalized positions q. Note:
R_AB
is a function of q.- Parameter
frame_A
: The frame A designated in the rigid transform
R_AB
.- Parameter
frame_B
: The frame G designated in the rigid transform
R_AB
.- Returns
R_AB
: The RigidTransform relating frame A and frame B.
- Parameter
- CalcRelativeTransform(self: pydrake.multibody.plant.MultibodyPlant, context: pydrake.systems.framework.Context, frame_A: pydrake.multibody.tree.Frame, frame_B: pydrake.multibody.tree.Frame) pydrake.math.RigidTransform
Calculates the rigid transform (pose)
X_AB
relating frame A and frame B.- Parameter
context
: The state of the multibody system, which includes the system’s generalized positions q. Note:
X_AB
is a function of q.- Parameter
frame_A
: The frame A designated in the rigid transform
X_AB
.- Parameter
frame_B
: The frame G designated in the rigid transform
X_AB
.- Returns
X_AB
: The RigidTransform relating frame A and frame B.
- Parameter
- CalcSpatialAccelerationsFromVdot(self: pydrake.multibody.plant.MultibodyPlant, context: pydrake.systems.framework.Context, known_vdot: numpy.ndarray[numpy.float64[m, 1]]) list[pydrake.multibody.math.SpatialAcceleration]
Given the state of this model in
context
and a known vector of generalized accelerationsknown_vdot
, this method computes the spatial accelerationA_WB
for each body as measured and expressed in the world frame W.- Parameter
context
: The context containing the state of this model.
- Parameter
known_vdot
: A vector with the generalized accelerations for the full model.
- Parameter
A_WB_array
: A pointer to a valid, non nullptr, vector of spatial accelerations containing the spatial acceleration
A_WB
for each body. It must be of size equal to the number of bodies in the model. On output, entries will be ordered by BodyIndex.
- Raises
RuntimeError if A_WB_array is not of size num_bodies() –
- Parameter
- CalcSpatialInertia(self: pydrake.multibody.plant.MultibodyPlant, context: pydrake.systems.framework.Context, frame_F: pydrake.multibody.tree.Frame, body_indexes: list[pydrake.multibody.tree.BodyIndex]) pydrake.multibody.tree.SpatialInertia
Returns M_SFo_F, the spatial inertia of a set S of bodies about point Fo (the origin of a frame F), expressed in frame F. You may regard M_SFo_F as measuring spatial inertia as if the set S of bodies were welded into a single composite body at the configuration specified in the
context
.- Parameter
context
: Contains the configuration of the set S of bodies.
- Parameter
frame_F
: specifies the about-point Fo (frame_F’s origin) and the expressed-in frame for the returned spatial inertia.
- Parameter
body_indexes
: Array of selected bodies. This method does not distinguish between welded bodies, joint-connected bodies, etc.
- Raises
RuntimeError if body_indexes contains an invalid BodyIndex or if –
there is a repeated BodyIndex. –
Note
The mass and inertia of the world_body() does not contribute to the the returned spatial inertia.
- Parameter
- CalcSpatialMomentumInWorldAboutPoint(*args, **kwargs)
Overloaded function.
CalcSpatialMomentumInWorldAboutPoint(self: pydrake.multibody.plant.MultibodyPlant, context: pydrake.systems.framework.Context, p_WoP_W: numpy.ndarray[numpy.float64[3, 1]]) -> pydrake.multibody.math.SpatialMomentum
This method returns the spatial momentum of
this
MultibodyPlant in the world frame W, about a designated point P, expressed in the world frame W.- Parameter
context
: Contains the state of the model.
- Parameter
p_WoP_W
: Position from Wo (origin of the world frame W) to an arbitrary point P, expressed in the world frame W.
- Returns
L_WSP_W
: , spatial momentum of the system S represented by
this
plant, measured in the world frame W, about point P, expressed in W.
Note
To calculate the spatial momentum of this system S in W about Scm (the system’s center of mass), use something like:
Click to expand C++ code...
MultibodyPlant<T> plant; // ... code to load a model .... const Vector3<T> p_WoScm_W = plant.CalcCenterOfMassPositionInWorld(context); const SpatialMomentum<T> L_WScm_W = plant.CalcSpatialMomentumInWorldAboutPoint(context, p_WoScm_W);
CalcSpatialMomentumInWorldAboutPoint(self: pydrake.multibody.plant.MultibodyPlant, context: pydrake.systems.framework.Context, model_instances: list[pydrake.multibody.tree.ModelInstanceIndex], p_WoP_W: numpy.ndarray[numpy.float64[3, 1]]) -> pydrake.multibody.math.SpatialMomentum
This method returns the spatial momentum of a set of model instances in the world frame W, about a designated point P, expressed in frame W.
- Parameter
context
: Contains the state of the model.
- Parameter
model_instances
: Set of selected model instances.
- Parameter
p_WoP_W
: Position from Wo (origin of the world frame W) to an arbitrary point P, expressed in the world frame W.
- Returns
L_WSP_W
: , spatial momentum of the system S represented by the model_instances, measured in world frame W, about point P, expressed in W.
Note
To calculate the spatial momentum of this system S in W about Scm (the system’s center of mass), use something like:
Click to expand C++ code...
MultibodyPlant<T> plant; // ... code to create a set of selected model instances, e.g., ... const ModelInstanceIndex gripper_model_instance = plant.GetModelInstanceByName("gripper"); const ModelInstanceIndex robot_model_instance = plant.GetBodyByName("end_effector").model_instance(); const std::vector<ModelInstanceIndex> model_instances{ gripper_model_instance, robot_model_instance}; const Vector3<T> p_WoScm_W = plant.CalcCenterOfMassPositionInWorld(context, model_instances); SpatialMomentum<T> L_WScm_W = plant.CalcSpatialMomentumInWorldAboutPoint(context, model_instances, p_WoScm_W);
- Raises
RuntimeError if model_instances contains an invalid –
ModelInstanceIndex. –
- CalcTotalMass(*args, **kwargs)
Overloaded function.
CalcTotalMass(self: pydrake.multibody.plant.MultibodyPlant, context: pydrake.systems.framework.Context) -> float
Calculates the total mass of all bodies in this MultibodyPlant.
- Parameter
context
: Contains the state of the model.
- Returns
The
: total mass of all bodies or 0 if there are none.
Note
The mass of the world_body() does not contribute to the total mass.
CalcTotalMass(self: pydrake.multibody.plant.MultibodyPlant, context: pydrake.systems.framework.Context, model_instances: list[pydrake.multibody.tree.ModelInstanceIndex]) -> float
Calculates the total mass of all bodies contained in model_instances.
- Parameter
context
: Contains the state of the model.
- Parameter
model_instances
: Vector of selected model instances. This method does not distinguish between welded, joint connected, or floating bodies.
- Returns
The
: total mass of all bodies belonging to a model instance in model_instances or 0 if model_instances is empty.
Note
The mass of the world_body() does not contribute to the total mass and each body only contributes to the total mass once, even if the body has repeated occurrence (instance) in model_instances.
- CollectRegisteredGeometries(self: pydrake.multibody.plant.MultibodyPlant, bodies: list[pydrake.multibody.tree.RigidBody]) pydrake.geometry.GeometrySet
For each of the provided
bodies
, collects up all geometries that have been registered to that body. Intended to be used in conjunction with CollisionFilterDeclaration and CollisionFilterManager::Apply() to filter collisions between the geometries registered to the bodies.For example:
Click to expand C++ code...
// Don't report on collisions between geometries affixed to `body1`, // `body2`, or `body3`. std::vector<const RigidBody<T>*> bodies{&body1, &body2, &body3}; geometry::GeometrySet set = plant.CollectRegisteredGeometries(bodies); scene_graph.collision_filter_manager().Apply( CollisionFilterDeclaration().ExcludeWithin(set));
Note
There is a very specific order of operations:
Bodies and geometries must be added to the MultibodyPlant.
Create GeometrySet instances from bodies (via this method).
Invoke SceneGraph::ExcludeCollisions*() to filter collisions.
Allocate context.
Changing the order will cause exceptions to be thrown.
- Raises
RuntimeError if this MultibodyPlant was not registered with a –
SceneGraph. –
- deformable_model(self: pydrake.multibody.plant.MultibodyPlant) pydrake.multibody.plant.DeformableModel
Returns the DeformableModel owned by this plant.
- Raises
RuntimeError if this plant doesn't own a DeformableModel. –
Warning
This feature is considered to be experimental and may change or be removed at any time, without any deprecation notice ahead of time.
- EvalBodyPoseInWorld(self: pydrake.multibody.plant.MultibodyPlant, context: pydrake.systems.framework.Context, body: pydrake.multibody.tree.RigidBody) pydrake.math.RigidTransform
Evaluate the pose
X_WB
of a body B in the world frame W.- Parameter
context
: The context storing the state of the model.
- Parameter
body_B
: The body B for which the pose is requested.
- Returns
X_WB
: The pose of body frame B in the world frame W.
- Raises
RuntimeError if Finalize() was not called on this model or if –
body_B` does not belong to this model –
- Parameter
- EvalBodySpatialAccelerationInWorld(self: pydrake.multibody.plant.MultibodyPlant, context: pydrake.systems.framework.Context, body: pydrake.multibody.tree.RigidBody) pydrake.multibody.math.SpatialAcceleration
Evaluates A_WB, body B’s spatial acceleration in the world frame W.
- Parameter
context
: The context storing the state of the model.
- Parameter
body_B
: The body for which spatial acceleration is requested.
- Returns
A_WB_W
: RigidBody B’s spatial acceleration in the world frame W, expressed in W (for point Bo, the body’s origin).
- Raises
RuntimeError if Finalize() was not called on this model or if –
body_B` does not belong to this model –
Note
When cached values are out of sync with the state stored in context, this method performs an expensive forward dynamics computation, whereas once evaluated, successive calls to this method are inexpensive.
- Parameter
- EvalBodySpatialVelocityInWorld(self: pydrake.multibody.plant.MultibodyPlant, context: pydrake.systems.framework.Context, body: pydrake.multibody.tree.RigidBody) pydrake.multibody.math.SpatialVelocity
Evaluates V_WB, body B’s spatial velocity in the world frame W.
- Parameter
context
: The context storing the state of the model.
- Parameter
body_B
: The body B for which the spatial velocity is requested.
- Returns
V_WB_W
: RigidBody B’s spatial velocity in the world frame W, expressed in W (for point Bo, the body’s origin).
- Raises
RuntimeError if Finalize() was not called on this model or if –
body_B` does not belong to this model –
- Parameter
- EvalSceneGraphInspector(self: pydrake.multibody.plant.MultibodyPlant, context: pydrake.systems.framework.Context) pydrake.geometry.SceneGraphInspector
Returns the inspector from the
context
for the SceneGraph associated with this plant, via this plant’s “geometry_query” input port. (In the future, the inspector might come from a different context source that is more efficient than the “geometry_query” input port.)
- Finalize(self: pydrake.multibody.plant.MultibodyPlant) None
This method must be called after all elements in the model (joints, bodies, force elements, constraints, etc.) are added and before any computations are performed. It essentially compiles all the necessary “topological information”, i.e. how bodies, joints and, any other elements connect with each other, and performs all the required pre-processing to enable computations at a later stage.
If the finalize stage is successful, the topology of this MultibodyPlant is valid, meaning that the topology is up-to-date after this call. No more multibody elements can be added after a call to Finalize().
At Finalize(), state and input/output ports for
this
plant are declared.For a full account of the effects of Finalize(), see mbp_finalize_stage “Finalize() stage”.
See also
is_finalized(), mbp_finalize_stage “Finalize() stage”.
- Raises
RuntimeError if the MultibodyPlant has already been finalized. –
- geometry_source_is_registered(self: pydrake.multibody.plant.MultibodyPlant) bool
Returns
True
ifthis
MultibodyPlant was registered with a SceneGraph. This method can be called at any time during the lifetime ofthis
plant to query ifthis
plant has been registered with a SceneGraph, either pre- or post-finalize, see Finalize().
- get_actuation_input_port(*args, **kwargs)
Overloaded function.
get_actuation_input_port(self: pydrake.multibody.plant.MultibodyPlant) -> pydrake.systems.framework.InputPort
Returns a constant reference to the input port for external actuation for all actuated dofs. This input port is a vector valued port and can be set with JointActuator::set_actuation_vector(). The actuation value for a particular actuator can be found at offset JointActuator::input_start() in this vector. Refer to mbp_actuation “Actuation” for further details.
- Precondition:
Finalize() was already called on
this
plant.
- Raises
RuntimeError if called before Finalize() –
get_actuation_input_port(self: pydrake.multibody.plant.MultibodyPlant, model_instance: pydrake.multibody.tree.ModelInstanceIndex) -> pydrake.systems.framework.InputPort
Returns a constant reference to the input port for external actuation for a specific model instance. This is a vector valued port with entries ordered by monotonically increasing JointActuatorIndex within
model_instance
. Refer to mbp_actuation “Actuation” for further details.Every model instance in
this
plant model has an actuation input port, even if zero sized (for model instance with no actuators).See also
GetJointActuatorIndices(), GetActuatedJointIndices().
- Precondition:
Finalize() was already called on
this
plant.
- Raises
RuntimeError if called before Finalize() –
RuntimeError if the model instance does not exist. –
- get_adjacent_bodies_collision_filters(self: pydrake.multibody.plant.MultibodyPlant) bool
Returns whether to apply collision filters to topologically adjacent bodies at Finalize() time.
- get_applied_generalized_force_input_port(self: pydrake.multibody.plant.MultibodyPlant) pydrake.systems.framework.InputPort
Returns a constant reference to the vector-valued input port for applied generalized forces, and the vector will be added directly into
tau
(see mbp_equations_of_motion “System dynamics”). This vector is ordered using the same convention as the plant velocities: you can set the generalized forces that will be applied to model instance i using, e.g.,SetVelocitiesInArray(i, model_forces, &force_array)
.- Raises
RuntimeError if called before Finalize() –
- get_applied_spatial_force_input_port(self: pydrake.multibody.plant.MultibodyPlant) pydrake.systems.framework.InputPort
Returns a constant reference to the input port for applying spatial forces to bodies in the plant. The data type for the port is an std::vector of ExternallyAppliedSpatialForce; any number of spatial forces can be applied to any number of bodies in the plant.
- get_body(self: pydrake.multibody.plant.MultibodyPlant, body_index: pydrake.multibody.tree.BodyIndex) pydrake.multibody.tree.RigidBody
Returns a constant reference to the body with unique index
body_index
.- Raises
RuntimeError if body_index does not correspond to a body in –
this model. –
- get_body_poses_output_port(self: pydrake.multibody.plant.MultibodyPlant) pydrake.systems.framework.OutputPort
Returns the output port of all body poses in the world frame. You can obtain the pose
X_WB
of a body B in the world frame W with:Click to expand C++ code...
const auto& X_WB_all = plant.get_body_poses_output_port(). .Eval<std::vector<math::RigidTransform<double>>>(plant_context); const BodyIndex arm_body_index = plant.GetBodyByName("arm").index(); const math::RigidTransform<double>& X_WArm = X_WB_all[arm_body_index];
As shown in the example above, the resulting
std::vector
of body poses is indexed by BodyIndex, and it has size num_bodies(). BodyIndex “zero” (0) always corresponds to the world body, with pose equal to the identity at all times.- Raises
RuntimeError if called pre-finalize. –
- get_body_spatial_accelerations_output_port(self: pydrake.multibody.plant.MultibodyPlant) pydrake.systems.framework.OutputPort
Returns the output port of all body spatial accelerations in the world frame. You can obtain the spatial acceleration
A_WB
of a body B (for point Bo, the body’s origin) in the world frame W with:Click to expand C++ code...
const auto& A_WB_all = plant.get_body_spatial_accelerations_output_port(). .Eval<std::vector<SpatialAcceleration<double>>>(plant_context); const BodyIndex arm_body_index = plant.GetBodyByName("arm").index(); const SpatialVelocity<double>& A_WArm = A_WB_all[arm_body_index];
As shown in the example above, the resulting
std::vector
of body spatial accelerations is indexed by BodyIndex, and it has size num_bodies(). BodyIndex “zero” (0) always corresponds to the world body, with zero spatial acceleration at all times.In a discrete-time plant, the use_sampled_output_ports setting affects the output of this port. See output_port_sampling “Output port sampling” for details. When sampling is enabled and the plant has not yet taken a step, the output value will be all zeros.
- Raises
RuntimeError if called pre-finalize. –
- get_body_spatial_velocities_output_port(self: pydrake.multibody.plant.MultibodyPlant) pydrake.systems.framework.OutputPort
Returns the output port of all body spatial velocities in the world frame. You can obtain the spatial velocity
V_WB
of a body B in the world frame W with:Click to expand C++ code...
const auto& V_WB_all = plant.get_body_spatial_velocities_output_port(). .Eval<std::vector<SpatialVelocity<double>>>(plant_context); const BodyIndex arm_body_index = plant.GetBodyByName("arm").index(); const SpatialVelocity<double>& V_WArm = V_WB_all[arm_body_index];
As shown in the example above, the resulting
std::vector
of body spatial velocities is indexed by BodyIndex, and it has size num_bodies(). BodyIndex “zero” (0) always corresponds to the world body, with zero spatial velocity at all times.- Raises
RuntimeError if called pre-finalize. –
- get_contact_model(self: pydrake.multibody.plant.MultibodyPlant) pydrake.multibody.plant.ContactModel
Returns the model used for contact. See documentation for ContactModel.
- get_contact_penalty_method_time_scale(self: pydrake.multibody.plant.MultibodyPlant) float
Returns a time-scale estimate
tc
based on the requested penetration allowance δ set with set_penetration_allowance(). For the compliant contact model to enforce non-penetration, this time scale relates to the time it takes the relative normal velocity between two bodies to go to zero. This time scaletc
is a global estimate of the dynamics introduced by the compliant contact model and goes to zero in the limit to ideal rigid contact. Since numerical integration methods for continuum systems must be able to resolve a system’s dynamics, the time step used by an integrator must in general be much smaller than the time scaletc
. How much smaller will depend on the details of the problem and the convergence characteristics of the integrator and should be tuned appropriately. Another factor to take into account for setting up the simulation’s time step is the speed of the objects in your simulation. Ifvn
represents a reference velocity scale for the normal relative velocity between bodies, the new time scaletn = δ / vn
represents the time it would take for the distance between two bodies approaching with relative normal velocityvn
to decrease by the penetration_allowance δ. In this case a user should choose a time step for simulation that can resolve the smallest of the two time scalestc
andtn
.
- get_contact_results_output_port(self: pydrake.multibody.plant.MultibodyPlant) pydrake.systems.framework.OutputPort
Returns a constant reference to the port that outputs ContactResults.
In a discrete-time plant, the use_sampled_output_ports setting affects the output of this port. See output_port_sampling “Output port sampling” for details. When sampling is enabled and the plant has not yet taken a step, the output value will be empty (no contacts).
- Raises
RuntimeError if called pre-finalize, see Finalize() –
- get_contact_surface_representation(self: pydrake.multibody.plant.MultibodyPlant) pydrake.geometry.HydroelasticContactRepresentation
Gets the current representation of contact surfaces used by
this
MultibodyPlant.
- get_deformable_body_configuration_output_port(self: pydrake.multibody.plant.MultibodyPlant) pydrake.systems.framework.OutputPort
Returns the output port for vertex positions (configurations), measured and expressed in the World frame, of the deformable bodies in
this
plant as a GeometryConfigurationVector.
- get_desired_state_input_port(self: pydrake.multibody.plant.MultibodyPlant, model_instance: pydrake.multibody.tree.ModelInstanceIndex) pydrake.systems.framework.InputPort
For models with PD controlled joint actuators, returns the port to provide the desired state for the full
model_instance
. Refer to mbp_actuation “Actuation” for further details.For consistency with get_actuation_input_port(), each model instance in
this
plant model has a desired states input port, even if zero sized (for model instance with no actuators.)Note
This is a vector valued port of size 2*num_actuators(model_instance), where we assumed 1-DOF actuated joints. This is true even for unactuated models, for which this port is zero sized. This port must provide one desired position and one desired velocity per joint actuator. Desired state is assumed to be packed as xd = [qd, vd] that is, configurations first followed by velocities. The actuation value for a particular actuator can be found at offset JointActuator::input_start() in both qd and vd. For example:
Click to expand C++ code...
const double qd_actuator = xd[actuator.input_start()]; const double vd_actuator = xd[actuator.input_start() + plant.num_actuated_dofs()];
Warning
If a user specifies a PD controller for an actuator from a given model instance, then all actuators of that model instance are required to be PD controlled.
Warning
It is required to connect this port for PD controlled model instances.
- get_discrete_contact_approximation(self: pydrake.multibody.plant.MultibodyPlant) pydrake.multibody.plant.DiscreteContactApproximation
- Returns
the discrete contact solver approximation.
- get_discrete_contact_solver(self: pydrake.multibody.plant.MultibodyPlant) pydrake.multibody.plant.DiscreteContactSolver
Returns the contact solver type used for discrete MultibodyPlant models.
- get_force_element(self: pydrake.multibody.plant.MultibodyPlant, force_element_index: pydrake.multibody.tree.ForceElementIndex) pydrake.multibody.tree.ForceElement
Returns a constant reference to the force element with unique index
force_element_index
.- Raises
RuntimeError when force_element_index does not correspond to a –
force element in this model. –
- get_frame(self: pydrake.multibody.plant.MultibodyPlant, frame_index: pydrake.multibody.tree.FrameIndex) pydrake.multibody.tree.Frame
Returns a constant reference to the frame with unique index
frame_index
.- Raises
RuntimeError if frame_index does not correspond to a frame in –
this plant. –
- get_generalized_acceleration_output_port(*args, **kwargs)
Overloaded function.
get_generalized_acceleration_output_port(self: pydrake.multibody.plant.MultibodyPlant) -> pydrake.systems.framework.OutputPort
Returns a constant reference to the output port for generalized accelerations v̇ of the model.
In a discrete-time plant, the use_sampled_output_ports setting affects the output of this port. See output_port_sampling “Output port sampling” for details. When sampling is enabled and the plant has not yet taken a step, the output value will be all zeros.
- Precondition:
Finalize() was already called on
this
plant.
- Raises
RuntimeError if called before Finalize() –
get_generalized_acceleration_output_port(self: pydrake.multibody.plant.MultibodyPlant, model_instance: pydrake.multibody.tree.ModelInstanceIndex) -> pydrake.systems.framework.OutputPort
Returns a constant reference to the output port for the generalized accelerations v̇ᵢ ⊆ v̇ for model instance i.
In a discrete-time plant, the use_sampled_output_ports setting affects the output of this port. See output_port_sampling “Output port sampling” for details. When sampling is enabled and the plant has not yet taken a step, the output value will be all zeros.
- Precondition:
Finalize() was already called on
this
plant.
- Raises
RuntimeError if called before Finalize() –
RuntimeError if the model instance does not exist. –
- get_generalized_contact_forces_output_port(self: pydrake.multibody.plant.MultibodyPlant, model_instance: pydrake.multibody.tree.ModelInstanceIndex) pydrake.systems.framework.OutputPort
Returns a constant reference to the output port of generalized contact forces for a specific model instance.
In a discrete-time plant, the use_sampled_output_ports setting affects the output of this port. See output_port_sampling “Output port sampling” for details. When sampling is enabled and the plant has not yet taken a step, the output value will be all zeros.
- Precondition:
Finalize() was already called on
this
plant.
- Raises
RuntimeError if called before Finalize() –
RuntimeError if the model instance does not exist. –
- get_geometry_pose_output_port(self: pydrake.multibody.plant.MultibodyPlant) pydrake.systems.framework.OutputPort
Returns the output port of frames’ poses to communicate with a SceneGraph.
- get_geometry_query_input_port(self: pydrake.multibody.plant.MultibodyPlant) pydrake.systems.framework.InputPort
Returns a constant reference to the input port used to perform geometric queries on a SceneGraph. See SceneGraph::get_query_output_port(). Refer to section mbp_geometry “Geometry” of this class’s documentation for further details on collision geometry registration and connection with a SceneGraph.
- get_joint(self: pydrake.multibody.plant.MultibodyPlant, joint_index: pydrake.multibody.tree.JointIndex) pydrake.multibody.tree.Joint
Returns a constant reference to the joint with unique index
joint_index
.- Raises
RuntimeError when joint_index does not correspond to a joint –
in this model. –
- get_joint_actuator(self: pydrake.multibody.plant.MultibodyPlant, actuator_index: pydrake.multibody.tree.JointActuatorIndex) pydrake.multibody.tree.JointActuator
Returns a constant reference to the joint actuator with unique index
actuator_index
.- Raises
RuntimeError if actuator_index does not correspond to a joint –
actuator in this tree. –
- get_mutable_joint(self: pydrake.multibody.plant.MultibodyPlant, joint_index: pydrake.multibody.tree.JointIndex) pydrake.multibody.tree.Joint
Returns a mutable reference to the joint with unique index
joint_index
.- Raises
RuntimeError when joint_index does not correspond to a joint –
in this model. –
- get_mutable_joint_actuator(self: pydrake.multibody.plant.MultibodyPlant, actuator_index: pydrake.multibody.tree.JointActuatorIndex) pydrake.multibody.tree.JointActuator
Returns a mutable reference to the joint actuator with unique index
actuator_index
.- Raises
RuntimeError if actuator_index does not correspond to a joint –
actuator in this tree. –
- get_net_actuation_output_port(*args, **kwargs)
Overloaded function.
get_net_actuation_output_port(self: pydrake.multibody.plant.MultibodyPlant) -> pydrake.systems.framework.OutputPort
Returns a constant reference to the output port that reports actuation values applied through joint actuators. This output port is a vector valued port. The actuation value for a particular actuator can be found at offset JointActuator::input_start() in this vector. Models that include PD controllers will include their contribution in this port, refer to mbp_actuation “Actuation” for further details.
In a discrete-time plant, the use_sampled_output_ports setting affects the output of this port. See output_port_sampling “Output port sampling” for details. When sampling is enabled and the plant has not yet taken a step, the output value will be all zeros.
Note
PD controllers are not considered for actuators on locked joints, see Joint::Lock(). Therefore they do not contribute to this port.
- Precondition:
Finalize() was already called on
this
plant.
- Raises
RuntimeError if called before Finalize() –
get_net_actuation_output_port(self: pydrake.multibody.plant.MultibodyPlant, model_instance: pydrake.multibody.tree.ModelInstanceIndex) -> pydrake.systems.framework.OutputPort
Returns a constant reference to the output port that reports actuation values applied through joint actuators, for a specific model instance. Models that include PD controllers will include their contribution in this port, refer to mbp_actuation “Actuation” for further details. This is a vector valued port with entries ordered by monotonically increasing JointActuatorIndex within
model_instance
.Every model instance in
this
plant model has a net actuation output port, even if zero sized (for model instance with no actuators).In a discrete-time plant, the use_sampled_output_ports setting affects the output of this port. See output_port_sampling “Output port sampling” for details. When sampling is enabled and the plant has not yet taken a step, the output value will be all zeros.
Note
PD controllers are not considered for actuators on locked joints, see Joint::Lock(). Therefore they do not contribute to this port.
- Precondition:
Finalize() was already called on
this
plant.
- Raises
RuntimeError if called before Finalize() –
- get_reaction_forces_output_port(self: pydrake.multibody.plant.MultibodyPlant) pydrake.systems.framework.OutputPort
Returns the port for joint reaction forces. A Joint models the kinematical relationship which characterizes the possible relative motion between two bodies. In Drake, a joint connects a frame
Jp
on parent body P with a frameJc
on a child body C. This usage of the terms parent and child is just a convention and implies nothing about the inboard-outboard relationship between the bodies. Since a Joint imposes a kinematical relationship which characterizes the possible relative motion between frames Jp and Jc, reaction forces on each body are established. That is, we could cut the model at the joint and replace it with equivalent forces equal to these reaction forces in order to attain the same motions of the mechanical system.This output port allows to evaluate the reaction force
F_CJc_Jc
on the child body C, atJc
, and expressed in Jc for all joints in the model. This port evaluates to a vector of type std::vector<SpatialForce<T>> and size num_joints() indexed by JointIndex, see Joint::index(). Each entry corresponds to the spatial forceF_CJc_Jc
applied on the joint’s child body C (Joint::child_body()), at the joint’s child frameJc
(Joint::frame_on_child()) and expressed in frameJc
.In a discrete-time plant, the use_sampled_output_ports setting affects the output of this port. See output_port_sampling “Output port sampling” for details. When sampling is enabled and the plant has not yet taken a step, the output value will be all zeros.
- Raises
RuntimeError if called pre-finalize. –
- get_sap_near_rigid_threshold(self: pydrake.multibody.plant.MultibodyPlant) float
- Returns
the SAP near rigid regime threshold.
See also
See set_sap_near_rigid_threshold().
- get_source_id(self: pydrake.multibody.plant.MultibodyPlant) Optional[pydrake.geometry.SourceId]
Returns the unique id identifying
this
plant as a source for a SceneGraph. Returnsnullopt
ifthis
plant did not register any geometry. This method can be called at any time during the lifetime ofthis
plant to query ifthis
plant has been registered with a SceneGraph, either pre- or post-finalize, see Finalize(). However, a geometry::SourceId is only assigned once at the first call of any of this plant’s geometry registration methods, and it does not change after that. Post-finalize calls will always return the same value.
- get_state_output_port(*args, **kwargs)
Overloaded function.
get_state_output_port(self: pydrake.multibody.plant.MultibodyPlant) -> pydrake.systems.framework.OutputPort
Returns a constant reference to the output port for the multibody state x = [q, v] of the model.
- Precondition:
Finalize() was already called on
this
plant.
- Raises
RuntimeError if called before Finalize() –
get_state_output_port(self: pydrake.multibody.plant.MultibodyPlant, model_instance: pydrake.multibody.tree.ModelInstanceIndex) -> pydrake.systems.framework.OutputPort
Returns a constant reference to the output port for the state xᵢ = [qᵢ vᵢ] of model instance i. (Here qᵢ ⊆ q and vᵢ ⊆ v.)
- Precondition:
Finalize() was already called on
this
plant.
- Raises
RuntimeError if called before Finalize() –
RuntimeError if the model instance does not exist. –
- GetAccelerationLowerLimits(self: pydrake.multibody.plant.MultibodyPlant) numpy.ndarray[numpy.float64[m, 1]]
Returns a vector of size
num_velocities()
containing the lower acceleration limits for every generalized velocity coordinate. These include joint and free body coordinates. Any unbounded or unspecified limits will be -infinity.- Raises
RuntimeError if called pre-finalize. –
- GetAccelerationUpperLimits(self: pydrake.multibody.plant.MultibodyPlant) numpy.ndarray[numpy.float64[m, 1]]
Upper limit analog of GetAccelerationsLowerLimits(), where any unbounded or unspecified limits will be +infinity.
See also
GetAccelerationLowerLimits() for more information.
- GetActuatedJointIndices(self: pydrake.multibody.plant.MultibodyPlant, model_instance: pydrake.multibody.tree.ModelInstanceIndex) list[pydrake.multibody.tree.JointIndex]
Returns a list of actuated joint indices associated with
model_instance
.- Raises
RuntimeError if called pre-finalize. –
- GetActuatorNames(*args, **kwargs)
Overloaded function.
GetActuatorNames(self: pydrake.multibody.plant.MultibodyPlant, add_model_instance_prefix: bool = True) -> list[str]
Returns a list of string names corresponding to each element of the actuation vector. These strings take the form
{model_instance_name}_{joint_actuator_name}
, but the prefix may optionally be withheld usingadd_model_instance_prefix
.The returned names are guaranteed to be unique if
add_model_instance_prefix
isTrue
(the default).- Raises
RuntimeError if the plant is not finalized. –
GetActuatorNames(self: pydrake.multibody.plant.MultibodyPlant, model_instance: pydrake.multibody.tree.ModelInstanceIndex, add_model_instance_prefix: bool = False) -> list[str]
Returns a list of string names corresponding to each element of the actuation vector. These strings take the form
{model_instance_name}_{joint_actuator_name}
, but the prefix may optionally be withheld usingadd_model_instance_prefix
.The returned names are guaranteed to be unique.
- Raises
RuntimeError if the plant is not finalized or if the –
model_instance` is invalid –
- GetBodiesKinematicallyAffectedBy(self: pydrake.multibody.plant.MultibodyPlant, joint_indexes: list[pydrake.multibody.tree.JointIndex]) list[pydrake.multibody.tree.BodyIndex]
Returns all bodies whose kinematics are transitively affected by the given vector of Joints. The affected bodies are returned in increasing order of body indexes. Note that this is a kinematic relationship rather than a dynamic one. For example, if one of the inboard joints is a free (6dof) joint, the kinematic influence is still felt even though dynamically there would be no influence on the outboard body. This function can be only be called post-finalize, see Finalize().
- Raises
RuntimeError if any of the given joint has an invalid index, –
doesn't correspond to a mobilizer, or is welded. –
- GetBodiesWeldedTo(self: pydrake.multibody.plant.MultibodyPlant, body: pydrake.multibody.tree.RigidBody) list[pydrake.multibody.tree.RigidBody]
Returns all bodies that are transitively welded, or rigidly affixed, to
body
, per these two definitions:A body is always considered welded to itself.
2. Two unique bodies are considered welded together exclusively by the presence of a weld joint, not by other constructs that prevent mobility (e.g. constraints).
This method can be called at any time during the lifetime of
this
plant, either pre- or post-finalize, see Finalize().Meant to be used with
CollectRegisteredGeometries
.The following example demonstrates filtering collisions between all bodies rigidly affixed to a door (which could be moving) and all bodies rigidly affixed to the world:
Click to expand C++ code...
GeometrySet g_world = plant.CollectRegisteredGeometries( plant.GetBodiesWeldedTo(plant.world_body())); GeometrySet g_door = plant.CollectRegisteredGeometries( plant.GetBodiesWeldedTo(plant.GetBodyByName("door"))); scene_graph.ExcludeCollisionsBetweeen(g_world, g_door);
Note
Usages akin to this example may introduce redundant collision filtering; this will not have a functional impact, but may have a minor performance impact.
- Returns
all bodies rigidly fixed to
body
. This does not return the bodies in any prescribed order.- Raises
RuntimeError if body is not part of this plant. –
- GetBodyByName(*args, **kwargs)
Overloaded function.
GetBodyByName(self: pydrake.multibody.plant.MultibodyPlant, name: str) -> pydrake.multibody.tree.RigidBody
Returns a constant reference to a body that is identified by the string
name
inthis
MultibodyPlant.- Raises
RuntimeError if there is no body with the requested name. –
RuntimeError if the body name occurs in multiple model instances. –
See also
HasBodyNamed() to query if there exists a body in
this
MultibodyPlant with a given specified name.GetBodyByName(self: pydrake.multibody.plant.MultibodyPlant, name: str, model_instance: pydrake.multibody.tree.ModelInstanceIndex) -> pydrake.multibody.tree.RigidBody
Returns a constant reference to the body that is uniquely identified by the string
name
andmodel_instance
inthis
MultibodyPlant.- Raises
RuntimeError if there is no body with the requested name. –
See also
HasBodyNamed() to query if there exists a body in
this
MultibodyPlant with a given specified name.
- GetBodyFrameIdIfExists(self: pydrake.multibody.plant.MultibodyPlant, body_index: pydrake.multibody.tree.BodyIndex) Optional[pydrake.geometry.FrameId]
If the body with
body_index
belongs to the called plant, it returns the geometry::FrameId associated with it. Otherwise, it returns nullopt.
- GetBodyFrameIdOrThrow(self: pydrake.multibody.plant.MultibodyPlant, body_index: pydrake.multibody.tree.BodyIndex) pydrake.geometry.FrameId
If the body with
body_index
belongs to the called plant, it returns the geometry::FrameId associated with it. Otherwise this method throws an exception.- Raises
RuntimeError if the called plant does not have the body indicated –
by body_index. –
- GetBodyFromFrameId(self: pydrake.multibody.plant.MultibodyPlant, arg0: pydrake.geometry.FrameId) pydrake.multibody.tree.RigidBody
Given a geometry frame identifier, returns a pointer to the body associated with that id (nullptr if there is no such body).
- GetBodyIndices(self: pydrake.multibody.plant.MultibodyPlant, model_instance: pydrake.multibody.tree.ModelInstanceIndex) list[pydrake.multibody.tree.BodyIndex]
Returns a list of body indices associated with
model_instance
.
- GetCollisionGeometriesForBody(self: pydrake.multibody.plant.MultibodyPlant, body: pydrake.multibody.tree.RigidBody) list[pydrake.geometry.GeometryId]
Returns an array of GeometryId’s identifying the different contact geometries for
body
previously registered with a SceneGraph.Note
This method can be called at any time during the lifetime of
this
plant, either pre- or post-finalize, see Finalize(). Post-finalize calls will always return the same value.See also
RegisterCollisionGeometry(), Finalize()
- GetConstraintActiveStatus(self: pydrake.multibody.plant.MultibodyPlant, context: pydrake.systems.framework.Context, id: pydrake.multibody.tree.MultibodyConstraintId) bool
Returns the active status of the constraint given by
id
incontext
.- Raises
RuntimeError if the MultibodyPlant has not been finalized. –
RuntimeError if id does not belong to any multibody constraint –
in context. –
- GetConstraintIds(self: pydrake.multibody.plant.MultibodyPlant) list[pydrake.multibody.tree.MultibodyConstraintId]
Returns a list of all constraint identifiers. The returned vector becomes invalid after any calls to Add*Constraint() or RemoveConstraint().
- static GetDefaultContactSurfaceRepresentation(time_step: float) pydrake.geometry.HydroelasticContactRepresentation
Return the default value for contact representation, given the desired time step. Discrete systems default to use polygons; continuous systems default to use triangles.
- GetDefaultFreeBodyPose(self: pydrake.multibody.plant.MultibodyPlant, body: pydrake.multibody.tree.RigidBody) pydrake.math.RigidTransform
Gets the default pose of
body
as set by SetDefaultFreeBodyPose(). If no pose is specified for the body, returns the identity pose.- Parameter
body
: RigidBody whose default pose will be retrieved.
- Returns
X_PB
: The pose of the free body relative to its parent frame.
Note
The parent frame is not necessarily the world frame. See mbp_working_with_free_bodies “above for details”.
- Parameter
- GetDefaultPositions(*args, **kwargs)
Overloaded function.
GetDefaultPositions(self: pydrake.multibody.plant.MultibodyPlant) -> numpy.ndarray[numpy.float64[m, 1]]
Gets the default positions for the plant, which can be changed via SetDefaultPositions().
- Raises
RuntimeError if the plant is not finalized. –
GetDefaultPositions(self: pydrake.multibody.plant.MultibodyPlant, model_instance: pydrake.multibody.tree.ModelInstanceIndex) -> numpy.ndarray[numpy.float64[m, 1]]
Gets the default positions for the plant for a given model instance, which can be changed via SetDefaultPositions().
- Raises
RuntimeError if the plant is not finalized, or if the –
model_instance is invalid, –
- GetEffortLowerLimits(self: pydrake.multibody.plant.MultibodyPlant) numpy.ndarray[numpy.float64[m, 1]]
Returns a vector of size
num_actuated_dofs()
containing the lower effort limits for every actuator. Any unbounded or unspecified limits will be -∞. The returned vector is indexed by JointActuatorIndex, see JointActuator::index().See also
GetEffortUpperLimits()
- Raises
RuntimeError if called pre-finalize. –
- GetEffortUpperLimits(self: pydrake.multibody.plant.MultibodyPlant) numpy.ndarray[numpy.float64[m, 1]]
Returns a vector of size
num_actuated_dofs()
containing the upper effort limits for every actuator. Any unbounded or unspecified limits will be +∞. The returned vector is indexed by JointActuatorIndex, see JointActuator::index().See also
GetEffortLowerLimits()
- Raises
RuntimeError if called pre-finalize. –
- GetFloatingBaseBodies(self: pydrake.multibody.plant.MultibodyPlant) set[pydrake.multibody.tree.BodyIndex]
Returns the set of body indices corresponding to the floating base bodies in the model, in no particular order.
- Raises
RuntimeError if called pre-finalize, see Finalize() –
- GetFrameByName(*args, **kwargs)
Overloaded function.
GetFrameByName(self: pydrake.multibody.plant.MultibodyPlant, name: str) -> pydrake.multibody.tree.Frame
Returns a constant reference to a frame that is identified by the string
name
inthis
model.- Raises
RuntimeError if there is no frame with the requested name. –
RuntimeError if the frame name occurs in multiple model instances. –
See also
HasFrameNamed() to query if there exists a frame in
this
model with a given specified name.GetFrameByName(self: pydrake.multibody.plant.MultibodyPlant, name: str, model_instance: pydrake.multibody.tree.ModelInstanceIndex) -> pydrake.multibody.tree.Frame
Returns a constant reference to the frame that is uniquely identified by the string
name
inmodel_instance
.- Raises
RuntimeError if there is no frame with the requested name. –
RuntimeError if model_instance is not valid for this model. –
See also
HasFrameNamed() to query if there exists a frame in
this
model with a given specified name.
- GetFrameIndices(self: pydrake.multibody.plant.MultibodyPlant, model_instance: pydrake.multibody.tree.ModelInstanceIndex) list[pydrake.multibody.tree.FrameIndex]
Returns a list of frame indices associated with
model_instance
.
- GetFreeBodyPose(self: pydrake.multibody.plant.MultibodyPlant, context: pydrake.systems.framework.Context, body: pydrake.multibody.tree.RigidBody) pydrake.math.RigidTransform
Gets the pose of a given
body
in the parent frame P.Note
The parent frame is not necessarily the world frame. See mbp_working_with_free_bodies “above for details”. To acquire X_WB, regardless of what P is, kinematics need to be evaluated by calling EvalBodyPoseInWorld().
- Raises
RuntimeError if body is not a free body in the model. –
RuntimeError if called pre-finalize. –
- GetJointActuatorByName(*args, **kwargs)
Overloaded function.
GetJointActuatorByName(self: pydrake.multibody.plant.MultibodyPlant, name: str) -> pydrake.multibody.tree.JointActuator
Returns a constant reference to an actuator that is identified by the string
name
inthis
MultibodyPlant.- Raises
RuntimeError if there is no actuator with the requested name. –
RuntimeError if the actuator name occurs in multiple model –
instances. –
See also
HasJointActuatorNamed() to query if there exists an actuator in
this
MultibodyPlant with a given specified name.GetJointActuatorByName(self: pydrake.multibody.plant.MultibodyPlant, name: str, model_instance: pydrake.multibody.tree.ModelInstanceIndex) -> pydrake.multibody.tree.JointActuator
Returns a constant reference to the actuator that is uniquely identified by the string
name
andmodel_instance
inthis
MultibodyPlant.- Raises
RuntimeError if there is no actuator with the requested name. –
RuntimeError if model_instance is not valid for this model. –
See also
HasJointActuatorNamed() to query if there exists an actuator in
this
MultibodyPlant with a given specified name.
- GetJointActuatorIndices(*args, **kwargs)
Overloaded function.
GetJointActuatorIndices(self: pydrake.multibody.plant.MultibodyPlant) -> list[pydrake.multibody.tree.JointActuatorIndex]
Returns a list of all joint actuator indices. The vector is ordered by monotonically increasing JointActuatorIndex, but the indices will in general not be consecutive due to actuators that were removed.
GetJointActuatorIndices(self: pydrake.multibody.plant.MultibodyPlant, model_instance: pydrake.multibody.tree.ModelInstanceIndex) -> list[pydrake.multibody.tree.JointActuatorIndex]
Returns a list of joint actuator indices associated with
model_instance
. The vector is ordered by monotonically increasing JointActuatorIndex.- Raises
RuntimeError if called pre-finalize. –
- GetJointByName(self: pydrake.multibody.plant.MultibodyPlant, name: str, model_instance: Optional[pydrake.multibody.tree.ModelInstanceIndex] = None) pydrake.multibody.tree.Joint
Returns a constant reference to a joint that is identified by the string
name
inthis
MultibodyPlant. If the optional template argument is supplied, then the returned value is downcast to the specifiedJointType
.- Template parameter
JointType
: The specific type of the Joint to be retrieved. It must be a subclass of Joint.
- Raises
RuntimeError if the named joint is not of type JointType or if –
there is no Joint with that name. –
RuntimeError if model_instance is not valid for this model. –
See also
HasJointNamed() to query if there exists a joint in
this
MultibodyPlant with a given specified name.- Template parameter
- GetJointIndices(*args, **kwargs)
Overloaded function.
GetJointIndices(self: pydrake.multibody.plant.MultibodyPlant) -> list[pydrake.multibody.tree.JointIndex]
Returns a list of all joint indices. The vector is ordered by monotonically increasing JointIndex, but the indices will in general not be consecutive due to joints that were removed.
GetJointIndices(self: pydrake.multibody.plant.MultibodyPlant, model_instance: pydrake.multibody.tree.ModelInstanceIndex) -> list[pydrake.multibody.tree.JointIndex]
Returns a list of joint indices associated with
model_instance
.
- GetModelInstanceByName(self: pydrake.multibody.plant.MultibodyPlant, name: str) pydrake.multibody.tree.ModelInstanceIndex
Returns the index to the model instance that is uniquely identified by the string
name
inthis
MultibodyPlant.- Raises
RuntimeError if there is no instance with the requested name. –
See also
HasModelInstanceNamed() to query if there exists an instance in
this
MultibodyPlant with a given specified name.
- GetModelInstanceName(self: pydrake.multibody.plant.MultibodyPlant, model_instance: pydrake.multibody.tree.ModelInstanceIndex) str
Returns the name of a
model_instance
.- Raises
RuntimeError when model_instance does not correspond to a –
model in this model. –
- GetMutableJointByName(self: pydrake.multibody.plant.MultibodyPlant, name: str, model_instance: Optional[pydrake.multibody.tree.ModelInstanceIndex] = None) pydrake.multibody.tree.Joint
Returns a constant reference to a joint that is identified by the string
name
inthis
MultibodyPlant. If the optional template argument is supplied, then the returned value is downcast to the specifiedJointType
.- Template parameter
JointType
: The specific type of the Joint to be retrieved. It must be a subclass of Joint.
- Raises
RuntimeError if the named joint is not of type JointType or if –
there is no Joint with that name. –
RuntimeError if model_instance is not valid for this model. –
See also
HasJointNamed() to query if there exists a joint in
this
MultibodyPlant with a given specified name.- Template parameter
- GetPositionLowerLimits(self: pydrake.multibody.plant.MultibodyPlant) numpy.ndarray[numpy.float64[m, 1]]
Returns a vector of size
num_positions()
containing the lower position limits for every generalized position coordinate. These include joint and free body coordinates. Any unbounded or unspecified limits will be -infinity.- Raises
RuntimeError if called pre-finalize. –
- GetPositionNames(*args, **kwargs)
Overloaded function.
GetPositionNames(self: pydrake.multibody.plant.MultibodyPlant, add_model_instance_prefix: bool = True, always_add_suffix: bool = True) -> list[str]
Returns a list of string names corresponding to each element of the position vector. These strings take the form
{model_instance_name}_{joint_name}_{joint_position_suffix}
, but the prefix and suffix may optionally be withheld usingadd_model_instance_prefix
andalways_add_suffix
.- Parameter
always_add_suffix
: (optional). If true, then the suffix is always added. If false, then the suffix is only added for joints that have more than one position (in this case, not adding would lead to ambiguity).
The returned names are guaranteed to be unique if
add_model_instance_prefix
isTrue
(the default).- Raises
RuntimeError if the plant is not finalized. –
GetPositionNames(self: pydrake.multibody.plant.MultibodyPlant, model_instance: pydrake.multibody.tree.ModelInstanceIndex, add_model_instance_prefix: bool = False, always_add_suffix: bool = True) -> list[str]
Returns a list of string names corresponding to each element of the position vector. These strings take the form
{model_instance_name}_{joint_name}_{joint_position_suffix}
, but the prefix and suffix may optionally be withheld usingadd_model_instance_prefix
andalways_add_suffix
.- Parameter
always_add_suffix
: (optional). If true, then the suffix is always added. If false, then the suffix is only added for joints that have more than one position (in this case, not adding would lead to ambiguity).
The returned names are guaranteed to be unique.
- Raises
RuntimeError if the plant is not finalized or if the –
model_instance` is invalid –
- GetPositions(*args, **kwargs)
Overloaded function.
GetPositions(self: pydrake.multibody.plant.MultibodyPlant, context: pydrake.systems.framework.Context) -> numpy.ndarray[numpy.float64[m, 1]]
Returns a const vector reference to the vector of generalized positions q in a given Context.
Note
This method returns a reference to existing data, exhibits constant i.e., O(1) time complexity, and runs very quickly.
- Raises
RuntimeError if context does not correspond to the Context for –
a multibody model. –
GetPositions(self: pydrake.multibody.plant.MultibodyPlant, context: pydrake.systems.framework.Context, model_instance: pydrake.multibody.tree.ModelInstanceIndex) -> numpy.ndarray[numpy.float64[m, 1]]
Returns a vector containing the generalized positions q of a specified model instance in a given Context.
Note
Returns a dense vector of dimension
num_positions(model_instance)
associated withmodel_instance
by copying fromcontext
.- Raises
RuntimeError if context does not correspond to the Context for –
a multibody model or model_instance is invalid. –
GetPositions(self: pydrake.multibody.plant.MultibodyPlant, context: pydrake.systems.framework.Context) -> numpy.ndarray[numpy.float64[m, 1]]
Returns a const vector reference to the vector of generalized positions q in a given Context.
Note
This method returns a reference to existing data, exhibits constant i.e., O(1) time complexity, and runs very quickly.
- Raises
RuntimeError if context does not correspond to the Context for –
a multibody model. –
GetPositions(self: pydrake.multibody.plant.MultibodyPlant, context: pydrake.systems.framework.Context, model_instance: pydrake.multibody.tree.ModelInstanceIndex) -> numpy.ndarray[numpy.float64[m, 1]]
Returns a vector containing the generalized positions q of a specified model instance in a given Context.
Note
Returns a dense vector of dimension
num_positions(model_instance)
associated withmodel_instance
by copying fromcontext
.- Raises
RuntimeError if context does not correspond to the Context for –
a multibody model or model_instance is invalid. –
- GetPositionsAndVelocities(*args, **kwargs)
Overloaded function.
GetPositionsAndVelocities(self: pydrake.multibody.plant.MultibodyPlant, context: pydrake.systems.framework.Context) -> numpy.ndarray[numpy.float64[m, 1]]
Returns a const vector reference
[q; v]
to the generalized positions q and generalized velocities v in a given Context.Note
This method returns a reference to existing data, exhibits constant i.e., O(1) time complexity, and runs very quickly.
- Raises
RuntimeError if context does not correspond to the Context for –
a multibody model. –
GetPositionsAndVelocities(self: pydrake.multibody.plant.MultibodyPlant, context: pydrake.systems.framework.Context, model_instance: pydrake.multibody.tree.ModelInstanceIndex) -> numpy.ndarray[numpy.float64[m, 1]]
Returns a vector
[q; v]
containing the generalized positions q and generalized velocities v of a specified model instance in a given Context.Note
Returns a dense vector of dimension
num_positions(model_instance) + num_velocities(model_instance)
associated withmodel_instance
by copying fromcontext
.- Raises
RuntimeError if context does not correspond to the Context for –
a multibody model or model_instance is invalid. –
- GetPositionsFromArray(self: pydrake.multibody.plant.MultibodyPlant, model_instance: pydrake.multibody.tree.ModelInstanceIndex, q: numpy.ndarray[numpy.float64[m, 1]]) numpy.ndarray[numpy.float64[m, 1]]
Returns a vector of generalized positions for
model_instance
from a vectorq_array
of generalized positions for the entire model model. This method throws an exception ifq
is not of size MultibodyPlant::num_positions().
- GetPositionUpperLimits(self: pydrake.multibody.plant.MultibodyPlant) numpy.ndarray[numpy.float64[m, 1]]
Upper limit analog of GetPositionLowerLimits(), where any unbounded or unspecified limits will be +infinity.
See also
GetPositionLowerLimits() for more information.
- GetRigidBodyByName(*args, **kwargs)
Overloaded function.
GetRigidBodyByName(self: pydrake.multibody.plant.MultibodyPlant, name: str) -> pydrake.multibody.tree.RigidBody
Returns a constant reference to a rigid body that is identified by the string
name
inthis
model.- Raises
RuntimeError if there is no body with the requested name. –
RuntimeError if the body name occurs in multiple model instances. –
RuntimeError if the requested body is not a RigidBody. –
See also
HasBodyNamed() to query if there exists a body in
this
model with a given specified name.GetRigidBodyByName(self: pydrake.multibody.plant.MultibodyPlant, name: str, model_instance: pydrake.multibody.tree.ModelInstanceIndex) -> pydrake.multibody.tree.RigidBody
Returns a constant reference to the rigid body that is uniquely identified by the string
name
inmodel_instance
.- Raises
RuntimeError if there is no body with the requested name. –
RuntimeError if the requested body is not a RigidBody. –
RuntimeError if model_instance is not valid for this model. –
See also
HasBodyNamed() to query if there exists a body in
this
model with a given specified name.
- GetStateNames(*args, **kwargs)
Overloaded function.
GetStateNames(self: pydrake.multibody.plant.MultibodyPlant, add_model_instance_prefix: bool = True) -> list[str]
Returns a list of string names corresponding to each element of the multibody state vector. These strings take the form
{model_instance_name}_{joint_name}_{joint_position_suffix | joint_velocity_suffix}
, but the prefix may optionally be withheld usingadd_model_instance_prefix
.The returned names are guaranteed to be unique if
add_model_instance_prefix
isTrue
(the default).- Raises
RuntimeError if the plant is not finalized. –
GetStateNames(self: pydrake.multibody.plant.MultibodyPlant, model_instance: pydrake.multibody.tree.ModelInstanceIndex, add_model_instance_prefix: bool = False) -> list[str]
Returns a list of string names corresponding to each element of the multibody state vector. These strings take the form
{model_instance_name}_{joint_name}_{joint_position_suffix | joint_velocity_suffix}
, but the prefix may optionally be withheld usingadd_model_instance_prefix
.The returned names are guaranteed to be unique.
- Raises
RuntimeError if the plant is not finalized or if the –
model_instance` is invalid –
- GetTopologyGraphvizString(self: pydrake.multibody.plant.MultibodyPlant) str
Returns a Graphviz string describing the topology of this plant. To render the string, use the Graphviz tool,
dot
. http://www.graphviz.org/Note: this method can be called either before or after
Finalize()
.
- GetUniqueFreeBaseBodyOrThrow(self: pydrake.multibody.plant.MultibodyPlant, model_instance: pydrake.multibody.tree.ModelInstanceIndex) pydrake.multibody.tree.RigidBody
If there exists a unique base body that belongs to the model given by
model_instance
and that unique base body is free (see HasUniqueBaseBody()), return that free body. Throw an exception otherwise.- Raises
RuntimeError if called pre-finalize. –
RuntimeError if model_instance is not valid. –
RuntimeError if HasUniqueFreeBaseBody(model_instance) == false. –
- GetVelocities(*args, **kwargs)
Overloaded function.
GetVelocities(self: pydrake.multibody.plant.MultibodyPlant, context: pydrake.systems.framework.Context) -> numpy.ndarray[numpy.float64[m, 1]]
Returns a const vector reference to the generalized velocities v in a given Context.
Note
This method returns a reference to existing data, exhibits constant i.e., O(1) time complexity, and runs very quickly.
- Raises
RuntimeError if context does not correspond to the Context for –
a multibody model. –
GetVelocities(self: pydrake.multibody.plant.MultibodyPlant, context: pydrake.systems.framework.Context, model_instance: pydrake.multibody.tree.ModelInstanceIndex) -> numpy.ndarray[numpy.float64[m, 1]]
Returns a vector containing the generalized velocities v of a specified model instance in a given Context.
Note
returns a dense vector of dimension
num_velocities(model_instance)
associated withmodel_instance
by copying fromcontext
.- Raises
RuntimeError if context does not correspond to the Context for –
a multibody model or model_instance is invalid. –
GetVelocities(self: pydrake.multibody.plant.MultibodyPlant, context: pydrake.systems.framework.Context) -> numpy.ndarray[numpy.float64[m, 1]]
Returns a const vector reference to the generalized velocities v in a given Context.
Note
This method returns a reference to existing data, exhibits constant i.e., O(1) time complexity, and runs very quickly.
- Raises
RuntimeError if context does not correspond to the Context for –
a multibody model. –
GetVelocities(self: pydrake.multibody.plant.MultibodyPlant, context: pydrake.systems.framework.Context, model_instance: pydrake.multibody.tree.ModelInstanceIndex) -> numpy.ndarray[numpy.float64[m, 1]]
Returns a vector containing the generalized velocities v of a specified model instance in a given Context.
Note
returns a dense vector of dimension
num_velocities(model_instance)
associated withmodel_instance
by copying fromcontext
.- Raises
RuntimeError if context does not correspond to the Context for –
a multibody model or model_instance is invalid. –
- GetVelocitiesFromArray(self: pydrake.multibody.plant.MultibodyPlant, model_instance: pydrake.multibody.tree.ModelInstanceIndex, v: numpy.ndarray[numpy.float64[m, 1]]) numpy.ndarray[numpy.float64[m, 1]]
Returns a vector of generalized velocities for
model_instance
from a vectorv
of generalized velocities for the entire MultibodyPlant model. This method throws an exception if the input array is not of size MultibodyPlant::num_velocities().
- GetVelocityLowerLimits(self: pydrake.multibody.plant.MultibodyPlant) numpy.ndarray[numpy.float64[m, 1]]
Returns a vector of size
num_velocities()
containing the lower velocity limits for every generalized velocity coordinate. These include joint and free body coordinates. Any unbounded or unspecified limits will be -infinity.- Raises
RuntimeError if called pre-finalize. –
- GetVelocityNames(*args, **kwargs)
Overloaded function.
GetVelocityNames(self: pydrake.multibody.plant.MultibodyPlant, add_model_instance_prefix: bool = True, always_add_suffix: bool = True) -> list[str]
Returns a list of string names corresponding to each element of the velocity vector. These strings take the form
{model_instance_name}_{joint_name}_{joint_velocity_suffix}
, but the prefix and suffix may optionally be withheld usingadd_model_instance_prefix
andalways_add_suffix
.- Parameter
always_add_suffix
: (optional). If true, then the suffix is always added. If false, then the suffix is only added for joints that have more than one position (in this case, not adding would lead to ambiguity).
The returned names are guaranteed to be unique if
add_model_instance_prefix
isTrue
(the default).- Raises
RuntimeError if the plant is not finalized. –
GetVelocityNames(self: pydrake.multibody.plant.MultibodyPlant, model_instance: pydrake.multibody.tree.ModelInstanceIndex, add_model_instance_prefix: bool = False, always_add_suffix: bool = True) -> list[str]
Returns a list of string names corresponding to each element of the velocity vector. These strings take the form
{model_instance_name}_{joint_name}_{joint_velocity_suffix}
, but the prefix and suffix may optionally be withheld usingadd_model_instance_prefix
andalways_add_suffix
.- Parameter
always_add_suffix
: (optional). If true, then the suffix is always added. If false, then the suffix is only added for joints that have more than one position (in this case, not adding would lead to ambiguity).
The returned names are guaranteed to be unique.
- Raises
RuntimeError if the plant is not finalized or if the –
model_instance` is invalid –
- GetVelocityUpperLimits(self: pydrake.multibody.plant.MultibodyPlant) numpy.ndarray[numpy.float64[m, 1]]
Upper limit analog of GetVelocitysLowerLimits(), where any unbounded or unspecified limits will be +infinity.
See also
GetVelocityLowerLimits() for more information.
- GetVisualGeometriesForBody(self: pydrake.multibody.plant.MultibodyPlant, body: pydrake.multibody.tree.RigidBody) list[pydrake.geometry.GeometryId]
Returns an array of GeometryId’s identifying the different visual geometries for
body
previously registered with a SceneGraph.Note
This method can be called at any time during the lifetime of
this
plant, either pre- or post-finalize, see Finalize(). Post-finalize calls will always return the same value.See also
RegisterVisualGeometry(), Finalize()
- gravity_field(self: pydrake.multibody.plant.MultibodyPlant) pydrake.multibody.tree.UniformGravityFieldElement
An accessor to the current gravity field.
- has_joint(self: pydrake.multibody.plant.MultibodyPlant, joint_index: pydrake.multibody.tree.JointIndex) bool
Returns true if plant has a joint with unique index
joint_index
. The value could be false if the joint was removed using RemoveJoint().
- has_joint_actuator(self: pydrake.multibody.plant.MultibodyPlant, actuator_index: pydrake.multibody.tree.JointActuatorIndex) bool
Returns true if plant has a joint actuator with unique index
actuator_index
. The value could be false if the actuator was removed using RemoveJointActuator().
- has_sampled_output_ports(self: pydrake.multibody.plant.MultibodyPlant) bool
(Advanced) If
this
plant is continuous (i.e., is_discrete() isFalse
), returns false. Ifthis
plant is discrete, returns whether or not the output ports are sampled (change only at a time step boundary) or live (instantaneously reflect changes to the input ports). See output_port_sampling “Output port sampling” for details.
- HasBodyNamed(*args, **kwargs)
Overloaded function.
HasBodyNamed(self: pydrake.multibody.plant.MultibodyPlant, name: str) -> bool
- Returns
True
if a body namedname
was added to the MultibodyPlant.
See also
AddRigidBody().
- Raises
RuntimeError if the body name occurs in multiple model instances. –
HasBodyNamed(self: pydrake.multibody.plant.MultibodyPlant, name: str, model_instance: pydrake.multibody.tree.ModelInstanceIndex) -> bool
- Returns
True
if a body namedname
was added to the MultibodyPlant inmodel_instance
.
See also
AddRigidBody().
- Raises
RuntimeError if model_instance is not valid for this model. –
- HasFrameNamed(*args, **kwargs)
Overloaded function.
HasFrameNamed(self: pydrake.multibody.plant.MultibodyPlant, name: str) -> bool
- Returns
True
if a frame namedname
was added to the model.
See also
AddFrame().
- Raises
RuntimeError if the frame name occurs in multiple model instances. –
HasFrameNamed(self: pydrake.multibody.plant.MultibodyPlant, name: str, model_instance: pydrake.multibody.tree.ModelInstanceIndex) -> bool
- Returns
True
if a frame namedname
was added tomodel_instance
.
See also
AddFrame().
- Raises
RuntimeError if model_instance is not valid for this model. –
- HasJointActuatorNamed(*args, **kwargs)
Overloaded function.
HasJointActuatorNamed(self: pydrake.multibody.plant.MultibodyPlant, name: str) -> bool
- Returns
True
if an actuator namedname
was added to this model.
See also
AddJointActuator().
- Raises
RuntimeError if the actuator name occurs in multiple model –
instances. –
HasJointActuatorNamed(self: pydrake.multibody.plant.MultibodyPlant, name: str, model_instance: pydrake.multibody.tree.ModelInstanceIndex) -> bool
- Returns
True
if an actuator namedname
was added tomodel_instance
.
See also
AddJointActuator().
- Raises
RuntimeError if model_instance is not valid for this model. –
- HasJointNamed(*args, **kwargs)
Overloaded function.
HasJointNamed(self: pydrake.multibody.plant.MultibodyPlant, name: str) -> bool
- Returns
True
if a joint namedname
was added to this model.
See also
AddJoint().
- Raises
RuntimeError if the joint name occurs in multiple model instances. –
HasJointNamed(self: pydrake.multibody.plant.MultibodyPlant, name: str, model_instance: pydrake.multibody.tree.ModelInstanceIndex) -> bool
- Returns
True
if a joint namedname
was added tomodel_instance
.
See also
AddJoint().
- Raises
RuntimeError if model_instance is not valid for this model. –
- HasModelInstanceNamed(self: pydrake.multibody.plant.MultibodyPlant, name: str) bool
- Returns
True
if a model instance namedname
was added to this model.
See also
AddModelInstance().
- HasUniqueFreeBaseBody(self: pydrake.multibody.plant.MultibodyPlant, model_instance: pydrake.multibody.tree.ModelInstanceIndex) bool
Return true if there exists a unique base body in the model given by
model_instance
and that unique base body is free.- Raises
RuntimeError if called pre-finalize. –
RuntimeError if model_instance is not valid. –
- is_finalized(self: pydrake.multibody.plant.MultibodyPlant) bool
Returns
True
if this MultibodyPlant was finalized with a call to Finalize().See also
Finalize().
- is_gravity_enabled(self: pydrake.multibody.plant.MultibodyPlant, model_instance: pydrake.multibody.tree.ModelInstanceIndex) bool
- Returns
True
iff gravity is enabled formodel_instance
.
See also
set_gravity_enabled().
- Raises
RuntimeError if the model instance is invalid. –
- IsAnchored(self: pydrake.multibody.plant.MultibodyPlant, body: pydrake.multibody.tree.RigidBody) bool
Returns
True
ifbody
is anchored (i.e. the kinematic path betweenbody
and the world only contains weld joints.)- Raises
RuntimeError if called pre-finalize. –
- IsVelocityEqualToQDot(self: pydrake.multibody.plant.MultibodyPlant) bool
Returns true iff the generalized velocity v is exactly the time derivative q̇ of the generalized coordinates q. In this case MapQDotToVelocity() and MapVelocityToQDot() implement the identity map. This method is, in the worst case, O(n), where n is the number of joints.
- MakeActuationMatrix(self: pydrake.multibody.plant.MultibodyPlant) numpy.ndarray[numpy.float64[m, n]]
This method creates an actuation matrix B mapping a vector of actuation values u into generalized forces
tau_u = B * u
, where B is a matrix of sizenv x nu
withnu
equal to num_actuated_dofs() andnv
equal to num_velocities(). The vector u of actuation values is of size num_actuated_dofs(). For a given JointActuator,u[JointActuator::input_start()]
stores the value for the external actuation corresponding to that actuator.tau_u
on the other hand is indexed by generalized velocity indices according toJoint::velocity_start()
.Warning
B is a permutation matrix. While making a permutation has
O(n)
complexity, making a full B matrix hasO(n²)
complexity. For most applications this cost can be neglected but it could become significant for very large systems.
- MakeActuationMatrixPseudoinverse(self: pydrake.multibody.plant.MultibodyPlant) scipy.sparse.csc_matrix[numpy.float64]
Creates the pseudoinverse of the actuation matrix B directly (without requiring an explicit inverse calculation). See MakeActuationMatrix().
Notably, when B is full row rank (the system is fully actuated), then the pseudoinverse is a true inverse.
- MakeActuatorSelectorMatrix(*args, **kwargs)
Overloaded function.
MakeActuatorSelectorMatrix(self: pydrake.multibody.plant.MultibodyPlant, user_to_actuator_index_map: list[pydrake.multibody.tree.JointActuatorIndex]) -> numpy.ndarray[numpy.float64[m, n]]
This method allows user to map a vector
uₛ
containing the actuation for a set of selected actuators into the vector u containing the actuation values forthis
full model. The mapping, or selection, is returned in the form of a selector matrix Su such thatu = Su⋅uₛ
. The size nₛ of uₛ is always smaller or equal than the size of the full vector of actuation values u. That is, a user might be interested in only a given subset of actuators in the model.This selection matrix is particularly useful when adding PID control on a portion of the state, see systems::controllers::PidController.
A user specifies the preferred order in uₛ via
user_to_actuator_index_map
. The actuation values in uₛ are a concatenation of the values for each actuator in the order they appear inuser_to_actuator_index_map
. The actuation value in the full vector of actuation valuesu
for a particular actuator can be found at offset JointActuator::input_start().MakeActuatorSelectorMatrix(self: pydrake.multibody.plant.MultibodyPlant, user_to_joint_index_map: list[pydrake.multibody.tree.JointIndex]) -> numpy.ndarray[numpy.float64[m, n]]
Alternative signature to build an actuation selector matrix
Su
such thatu = Su⋅uₛ
, where u is the vector of actuation values for the full model (see get_actuation_input_port()) and uₛ is a vector of actuation values for the actuators acting on the joints listed byuser_to_joint_index_map
. It is assumed that all joints referenced byuser_to_joint_index_map
are actuated. See MakeActuatorSelectorMatrix(const std::vector<JointActuatorIndex>&) for details.- Raises
RuntimeError if any of the joints in user_to_joint_index_map –
does not have an actuator. –
- MakeQDotToVelocityMap(self: pydrake.multibody.plant.MultibodyPlant, context: pydrake.systems.framework.Context) scipy.sparse.csc_matrix[numpy.float64]
Returns the matrix
N⁺(q)
, which mapsv = N⁺(q)⋅q̇
, as described in MapQDotToVelocity(). Prefer calling MapQDotToVelocity() directly; this entry point is provided to support callers that require the explicit linear form (once q is given) of the relationship. This method is, in the worst case, O(n), where n is the number of joints.- Parameter
context
: The context containing the state of the model.
See also
MapVelocityToQDot()
- Parameter
- MakeStateSelectorMatrix(self: pydrake.multibody.plant.MultibodyPlant, user_to_joint_index_map: list[pydrake.multibody.tree.JointIndex]) numpy.ndarray[numpy.float64[m, n]]
This method allows users to map the state of
this
model, x, into a vector of selected state xₛ with a given preferred ordering. The mapping, or selection, is returned in the form of a selector matrix Sx such thatxₛ = Sx⋅x
. The size nₛ of xₛ is always smaller or equal than the size of the full state x. That is, a user might be interested in only a given portion of the full state x.This selection matrix is particularly useful when adding PID control on a portion of the state, see systems::controllers::PidController.
A user specifies the preferred order in xₛ via
user_to_joint_index_map
. The selected state is built such that selected positions are followed by selected velocities, as inxₛ = [qₛ, vₛ]
. The positions in qₛ are a concatenation of the positions for each joint in the order they appear inuser_to_joint_index_map
. That is, the positions foruser_to_joint_index_map[0]
are first, followed by the positions foruser_to_joint_index_map[1]
, etc. Similarly for the selected velocities vₛ.- Raises
RuntimeError if there are repeated indices in –
user_to_joint_index_map` –
- MakeVelocityToQDotMap(self: pydrake.multibody.plant.MultibodyPlant, context: pydrake.systems.framework.Context) scipy.sparse.csc_matrix[numpy.float64]
Returns the matrix
N(q)
, which mapsq̇ = N(q)⋅v
, as described in MapVelocityToQDot(). Prefer calling MapVelocityToQDot() directly; this entry point is provided to support callers that require the explicit linear form (once q is given) of the relationship. Do not take the (pseudo-)inverse ofN(q)
; call MakeQDotToVelocityMap instead. This method is, in the worst case, O(n), where n is the number of joints.- Parameter
context
: The context containing the state of the model.
See also
MapVelocityToQDot()
- Parameter
- MapQDotToVelocity(self: pydrake.multibody.plant.MultibodyPlant, context: pydrake.systems.framework.Context, qdot: numpy.ndarray[numpy.float64[m, 1]]) numpy.ndarray[numpy.float64[m, 1]]
Transforms the time derivative
qdot
of the generalized positions vectorq
(stored incontext
) to generalized velocitiesv
. v andq̇
are related linearly byq̇ = N(q)⋅v
. AlthoughN(q)
is not necessarily square, its left pseudo-inverseN⁺(q)
can be used to invert that relationship without residual error, provided thatqdot
is in the range space ofN(q)
(that is, if it could have been produced asq̇ = N(q)⋅v
for somev
). Using the configurationq
stored in the givencontext
this method calculatesv = N⁺(q)⋅q̇
.- Parameter
context
: The context containing the state of the model.
- Parameter
qdot
: A vector containing the time derivatives of the generalized positions. This method aborts if
qdot
is not of size num_positions().- Parameter
v
: A valid (non-null) pointer to a vector in
ℛⁿ
with n the number of generalized velocities. This method aborts if v is nullptr or if it is not of size num_velocities().
See also
MapVelocityToQDot()
See also
Mobilizer::MapQDotToVelocity()
- Parameter
- MapVelocityToQDot(self: pydrake.multibody.plant.MultibodyPlant, context: pydrake.systems.framework.Context, v: numpy.ndarray[numpy.float64[m, 1]]) numpy.ndarray[numpy.float64[m, 1]]
Transforms generalized velocities v to time derivatives
qdot
of the generalized positions vectorq
(stored incontext
). v andqdot
are related linearly byq̇ = N(q)⋅v
. Using the configurationq
stored in the givencontext
this method calculatesq̇ = N(q)⋅v
.- Parameter
context
: The context containing the state of the model.
- Parameter
v
: A vector of generalized velocities for this model. This method aborts if v is not of size num_velocities().
- Parameter
qdot
: A valid (non-null) pointer to a vector in
ℝⁿ
with n being the number of generalized positions in this model, given bynum_positions()
. This method aborts ifqdot
is nullptr or if it is not of size num_positions().
See also
MapQDotToVelocity()
See also
Mobilizer::MapVelocityToQDot()
- Parameter
- mutable_deformable_model(self: pydrake.multibody.plant.MultibodyPlant) pydrake.multibody.plant.DeformableModel
Returns a mutable reference to the DeformableModel owned by this plant.
- Raises
RuntimeError if the plant is finalized. –
Warning
This feature is considered to be experimental and may change or be removed at any time, without any deprecation notice ahead of time.
- mutable_gravity_field(self: pydrake.multibody.plant.MultibodyPlant) pydrake.multibody.tree.UniformGravityFieldElement
A mutable accessor to the current gravity field.
- num_actuated_dofs(*args, **kwargs)
Overloaded function.
num_actuated_dofs(self: pydrake.multibody.plant.MultibodyPlant) -> int
Returns the total number of actuated degrees of freedom. That is, the vector of actuation values u has this size. See AddJointActuator().
num_actuated_dofs(self: pydrake.multibody.plant.MultibodyPlant, model_instance: pydrake.multibody.tree.ModelInstanceIndex) -> int
Returns the total number of actuated degrees of freedom for a specific model instance. That is, the vector of actuation values u has this size. See AddJointActuator().
- Raises
RuntimeError if called pre-finalize. –
- num_actuators(*args, **kwargs)
Overloaded function.
num_actuators(self: pydrake.multibody.plant.MultibodyPlant) -> int
Returns the number of joint actuators in the model.
See also
AddJointActuator().
num_actuators(self: pydrake.multibody.plant.MultibodyPlant, model_instance: pydrake.multibody.tree.ModelInstanceIndex) -> int
Returns the number of actuators for a specific model instance.
- Raises
RuntimeError if called pre-finalize. –
- num_bodies(self: pydrake.multibody.plant.MultibodyPlant) int
Returns the number of RigidBody elements in the model, including the “world” RigidBody, which is always part of the model.
See also
AddRigidBody().
- num_collision_geometries(self: pydrake.multibody.plant.MultibodyPlant) int
Returns the number of geometries registered for contact modeling. This method can be called at any time during the lifetime of
this
plant, either pre- or post-finalize, see Finalize(). Post-finalize calls will always return the same value.
- num_constraints(self: pydrake.multibody.plant.MultibodyPlant) int
Returns the total number of constraints specified by the user.
- num_force_elements(self: pydrake.multibody.plant.MultibodyPlant) int
Returns the number of ForceElement objects.
See also
AddForceElement().
- num_frames(self: pydrake.multibody.plant.MultibodyPlant) int
Returns the number of Frame objects in this model. Frames include body frames associated with each of the bodies, including the world body. This means the minimum number of frames is one.
- num_joints(self: pydrake.multibody.plant.MultibodyPlant) int
Returns the number of joints in the model.
See also
AddJoint().
- num_model_instances(self: pydrake.multibody.plant.MultibodyPlant) int
Returns the number of model instances in the model.
See also
AddModelInstance().
- num_multibody_states(*args, **kwargs)
Overloaded function.
num_multibody_states(self: pydrake.multibody.plant.MultibodyPlant) -> int
Returns the size of the multibody system state vector x = [q v]. This will be
num_positions()
plusnum_velocities()
.- Raises
RuntimeError if called pre-finalize. –
num_multibody_states(self: pydrake.multibody.plant.MultibodyPlant, model_instance: pydrake.multibody.tree.ModelInstanceIndex) -> int
Returns the size of the multibody system state vector xᵢ = [qᵢ vᵢ] for model instance i. (Here qᵢ ⊆ q and vᵢ ⊆ v.) will be
num_positions(model_instance)
plusnum_velocities(model_instance)
.- Raises
RuntimeError if called pre-finalize. –
- num_positions(*args, **kwargs)
Overloaded function.
num_positions(self: pydrake.multibody.plant.MultibodyPlant) -> int
Returns the size of the generalized position vector q for this model.
- Raises
RuntimeError if called pre-finalize. –
num_positions(self: pydrake.multibody.plant.MultibodyPlant, model_instance: pydrake.multibody.tree.ModelInstanceIndex) -> int
Returns the size of the generalized position vector qᵢ for model instance i.
- Raises
RuntimeError if called pre-finalize. –
- num_velocities(*args, **kwargs)
Overloaded function.
num_velocities(self: pydrake.multibody.plant.MultibodyPlant) -> int
Returns the size of the generalized velocity vector v for this model.
- Raises
RuntimeError if called pre-finalize. –
num_velocities(self: pydrake.multibody.plant.MultibodyPlant, model_instance: pydrake.multibody.tree.ModelInstanceIndex) -> int
Returns the size of the generalized velocity vector vᵢ for model instance i.
- Raises
RuntimeError if called pre-finalize. –
- NumBodiesWithName(self: pydrake.multibody.plant.MultibodyPlant, name: str) int
- Returns
The total number of bodies (across all model instances) with the given name.
- RegisterAsSourceForSceneGraph(self: pydrake.multibody.plant.MultibodyPlant, scene_graph: pydrake.geometry.SceneGraph) pydrake.geometry.SourceId
Registers
this
plant to serve as a source for an instance of SceneGraph. This registration allows MultibodyPlant to register geometry withscene_graph
for visualization and/or collision queries. The string returned bythis->get_name()
is passed to SceneGraph’s RegisterSource, so it is highly recommended that you give the plant a recognizable name before calling this. Successive registration calls with SceneGraph must be performed on the same instance to which the pointer argumentscene_graph
points to. Failure to do so will result in runtime exceptions.- Parameter
scene_graph
: A valid non nullptr to the SceneGraph instance for which
this
plant will sever as a source, see SceneGraph documentation for further details.
- Returns
the SourceId of
this
plant inscene_graph
. It can also later on be retrieved with get_source_id().- Raises
RuntimeError if called post-finalize. –
RuntimeError if scene_graph is the nullptr. –
RuntimeError if called more than once. –
- Parameter
- RegisterCollisionGeometry(*args, **kwargs)
Overloaded function.
RegisterCollisionGeometry(self: pydrake.multibody.plant.MultibodyPlant, body: pydrake.multibody.tree.RigidBody, X_BG: pydrake.math.RigidTransform, shape: pydrake.geometry.Shape, name: str, properties: pydrake.geometry.ProximityProperties) -> pydrake.geometry.GeometryId
Registers geometry in a SceneGraph with a given geometry::Shape to be used for the contact modeling of a given
body
. More than one geometry can be registered with a body, in which case the body’s contact geometry is the union of all geometries registered to that body.- Parameter
body
: The body for which geometry is being registered.
- Parameter
X_BG
: The fixed pose of the geometry frame G in the body frame B.
- Parameter
shape
: The geometry::Shape used for visualization. E.g.: geometry::Sphere, geometry::Cylinder, etc.
- Parameter
properties
: The proximity properties associated with the collision geometry. They must include the (
material
, coulomb_friction) property of type CoulombFriction<double>.
- Raises
RuntimeError if called post-finalize or if the properties are –
missing the coulomb friction property (or if it is of the wrong –
type) –
RegisterCollisionGeometry(self: pydrake.multibody.plant.MultibodyPlant, body: pydrake.multibody.tree.RigidBody, X_BG: pydrake.math.RigidTransform, shape: pydrake.geometry.Shape, name: str, coulomb_friction: pydrake.multibody.plant.CoulombFriction) -> pydrake.geometry.GeometryId
Overload which specifies a single property: coulomb_friction.
- RegisterVisualGeometry(*args, **kwargs)
Overloaded function.
RegisterVisualGeometry(self: pydrake.multibody.plant.MultibodyPlant, body: pydrake.multibody.tree.RigidBody, X_BG: pydrake.math.RigidTransform, shape: pydrake.geometry.Shape, name: str, diffuse_color: numpy.ndarray[numpy.float64[4, 1]]) -> pydrake.geometry.GeometryId
Overload for visual geometry registration. The following properties are set: - (“phong”, “diffuse”) =
diffuse_color
in both sets of properties. - (“label”, “id”) in perception properties as documented above.See mbp_geometry “the overview” for more details.
RegisterVisualGeometry(self: pydrake.multibody.plant.MultibodyPlant, body: pydrake.multibody.tree.RigidBody, geometry_instance: pydrake.geometry.GeometryInstance) -> pydrake.geometry.GeometryId
Registers the given
geometry_instance
in a SceneGraph to be used for visualization of a givenbody
.The roles that
geometry_instance
gets assigned (illustration/perception) in SceneGraph depend solely on the properties that have already been assigned togeometry_instance
. If any visual roles have been assigned, those will be the only roles used. If no visual roles have been assigned, then both roles will be assigned using the default set of property values.If the registered geometry has the perception role, it will have the (“label”, “id”) property. Possibly assigned as documented above.
See mbp_geometry “the overview” for more details.
- Parameter
body
: The body for which geometry is being registered.
- Parameter
geometry_instance
: The geometry to associate with the visual appearance of
body
.
- Raises
RuntimeError if geometry_instance is null. –
RuntimeError if called post-finalize. –
- Returns
the id for the registered geometry.
- RemoveConstraint(self: pydrake.multibody.plant.MultibodyPlant, id: pydrake.multibody.tree.MultibodyConstraintId) None
Removes the constraint
id
from the plant. Note that this will not remove constraints registered directly with DeformableModel.- Raises
RuntimeError if the MultibodyPlant has already been finalized. –
RuntimeError if id does not identify any multibody constraint –
in this plant. –
- RemoveJoint(self: pydrake.multibody.plant.MultibodyPlant, joint: pydrake.multibody.tree.Joint) None
Removes and deletes
joint
from this MultibodyPlant. Any existing references tojoint
will become invalid, and future calls toget_joint(joint_index)
will throw an exception. Other elements of the plant may depend onjoint
at the time of removal and should be removed first. For example, a JointActuator that depends onjoint
should be removed with RemoveJointActuator(). Currently, we do not provide joint dependency tracking for force elements or constraints, so this function will throw an exception if there are any user-added force elements or constraints in the plant.- Raises
RuntimeError if the plant is already finalized. –
RuntimeError if the plant contains a non-zero number of user-added –
force elements or user-added constraints. –
RuntimeError if joint has a dependent JointActuator. –
See also
AddJoint()
Note
It is important to note that the JointIndex assigned to a joint is immutable. New joint indices are assigned in increasing order, even if a joint with a lower index has been removed. This has the consequence that when a joint is removed from the plant, the sequence
[0, num_joints())
is not necessarily the correct set of un-removed joint indices in the plant. Thus, it is important NOT to loop over joint indices sequentially from0
tonum_joints() - 1
. Instead users should use the provided GetJointIndices() and GetJointIndices(ModelIndex) functions:Click to expand C++ code...
for (JointIndex index : plant.GetJointIndices()) { const Joint<double>& joint = plant.get_joint(index); ... }
- RemoveJointActuator(self: pydrake.multibody.plant.MultibodyPlant, actuator: pydrake.multibody.tree.JointActuator) None
Removes and deletes
actuator
from this MultibodyPlant. Any existing references toactuator
will become invalid, and future calls toget_joint_actuator(actuator_index)
will throw an exception.- Raises
RuntimeError if the plant is already finalized. –
See also
AddJointActuator()
- RenameModelInstance(self: pydrake.multibody.plant.MultibodyPlant, model_instance: pydrake.multibody.tree.ModelInstanceIndex, name: str) None
Renames an existing model instance.
- Parameter
model_instance
: The instance to rename.
- Parameter
name
: A string that uniquely identifies the instance within
this
model.
- Raises
RuntimeError if called after Finalize() –
RuntimeError if model_instance is not a valid index. –
RuntimeError if HasModelInstanceNamed(name) is true. –
- Parameter
- set_adjacent_bodies_collision_filters(self: pydrake.multibody.plant.MultibodyPlant, value: bool) None
Sets whether to apply collision filters to topologically adjacent bodies at Finalize() time. Filters are applied when there exists a joint between bodies, except in the case of 6-dof joints or joints in which the parent body is
world
.- Raises
RuntimeError iff called post-finalize. –
- set_contact_model(self: pydrake.multibody.plant.MultibodyPlant, model: pydrake.multibody.plant.ContactModel) None
Sets the contact model to be used by
this
MultibodyPlant, see ContactModel for available options. The default contact model is ContactModel::kHydroelasticWithFallback.- Raises
RuntimeError iff called post-finalize. –
- set_contact_surface_representation(self: pydrake.multibody.plant.MultibodyPlant, surface_representation: pydrake.geometry.HydroelasticContactRepresentation) None
Sets the representation of contact surfaces to be used by
this
MultibodyPlant. See geometry::HydroelasticContactRepresentation for available options. See GetDefaultContactSurfaceRepresentation() for explanation of default values.- Raises
RuntimeError if called post-finalize. –
- set_discrete_contact_approximation(self: pydrake.multibody.plant.MultibodyPlant, approximation: pydrake.multibody.plant.DiscreteContactApproximation) None
Sets the discrete contact model approximation.
Note
Calling this method also sets the contact solver type (see set_discrete_contact_solver()) according to: - DiscreteContactApproximation::kTamsi sets the solver to DiscreteContactSolver::kTamsi. - DiscreteContactApproximation::kSap, DiscreteContactApproximation::kSimilar and DiscreteContactApproximation::kLagged set the solver to DiscreteContactSolver::kSap.
- Raises
iff this plant is continuous (i.e. is_discrete() is –
False`. –
RuntimeError iff called post-finalize. –
- set_discrete_contact_solver(self: pydrake.multibody.plant.MultibodyPlant, contact_solver: pydrake.multibody.plant.DiscreteContactSolver) None
Sets the contact solver type used for discrete MultibodyPlant models.
Note
Calling this method also sets a default discrete approximation of contact (see set_discrete_contact_approximation()) according to: - DiscreteContactSolver::kTamsi sets the approximation to DiscreteContactApproximation::kTamsi. - DiscreteContactSolver::kSap sets the approximation to DiscreteContactApproximation::kSap.
Warning
This function is a no-op for continuous models (when is_discrete() is false.)
- Raises
RuntimeError iff called post-finalize. (Deprecated.) –
- Deprecated:
Use set_discrete_contact_approximation() to set the contact model approximation. The underlying solver will be inferred automatically. This will be removed from Drake on or after 2024-04-01.
- set_gravity_enabled(self: pydrake.multibody.plant.MultibodyPlant, model_instance: pydrake.multibody.tree.ModelInstanceIndex, is_enabled: bool) None
Sets is_gravity_enabled() for
model_instance
tois_enabled
. The effect ofis_enabled = false
is effectively equivalent to disabling (or making zero) gravity for all bodies in the specified model instance. By default is_gravity_enabled() equalsTrue
for all model instances.- Raises
RuntimeError if called post-finalize. –
RuntimeError if the model instance is invalid. –
- set_penetration_allowance(self: pydrake.multibody.plant.MultibodyPlant, penetration_allowance: float = 0.001) None
Sets the penetration allowance used to estimate the coefficients in the penalty method used to impose non-penetration among bodies. Refer to the section point_contact_defaults “Point Contact Default Parameters” for further details.
- Raises
RuntimeError if penetration_allowance is not positive. –
- set_sap_near_rigid_threshold(self: pydrake.multibody.plant.MultibodyPlant, near_rigid_threshold: float = 1.0) None
Non-negative dimensionless number typically in the range [0.0, 1.0], though larger values are allowed even if uncommon. This parameter controls the “near rigid” regime of the SAP solver, β in section V.B of [Castro et al., 2021]. It essentially controls a threshold value for the maximum amount of stiffness SAP can handle robustly. Beyond this value, stiffness saturates as explained in [Castro et al., 2021]. A value of 1.0 is a conservative choice to avoid ill-conditioning that might lead to softer than expected contact. If this is your case, consider turning off this approximation by setting this parameter to zero. For difficult cases where ill-conditioning is a problem, a small but non-zero number can be used, e.g. 1.0e-3.
- Raises
RuntimeError if near_rigid_threshold is negative. –
RuntimeError if called post-finalize. –
- set_stiction_tolerance(self: pydrake.multibody.plant.MultibodyPlant, v_stiction: float = 0.001) None
**** Stribeck model of friction
Currently MultibodyPlant uses the Stribeck approximation to model dry friction. The Stribeck model of friction is an approximation to Coulomb’s law of friction that allows using continuous time integration without the need to specify complementarity constraints. While this results in a simpler model immediately tractable with standard numerical methods for integration of ODE’s, it often leads to stiff dynamics that require an explicit integrator to take very small time steps. It is therefore recommended to use error controlled integrators when using this model or the discrete time stepping (see multibody_simulation). See stribeck_approximation for a detailed discussion of the Stribeck model.
Sets the stiction tolerance
v_stiction
for the Stribeck model, wherev_stiction
must be specified in m/s (meters per second.)v_stiction
defaults to a value of 1 millimeter per second. In selecting a value forv_stiction
, you must ask yourself the question, “When two objects are ostensibly in stiction, how much slip am I willing to allow?” There are two opposing design issues in picking a value for vₛ. On the one hand, small values of vₛ make the problem numerically stiff during stiction, potentially increasing the integration cost. On the other hand, it should be picked to be appropriate for the scale of the problem. For example, a car simulation could allow a “large” value for vₛ of 1 cm/s (1×10⁻² m/s), but reasonable stiction for grasping a 10 cm box might require limiting residual slip to 1×10⁻³ m/s or less. Ultimately, picking the largest viable value will allow your simulation to run faster and more robustly. Note thatv_stiction
is the slip velocity that we’d have when we are at edge of the friction cone. For cases when the friction force is well within the friction cone the slip velocity will always be smaller than this value. See also stribeck_approximation.- Raises
RuntimeError if v_stiction is non-positive. –
- SetActuationInArray(self: pydrake.multibody.plant.MultibodyPlant, model_instance: pydrake.multibody.tree.ModelInstanceIndex, u_instance: numpy.ndarray[numpy.float64[m, 1]], u: Optional[numpy.ndarray[numpy.float64[m, 1], flags.writeable]]) None
Given actuation values
u_instance
for the actuators inmodel_instance
, this function updates the actuation vector u for the entire plant model to which this actuator belongs to. Refer to mbp_actuation “Actuation” for further details.- Parameter
u_instance
: Actuation values for the model instance. Values are ordered by monotonically increasing JointActuatorIndex within the model instance.
- Parameter
u
: Actuation values for the entire plant model. The actuation value in
u
for a particular actuator must be found at offset JointActuator::input_start(). Only values corresponding tomodel_instance
are changed.
- Raises
RuntimeError if the size of u_instance is not equal to the –
number of actuation inputs for the joints of model_instance. –
- Parameter
- SetConstraintActiveStatus(self: pydrake.multibody.plant.MultibodyPlant, context: pydrake.systems.framework.Context, id: pydrake.multibody.tree.MultibodyConstraintId, status: bool) None
Sets the active status of the constraint given by
id
incontext
.- Raises
RuntimeError if the MultibodyPlant has not been finalized. –
RuntimeError if context == nullptr –
RuntimeError if id does not belong to any multibody constraint –
in context. –
- SetDefaultFreeBodyPose(*args, **kwargs)
Overloaded function.
SetDefaultFreeBodyPose(self: pydrake.multibody.plant.MultibodyPlant, body: pydrake.multibody.tree.RigidBody, X_PB: pydrake.math.RigidTransform) -> None
Sets the default pose of
body
. Ifbody.is_floating()
is true, this will affect subsequent calls to SetDefaultState(); otherwise, the only effect of the call is that the value will be echoed back in GetDefaultFreeBodyPose().Note
The parent frame is not necessarily the world frame. See mbp_working_with_free_bodies “above for details”.
- Parameter
body
: RigidBody whose default pose will be set.
- Parameter
X_PB
: Default pose of the body.
SetDefaultFreeBodyPose(self: pydrake.multibody.plant.MultibodyPlant, body: pydrake.multibody.tree.RigidBody, X_WB: pydrake.math.RigidTransform) -> None
Sets
context
to store the poseX_PB
of a givenbody
B in the parent frame P.Note
The parent frame is not necessarily the world frame. See mbp_working_with_free_bodies “above for details”.
- Raises
RuntimeError if body is not a free body in the model. –
RuntimeError if called pre-finalize. –
- SetDefaultPositions(*args, **kwargs)
Overloaded function.
SetDefaultPositions(self: pydrake.multibody.plant.MultibodyPlant, q: numpy.ndarray[numpy.float64[m, 1]]) -> None
Sets the default positions for the plant. Calls to CreateDefaultContext or SetDefaultContext/SetDefaultState will return a Context populated with these position values. They have no other effects on the dynamics of the system.
- Raises
RuntimeError if the plant is not finalized or if q is not of size –
num_positions() –
SetDefaultPositions(self: pydrake.multibody.plant.MultibodyPlant, model_instance: pydrake.multibody.tree.ModelInstanceIndex, q_instance: numpy.ndarray[numpy.float64[m, 1]]) -> None
Sets the default positions for the model instance. Calls to CreateDefaultContext or SetDefaultContext/SetDefaultState will return a Context populated with these position values. They have no other effects on the dynamics of the system.
- Raises
RuntimeError if the plant is not finalized, if the model_instance –
is invalid, or if the length of q_instance is not equal to –
num_positions(model_instance)` –
- SetDefaultState(self: pydrake.multibody.plant.MultibodyPlant, context: pydrake.systems.framework.Context, state: pydrake.systems.framework.State) None
Sets
state
according to defaults set by the user for joints (e.g. RevoluteJoint::set_default_angle()) and free bodies (SetDefaultFreeBodyPose()). If the user does not specify defaults, the state corresponds to zero generalized positions and velocities.- Raises
RuntimeError if called pre-finalize. See Finalize() –
- SetFreeBodyPose(*args, **kwargs)
Overloaded function.
SetFreeBodyPose(self: pydrake.multibody.plant.MultibodyPlant, context: pydrake.systems.framework.Context, body: pydrake.multibody.tree.RigidBody, X_PB: pydrake.math.RigidTransform) -> None
Sets
context
to store the poseX_PB
of a givenbody
B in the parent frame P.Note
The parent frame is not necessarily the world frame. See mbp_working_with_free_bodies “above for details”.
- Raises
RuntimeError if body is not a free body in the model. –
RuntimeError if called pre-finalize. –
SetFreeBodyPose(self: pydrake.multibody.plant.MultibodyPlant, context: pydrake.systems.framework.Context, body: pydrake.multibody.tree.RigidBody, X_WB: pydrake.math.RigidTransform) -> None
Sets
context
to store the poseX_PB
of a givenbody
B in the parent frame P.Note
The parent frame is not necessarily the world frame. See mbp_working_with_free_bodies “above for details”.
- Raises
RuntimeError if body is not a free body in the model. –
RuntimeError if called pre-finalize. –
- SetFreeBodySpatialVelocity(*args, **kwargs)
Overloaded function.
SetFreeBodySpatialVelocity(self: pydrake.multibody.plant.MultibodyPlant, body: pydrake.multibody.tree.RigidBody, V_PB: pydrake.multibody.math.SpatialVelocity, context: pydrake.systems.framework.Context) -> None
Sets
context
to store the spatial velocityV_PB
of a givenbody
B in its parent frame P.Note
The parent frame is not necessarily the world frame. See mbp_working_with_free_bodies “above for details”.
- Raises
RuntimeError if body is not a free body in the model. –
RuntimeError if called pre-finalize. –
SetFreeBodySpatialVelocity(self: pydrake.multibody.plant.MultibodyPlant, body: pydrake.multibody.tree.RigidBody, V_WB: pydrake.multibody.math.SpatialVelocity, context: pydrake.systems.framework.Context) -> None
Sets
context
to store the spatial velocityV_PB
of a givenbody
B in its parent frame P.Note
The parent frame is not necessarily the world frame. See mbp_working_with_free_bodies “above for details”.
- Raises
RuntimeError if body is not a free body in the model. –
RuntimeError if called pre-finalize. –
- SetPositions(*args, **kwargs)
Overloaded function.
SetPositions(self: pydrake.multibody.plant.MultibodyPlant, context: pydrake.systems.framework.Context, q: numpy.ndarray[numpy.float64[m, 1]]) -> None
Sets the generalized positions q in a given Context from a given vector. Prefer this method over GetMutablePositions().
- Raises
RuntimeError if context is nullptr, if context does not –
correspond to the Context for a multibody model, or if the length –
of q is not equal to num_positions() –
SetPositions(self: pydrake.multibody.plant.MultibodyPlant, context: pydrake.systems.framework.Context, model_instance: pydrake.multibody.tree.ModelInstanceIndex, q: numpy.ndarray[numpy.float64[m, 1]]) -> None
Sets the generalized positions q in a given Context from a given vector. Prefer this method over GetMutablePositions().
- Raises
RuntimeError if context is nullptr, if context does not –
correspond to the Context for a multibody model, or if the length –
of q is not equal to num_positions() –
- SetPositionsAndVelocities(*args, **kwargs)
Overloaded function.
SetPositionsAndVelocities(self: pydrake.multibody.plant.MultibodyPlant, context: pydrake.systems.framework.Context, q_v: numpy.ndarray[numpy.float64[m, 1]]) -> None
Sets generalized positions q and generalized velocities v in a given Context from a given vector [q; v]. Prefer this method over GetMutablePositionsAndVelocities().
- Raises
RuntimeError if context is nullptr, if context does not –
correspond to the context for a multibody model, or if the length –
of q_v is not equal to num_positions() + num_velocities() –
SetPositionsAndVelocities(self: pydrake.multibody.plant.MultibodyPlant, context: pydrake.systems.framework.Context, model_instance: pydrake.multibody.tree.ModelInstanceIndex, q_v: numpy.ndarray[numpy.float64[m, 1]]) -> None
Sets generalized positions q and generalized velocities v from a given vector [q; v] for a specified model instance in a given Context.
- Raises
RuntimeError if context is nullptr, if context does not –
correspond to the Context for a multibody model, if the model –
instance index is invalid, or if the length of q_v is not –
equal to ``num_positions(model_instance) + –
num_velocities(model_instance)``. –
- SetPositionsInArray(self: pydrake.multibody.plant.MultibodyPlant, model_instance: pydrake.multibody.tree.ModelInstanceIndex, q_instance: numpy.ndarray[numpy.float64[m, 1]], q: Optional[numpy.ndarray[numpy.float64[m, 1], flags.writeable]]) None
Sets the vector of generalized positions for
model_instance
inq
usingq_instance
, leaving all other elements in the array untouched. This method throws an exception ifq
is not of size MultibodyPlant::num_positions() orq_instance
is not of sizeMultibodyPlant::num_positions(model_instance)
.
- SetUseSampledOutputPorts(self: pydrake.multibody.plant.MultibodyPlant, use_sampled_output_ports: bool) None
(Advanced) For a discrete-time plant, configures whether the output ports are sampled (the default) or live (opt-in). See output_port_sampling “Output port sampling” for details.
- Raises
RuntimeError if the plant is already finalized. –
RuntimeError if use_sampled_output_ports is True but –
this` MultibodyPlant is not a discrete model (is_discrete() = –
false) –
- SetVelocities(*args, **kwargs)
Overloaded function.
SetVelocities(self: pydrake.multibody.plant.MultibodyPlant, context: pydrake.systems.framework.Context, v: numpy.ndarray[numpy.float64[m, 1]]) -> None
Sets the generalized velocities v in a given Context from a given vector. Prefer this method over GetMutableVelocities().
- Raises
RuntimeError if the context is nullptr, if the context does –
not correspond to the context for a multibody model, or if the –
length of v is not equal to num_velocities() –
SetVelocities(self: pydrake.multibody.plant.MultibodyPlant, context: pydrake.systems.framework.Context, model_instance: pydrake.multibody.tree.ModelInstanceIndex, v: numpy.ndarray[numpy.float64[m, 1]]) -> None
Sets the generalized velocities v for a particular model instance in a given Context from a given vector.
- Raises
RuntimeError if the context is nullptr, if context does –
not correspond to the Context for a multibody model, if the model –
instance index is invalid, or if the length of v_instance is –
not equal to num_velocities(model_instance) –
- SetVelocitiesInArray(self: pydrake.multibody.plant.MultibodyPlant, model_instance: pydrake.multibody.tree.ModelInstanceIndex, v_instance: numpy.ndarray[numpy.float64[m, 1]], v: Optional[numpy.ndarray[numpy.float64[m, 1], flags.writeable]]) None
Sets the vector of generalized velocities for
model_instance
inv
usingv_instance
, leaving all other elements in the array untouched. This method throws an exception ifv
is not of size MultibodyPlant::num_velocities() orv_instance
is not of sizeMultibodyPlant::num_positions(model_instance)
.
- time_step(self: pydrake.multibody.plant.MultibodyPlant) float
The time step (or period) used to model
this
plant as a discrete system with periodic updates. Returns 0 (zero) if the plant is modeled as a continuous system. This property of the plant is specified at construction and therefore this query can be performed either pre- or post-finalize, see Finalize().See also
MultibodyPlant::MultibodyPlant(double)
- WeldFrames(self: pydrake.multibody.plant.MultibodyPlant, frame_on_parent_F: pydrake.multibody.tree.Frame, frame_on_child_M: pydrake.multibody.tree.Frame, X_FM: pydrake.math.RigidTransform = RigidTransform(R=RotationMatrix([[1.0, 0.0, 0.0], [0.0, 1.0, 0.0], [0.0, 0.0, 1.0]]), p=[0.0, 0.0, 0.0])) pydrake.multibody.tree.WeldJoint
Welds
frame_on_parent_F
andframe_on_child_M
with relative poseX_FM
. That is, the pose of frame M in frame F is fixed, with valueX_FM
. IfX_FM
is omitted, the identity transform will be used. The call to this method creates and adds a new WeldJoint to the model. The new WeldJoint is named as: frame_on_parent_F.name() + “_welds_to_” + frame_on_child_M.name().- Returns
a constant reference to the WeldJoint welding frames F and M.
- Raises
RuntimeError if the weld produces a duplicate joint name. –
- world_body(self: pydrake.multibody.plant.MultibodyPlant) pydrake.multibody.tree.RigidBody
Returns a constant reference to the world body.
- world_frame(self: pydrake.multibody.plant.MultibodyPlant) pydrake.multibody.tree.RigidBodyFrame
Returns a constant reference to the world frame.
- template pydrake.multibody.plant.MultibodyPlant_
Instantiations:
MultibodyPlant_[float]
,MultibodyPlant_[AutoDiffXd]
,MultibodyPlant_[Expression]
- class pydrake.multibody.plant.MultibodyPlant_[AutoDiffXd]
Bases:
pydrake.systems.framework.LeafSystem_[AutoDiffXd]
MultibodyPlant is a Drake system framework representation (see systems::System) for the model of a physical system consisting of a collection of interconnected bodies. See multibody for an overview of concepts/notation.
actuation→ applied_generalized_force→ applied_spatial_force→ model_instance_name[i]_actuation→ model_instance_name[i]_desired_state→ geometry_query→ MultibodyPlant → state → body_poses → body_spatial_velocities → body_spatial_accelerations → generalized_acceleration → net_actuation → reaction_forces → contact_results → model_instance_name[i]_state → model_instance_name[i]_generalized_acceleration → model_instance_name[i]_generalized_contact_forces → model_instance_name[i]_net_actuation → geometry_pose → deformable_body_configuration The ports whose names begin with <em style=”color:gray”> model_instance_name[i]</em> represent groups of ports, one for each of the model_instances “model instances”, with i ∈ {0, …, N-1} for the N model instances. If a model instance does not contain any data of the indicated type the port will still be present but its value will be a zero-length vector. (Model instances
world_model_instance()
anddefault_model_instance()
always exist.)The ports shown in <span style=”color:green”>green</span> are for communication with Drake’s geometry::SceneGraph “SceneGraph” system for dealing with geometry.
MultibodyPlant provides a user-facing API for:
mbp_input_and_output_ports “Ports”:
Access input and output ports. - mbp_construction “Construction”: Add bodies, joints, frames, force elements, and actuators. - mbp_geometry “Geometry”: Register geometries to a provided SceneGraph instance. - mbp_contact_modeling “Contact modeling”: Select and parameterize contact models. - mbp_state_accessors_and_mutators “State access and modification”: Obtain and manipulate position and velocity state variables. - mbp_parameters “Parameters” Working with system parameters for various multibody elements. - mbp_working_with_free_bodies “Free bodies”: Work conveniently with free (floating) bodies. - mbp_kinematic_and_dynamic_computations “Kinematics and dynamics”: Perform systems::Context “Context”-dependent kinematic and dynamic queries. - mbp_system_matrix_computations “System matrices”: Explicitly form matrices that appear in the equations of motion. - mbp_introspection “Introspection”: Perform introspection to find out what’s in the MultibodyPlant.
**** Model Instances
A MultiBodyPlant may contain multiple model instances. Each model instance corresponds to a set of bodies and their connections (joints). Model instances provide methods to get or set the state of the set of bodies (e.g., through GetPositionsAndVelocities() and SetPositionsAndVelocities()), connecting controllers (through get_state_output_port() and get_actuation_input_port()), and organizing duplicate models (read through a parser). In fact, many MultibodyPlant methods are overloaded to allow operating on the entire plant or just the subset corresponding to the model instance; for example, one GetPositions() method obtains the generalized positions for the entire plant while another GetPositions() method obtains the generalized positions for model instance.
Model instances are frequently defined through SDFormat files (using the
model
tag) and are automatically created when SDFormat files are parsed (by Parser). There are two special multibody::ModelInstanceIndex values. The world body is always multibody::ModelInstanceIndex 0. multibody::ModelInstanceIndex 1 is reserved for all elements with no explicit model instance and is generally only relevant for elements created programmatically (and only when a model instance is not explicitly specified). Note that Parser creates model instances (resulting in a multibody::ModelInstanceIndex ≥ 2) as needed.See num_model_instances(), num_positions(), num_velocities(), num_actuated_dofs(), AddModelInstance() GetPositionsAndVelocities(), GetPositions(), GetVelocities(), SetPositionsAndVelocities(), SetPositions(), SetVelocities(), GetPositionsFromArray(), GetVelocitiesFromArray(), SetPositionsInArray(), SetVelocitiesInArray(), SetActuationInArray(), HasModelInstanceNamed(), GetModelInstanceName(), get_state_output_port(), get_actuation_input_port().
**** System dynamics
The state of a multibody system
x = [q; v]
is given by its generalized positions vector q, of sizenq
(see num_positions()), and by its generalized velocities vector v, of sizenv
(see num_velocities()).A MultibodyPlant can be constructed to be either continuous or discrete. The choice is indicated by the time_step passed to the constructor – a non-zero time_step indicates a discrete plant, while a zero time_step indicates continuous. A systems::Simulator “Simulator” will step a discrete plant using the indicated time_step, but will allow a numerical integrator to choose how to advance time for a continuous MultibodyPlant.
We’ll discuss continuous plant dynamics in this section. Discrete dynamics is more complicated and gets its own section below.
As a Drake systems::System “System”, MultibodyPlant implements the governing equations for a multibody dynamical system in the form
ẋ = f(t, x, u)
with t being time and u external inputs such as actuation forces. The governing equations for the dynamics of a multibody system modeled with MultibodyPlant are [Featherstone 2008, Jain 2010]:Click to expand C++ code...
q̇ = N(q)v (1) M(q)v̇ + C(q, v)v = τ
where
M(q)
is the mass matrix of the multibody system (including rigid body mass properties and reflected_inertia “reflected inertias”),C(q, v)v
contains Coriolis, centripetal, and gyroscopic terms andN(q)
is the kinematic coupling matrix describing the relationship between q̇ (the time derivatives of the generalized positions) and the generalized velocities v, [Seth 2010].N(q)
is annq x nv
matrix. The vectorτ ∈ ℝⁿᵛ
on the right hand side of Eq. (1) is the system’s generalized forces. These incorporate gravity, springs, externally applied body forces, constraint forces, and contact forces.**** Discrete system dynamics
We’ll start with the basic difference equation interpretation of a discrete plant and then explain some Drake-specific subtleties.
Note
We use “kinematics” here to refer to quantities that involve only position or velocity, and “dynamics” to refer to quantities that also involve forces.
By default, a discrete MultibodyPlant has these update dynamics:
x[0] = initial kinematics state variables x (={q, v}), s s[0] = empty (no sample yet)
s[n+1] = g(t[n], x[n], u[n]) record sample x[n+1] = f(t[n], x[n], u[n]) update kinematics yd[n+1] = gd(s) dynamic outputs use sampled values yk[n+1] = gk(x) kinematic outputs use current x
Optionally, output port sampling can be disabled. In that case we have:
x[n+1] = f(t[n], x[n], u[n]) update kinematics yd[n+1] = gd(g(t, x, u)) dynamic outputs use current values yk[n+1] = gk(x) kinematic outputs use current x
We’re using
yd
andyk
above to represent the calculated values of dynamic and kinematic output ports, resp. Kinematic output ports are those that depend only on position and velocity:state
, body_poses,body_spatial_velocities
. Everything else depends on forces so is a dynamic output port:body_spatial_accelerations
, generalized_acceleration,net_actuation
, reaction_forces, andcontact_results
.Use the function SetUseSampledOutputPorts() to choose which dynamics you prefer. The default behavior (output port sampling) is more efficient for simulation, but use slightly-different kinematics for the dynamic output port computations versus the kinematic output ports. Disabling output port sampling provides “live” output port results that are recalculated from the current state and inputs whenever changes occur. It also eliminates the sampling state variable (s above). Note that kinematic output ports (that is, those depending only on position and velocity) are always “live” – they are calculated as needed from the current (updated) state.
The reason that the default mode is more efficient for simulation is that the sample variable s records expensive-to-compute results (such as hydroelastic contact forces) that are needed to advance the state x. Those results are thus available for free at the start of step n. If instead we wait until after the state is updated to n+1, we would have to recalculate those expensive results at the new state in order to report them. Thus sampling means the output ports show the results that were calculated using kinematics values x[n], although the Context has been updated to kinematics values x[n+1]. If that isn’t tolerable you should disable output port sampling. You can also force an update to occur using ExecuteForcedEvents().
See output_port_sampling “Output port sampling” below for more practical considerations.
Minor details most users won’t care about:
The sample variable s is a Drake Abstract state variable. When it is
present, the plant update is performed using an Unrestricted update; when it is absent we are able to use a Discrete update. Some Drake features (e.g. linearization of discrete systems) may be restricted to systems that use only Discrete (numeric) state variables and Discrete update. - The sample variable s is used only by output ports. It does not affect the behavior of any MultibodyPlant “Calc” or “Eval” functions – those are always calculated using the current values of time, kinematic state, and input port values.
**** Output port sampling
As described in mbp_discrete_dynamics “Discrete system dynamics” above, the semantics of certain MultibodyPlant output ports depends on whether the plant is configured to advance using continuous time integration or discrete time steps (see is_discrete()). This section explains the details, focusing on the practical aspects moreso than the equations.
Output ports that only depend on the [q, v] kinematic state (such as get_body_poses_output_port() or get_body_spatial_velocities_output_port()) do not change semantics for continuous vs discrete time. In all cases, the output value is a function of the kinematic state in the context.
Output ports that incorporate dynamics (i.e., forces) do change semantics based on the plant mode. Imagine that the get_applied_spatial_force_input_port() provides a continuously time-varying input force. The get_body_spatial_accelerations_output_port() output is dependent on that force. We could return a snapshot of the acceleration that was used in the last time step, or we could recalculate the acceleration to immediately reflect the changing forces. We call the former a “sampled” port and the latter a “live” port.
For a continuous-time plant, there is no distinction – the output port is always live – it immediately reflects the instantaneous input value. It is a “direct feedthrough” output port (see SystemBase::GetDirectFeedthroughs()).
For a discrete-time plant, the user can choose whether the output should be sampled or live: Use the function SetUseSampledOutputPorts() to change whether output ports are sampled or not, and has_sampled_output_ports() to check the current setting. When sampling is disabled, the only state in the context is the kinematic [q, v], so dynamics output ports will always reflect the instantaneous answer (i.e., direct feedthrough). When sampling is enabled (the default), the plant state incorporates a snapshot of the most recent step’s kinematics and dynamics, and the output ports will reflect that sampled state (i.e., not direct feedthrough). For a detailed discussion, see mbp_discrete_dynamics “Discrete system dynamics”.
For a discrete-time plant, the sampled outputs are generally much faster to calculate than the feedthrough outputs when any inputs ports are changing values faster than the discrete time step, e.g., during a simulation. When input ports are fixed, or change at the time step rate (e.g., during motion planning), sampled vs feedthrough will have similar computational performance.
Direct plant API function calls (e.g., EvalBodySpatialAccelerationInWorld()) that depend on forces always use the instantaneous (not sampled) accelerations.
Here are some practical tips that might help inform your particular situation:
(1) If you need a minimal-state representation for motion planning, mathematical optimization, or similar, then you can either use a continuous-time plant or set the config option
use_sampled_output_ports=false
on a discrete-time plant.(2) By default, setting the positions of a discrete-time plant in the Context will not have any effect on the dynamics-related output ports, e.g., the contact results will not change. If you need to see changes to outputs without running the plant in a Simulator, then you can either use a continuous-time plant, set the config option
use_sampled_output_ports=false
, or use ExecuteForcedEvents() to force a dynamics step and then the outputs (and positions) will change.**** Actuation
In a MultibodyPlant model an actuator can be added as a JointActuator, see AddJointActuator(). The plant declares actuation input ports to provide feedforward actuation, both for the MultibodyPlant as a whole (see get_actuation_input_port()) and for each individual model_instances “model instance” in the MultibodyPlant (see get_actuation_input_port(ModelInstanceIndex)const “get_actuation_input_port(ModelInstanceIndex)”). Any actuation input ports not connected are assumed to be zero. Actuation values from the full MultibodyPlant model port (get_actuation_input_port()) and from the per model-instance ports ( get_actuation_input_port(ModelInstanceIndex)const “get_actuation_input_port(ModelInstanceIndex)”) are summed up.
Note
A JointActuator’s index into the vector data supplied to MultibodyPlant’s actuation input port for all actuators (get_actuation_input_port()) is given by JointActuator::input_start(), NOT by its JointActuatorIndex. That is, the vector element data for a JointActuator at index JointActuatorIndex(i) in the full input port vector is found at index: MultibodyPlant::get_joint_actuator(JointActuatorIndex(i)).input_start(). For the get_actuation_input_port(ModelInstanceIndex)const “get_actuation_input_port(ModelInstanceIndex)” specific to a model index, the vector data is ordered by monotonically increasing JointActuatorIndex for the actuators within that model instance: the 0ᵗʰ vector element corresponds to the lowest-numbered JointActuatorIndex of that instance, the 1ˢᵗ vector element corresponds to the second-lowest-numbered JointActuatorIndex of that instance, etc.
Note
The following snippet shows how per model instance actuation can be set:
Click to expand C++ code...
ModelInstanceIndex model_instance_index = ...; VectorX<T> u_instance(plant.num_actuated_dofs(model_instance_index)); int offset = 0; for (JointActuatorIndex joint_actuator_index : plant.GetJointActuatorIndices(model_instance_index)) { const JointActuator<T>& actuator = plant.get_joint_actuator( joint_actuator_index); const Joint<T>& joint = actuator.joint(); VectorX<T> u_joint = ... my_actuation_logic_for(joint) ...; ASSERT(u_joint.size() == joint_actuator.num_inputs()); u_instance.segment(offset, u_joint.size()) = u_joint; offset += u_joint.size(); } plant.get_actuation_input_port(model_instance_index).FixValue( plant_context, u_instance);
Note
To inter-operate between the whole plant actuation vector and sets of per-model instance actuation vectors, see SetActuationInArray() to gather the model instance vectors into a whole plant vector and GetActuationFromArray() to scatter the whole plant vector into per-model instance vectors.
Warning
Effort limits (JointActuator::effort_limit()) are not enforced, unless PD controllers are defined. See pd_controllers “Using PD controlled actuators”.
** Using PD controlled actuators
While PD controllers can be modeled externally and be connected to the MultibodyPlant model via the get_actuation_input_port(), simulation stability at discrete-time steps can be compromised for high controller gains. For such cases, simulation stability and robustness can be improved significantly by moving your PD controller into the plant where the discrete solver can strongly couple controller and model dynamics.
Warning
Currently, this feature is only supported for discrete models (is_discrete() is true) using the SAP solver (get_discrete_contact_solver() returns DiscreteContactSolver::kSap.)
PD controlled joint actuators can be defined by setting PD gains for each joint actuator, see JointActuator::set_controller_gains(). Unless these gains are specified, joint actuators will not be PD controlled and JointActuator::has_controller() will return
False
.Warning
For PD controlled models, all joint actuators in a model instance are required to have PD controllers defined. That is, partially PD controlled model instances are not supported. An exception will be thrown when evaluating the actuation input ports if only a subset of the actuators in a model instance is PD controlled.
For models with PD controllers, the actuation torque per actuator is computed according to:
Click to expand C++ code...
ũ = -Kp⋅(q − qd) - Kd⋅(v − vd) + u_ff u = max(−e, min(e, ũ))
where qd and vd are desired configuration and velocity (see get_desired_state_input_port()) for the actuated joint (see JointActuator::joint()), Kp and Kd are the proportional and derivative gains of the actuator (see JointActuator::get_controller_gains()),
u_ff
is the feed-forward actuation specified with get_actuation_input_port(), ande
corresponds to effort limit (see JointActuator::effort_limit()).Notice that actuation through get_actuation_input_port() and PD control are not mutually exclusive, and they can be used together. This is better explained through examples: 1. PD controlled gripper. In this case, only PD control is used to drive the opening and closing of the fingers. The feed-forward term is assumed to be zero and the actuation input port is not required to be connected. 2. Robot arm. A typical configuration consists on applying gravity compensation in the feed-forward term plus PD control to drive the robot to a given desired state.
** Actuation input ports requirements
The following table specifies whether actuation ports are required to be connected or not:
Port | without PD control | with PD control | |- ——————————
- :——————-: |
- ————-
- | get_actuation_input_port() | yes | no¹ | |
get_desired_state_input_port() | no² | yes |
¹ Feed-forward actuation is not required for models with PD controlled actuators. This simplifies the diagram wiring for models that only rely on PD controllers.
² This port is always declared, though it will be zero sized for model instances with no PD controllers.
** Net actuation
The total joint actuation applied via the actuation input port (get_actuation_input_port()) and applied by the PD controllers is reported by the net actuation port (get_net_actuation_output_port()). That is, the net actuation port reports the total actuation applied by a given actuator.
Note
PD controllers are ignored when a joint is locked (see Joint::Lock()), and thus they have no effect on the actuation output.
**** Loading models from SDFormat files
Drake has the capability to load multibody models from SDFormat and URDF files. Consider the example below which loads an acrobot model:
Click to expand C++ code...
MultibodyPlant<T> acrobot; SceneGraph<T> scene_graph; Parser parser(&acrobot, &scene_graph); const std::string url = "package://drake/multibody/benchmarks/acrobot/acrobot.sdf"; parser.AddModelsFromUrl(url);
As in the example above, for models including visual geometry, collision geometry or both, the user must specify a SceneGraph for geometry handling. You can find a full example of the LQR controlled acrobot in examples/multibody/acrobot/run_lqr.cc.
AddModelFromFile() can be invoked multiple times on the same plant in order to load multiple model instances. Other methods are available on Parser such as AddModels() which allows creating model instances per each
<model>
tag found in the file. Please refer to each of these methods’ documentation for further details.**** Working with SceneGraph
** Adding a MultibodyPlant connected to a SceneGraph to your Diagram
Probably the simplest way to add and wire up a MultibodyPlant with a SceneGraph in your Diagram is using AddMultibodyPlantSceneGraph().
Recommended usages:
Assign to a MultibodyPlant reference (ignoring the SceneGraph):
Click to expand C++ code...
MultibodyPlant<double>& plant = AddMultibodyPlantSceneGraph(&builder, 0.0 /+ time_step +/); plant.DoFoo(...);
This flavor is the simplest, when the SceneGraph is not explicitly needed. (It can always be retrieved later via GetSubsystemByName(“scene_graph”).)
Assign to auto, and use the named public fields:
Click to expand C++ code...
auto items = AddMultibodyPlantSceneGraph(&builder, 0.0 /+ time_step +/); items.plant.DoFoo(...); items.scene_graph.DoBar(...);
or taking advantage of C++’s structured binding:
Click to expand C++ code...
auto [plant, scene_graph] = AddMultibodyPlantSceneGraph(&builder, 0.0); ... plant.DoFoo(...); scene_graph.DoBar(...);
This is the easiest way to use both the plant and scene_graph.
Assign to already-declared pointer variables:
Click to expand C++ code...
MultibodyPlant<double>* plant{}; SceneGraph<double>* scene_graph{}; std::tie(plant, scene_graph) = AddMultibodyPlantSceneGraph(&builder, 0.0 /+ time_step +/); plant->DoFoo(...); scene_graph->DoBar(...);
This flavor is most useful when the pointers are class member fields (and so perhaps cannot be references).
** Registering geometry with a SceneGraph
MultibodyPlant users can register geometry with a SceneGraph for essentially two purposes; a) visualization and, b) contact modeling.
Before any geometry registration takes place, a user must first make a call to RegisterAsSourceForSceneGraph() in order to register the MultibodyPlant as a client of a SceneGraph instance, point at which the plant will have assigned a valid geometry::SourceId. At Finalize(), MultibodyPlant will declare input/output ports as appropriate to communicate with the SceneGraph instance on which registrations took place. All geometry registration must be performed pre-finalize.
Multibodyplant declares an input port for geometric queries, see get_geometry_query_input_port(). If MultibodyPlant registers geometry with a SceneGraph via calls to RegisterCollisionGeometry(), users may use this port for geometric queries. The port must be connected to the same SceneGraph used for registration. The preferred mechanism is to use AddMultibodyPlantSceneGraph() as documented above.
In extraordinary circumstances, this can be done by hand and the setup process will include:
Call to RegisterAsSourceForSceneGraph().
Calls to RegisterCollisionGeometry(), as many as needed.
Call to Finalize(), user is done specifying the model.
4. Connect geometry::SceneGraph::get_query_output_port() to get_geometry_query_input_port(). 5. Connect get_geometry_pose_output_port() to geometry::SceneGraph::get_source_pose_port()
Refer to the documentation provided in each of the methods above for further details.
** Accessing point contact parameters MultibodyPlant’s point contact model looks for model parameters stored as geometry::ProximityProperties by geometry::SceneGraph. These properties can be obtained before or after context creation through geometry::SceneGraphInspector APIs as outlined below. MultibodyPlant expects the following properties for point contact modeling:
|Group name|Property Name|Required|Property Type|Property Description| |:--------:|:———–:|:------:|:—————-:|:-------------------| |material|coulomb_friction|yes¹|CoulombFriction<T>|Static and Dynamic friction.| |material|point_contact_stiffness|no²|T| Compliant point contact stiffness.| |material|hunt_crossley_dissipation |no²⁴|T| Compliant contact dissipation.| |material|relaxation_time|yes³⁴|T|Linear Kelvin–Voigt model parameter.|
¹ Collision geometry is required to be registered with a geometry::ProximityProperties object that contains the (“material”, “coulomb_friction”) property. If the property is missing, MultibodyPlant will throw an exception.
² If the property is missing, MultibodyPlant will use a heuristic value as the default. Refer to the section point_contact_defaults “Point Contact Default Parameters” for further details.
³ When using a linear Kelvin–Voigt model of dissipation (for instance when selecting the SAP solver), collision geometry is required to be registered with a geometry::ProximityProperties object that contains the (“material”, “relaxation_time”) property. If the property is missing, an exception will be thrown.
⁴ We allow to specify both hunt_crossley_dissipation and relaxation_time for a given geometry. However only one of these will get used, depending on the configuration of the MultibodyPlant. As an example, if the SAP contact approximation is specified (see set_discrete_contact_approximation()) only the relaxation_time is used while hunt_crossley_dissipation is ignored. Conversely, if the TAMSI, Similar or Lagged approximation is used (see set_discrete_contact_approximation()) only hunt_crossley_dissipation is used while relaxation_time is ignored. Currently, a continuous MultibodyPlant model will always use the Hunt & Crossley model and relaxation_time will be ignored.
Accessing and modifying contact properties requires interfacing with geometry::SceneGraph’s model inspector. Interfacing with a model inspector obtained from geometry::SceneGraph will provide the default registered values for a given parameter. These are the values that will initially appear in a systems::Context created by CreateDefaultContext(). Subsequently, true system parameters can be accessed and changed through a systems::Context once available. For both of the above cases, proximity properties are accessed through geometry::SceneGraphInspector APIs.
Before context creation an inspector can be retrieved directly from SceneGraph as:
Click to expand C++ code...
// For a SceneGraph<T> instance called scene_graph. const geometry::SceneGraphInspector<T>& inspector = scene_graph.model_inspector();
After context creation, an inspector can be retrieved from the state stored in the context:
Click to expand C++ code...
// For a MultibodyPlant<T> instance called mbp and a Context<T> called // context. const geometry::SceneGraphInspector<T>& inspector = mbp.EvalSceneGraphInspector(context);
Once an inspector is available, proximity properties can be retrieved as:
Click to expand C++ code...
// For a body with GeometryId called geometry_id const geometry::ProximityProperties* props = inspector.GetProximityProperties(geometry_id); const CoulombFriction<T>& geometry_friction = props->GetProperty<CoulombFriction<T>>("material", "coulomb_friction");
**** Working with MultibodyElement parameters Several MultibodyElements expose parameters, allowing the user flexible modification of some aspects of the plant’s model, post systems::Context creation. For details, refer to the documentation for the MultibodyElement whose parameters you are trying to modify/access (e.g. RigidBody, FixedOffsetFrame, etc.)
As an example, here is how to access and modify rigid body mass parameters:
Click to expand C++ code...
MultibodyPlant<double> plant; // ... Code to add bodies, finalize plant, and to obtain a context. const RigidBody<double>& body = plant.GetRigidBodyByName("BodyName"); const SpatialInertia<double> M_BBo_B = body.GetSpatialInertiaInBodyFrame(context); // .. logic to determine a new SpatialInertia parameter for body. const SpatialInertia<double>& M_BBo_B_new = .... // Modify the body parameter for spatial inertia. body.SetSpatialInertiaInBodyFrame(&context, M_BBo_B_new);
Another example, working with automatic differentiation in order to take derivatives with respect to one of the bodies’ masses:
Click to expand C++ code...
MultibodyPlant<double> plant; // ... Code to add bodies, finalize plant, and to obtain a // context and a body's spatial inertia M_BBo_B. // Scalar convert the plant. unique_ptr<MultibodyPlant<AutoDiffXd>> plant_autodiff = systems::System<double>::ToAutoDiffXd(plant); unique_ptr<Context<AutoDiffXd>> context_autodiff = plant_autodiff->CreateDefaultContext(); context_autodiff->SetTimeStateAndParametersFrom(context); const RigidBody<AutoDiffXd>& body = plant_autodiff->GetRigidBodyByName("BodyName"); // Modify the body parameter for mass. const AutoDiffXd mass_autodiff(mass, Vector1d(1)); body.SetMass(context_autodiff.get(), mass_autodiff); // M_autodiff(i, j).derivatives()(0), contains the derivatives of // M(i, j) with respect to the body's mass. MatrixX<AutoDiffXd> M_autodiff(plant_autodiff->num_velocities(), plant_autodiff->num_velocities()); plant_autodiff->CalcMassMatrix(*context_autodiff, &M_autodiff);
**** Adding modeling elements
Add multibody elements to a MultibodyPlant with methods like:
Bodies: AddRigidBody()
Joints: AddJoint()
see mbp_construction “Construction” for more.
All modeling elements must be added before Finalize() is called. See mbp_finalize_stage “Finalize stage” for a discussion.
**** Modeling contact
Please refer to drake_contacts “Contact Modeling in Drake” for details on the available approximations, setup, and considerations for a multibody simulation with frictional contact.
**** Energy and Power
MultibodyPlant implements the System energy and power methods, with some limitations. - Kinetic energy: fully implemented. - Potential energy and conservative power: currently include only gravity and contributions from ForceElement objects; potential energy from compliant contact and joint limits are not included. - Nonconservative power: currently includes only contributions from ForceElement objects; actuation and input port forces, joint damping, and dissipation from joint limits, friction, and contact dissipation are not included.
See Drake issue #12942 for more discussion.
**** Finalize() stage
Once the user is done adding modeling elements and registering geometry, a call to Finalize() must be performed. This call will: - Build the underlying tree structure of the multibody model, - declare the plant’s state, - declare the plant’s input and output ports, - declare collision filters to ignore collisions among rigid bodies: - between rigid bodies connected by a joint, - within subgraphs of welded rigid bodies. Note that MultibodyPlant will not introduce any collision filters on deformable bodies.
**** References
[Featherstone 2008] Featherstone, R., 2008.
Rigid body dynamics algorithms. Springer. - [Jain 2010] Jain, A., 2010. Robot and multibody dynamics: analysis and algorithms. Springer Science & Business Media. - [Seth 2010] Seth, A., Sherman, M., Eastman, P. and Delp, S., 2010. Minimal formulation of joint motion for biomechanisms. Nonlinear dynamics, 62(1), pp.291-303.
- __init__(self: pydrake.multibody.plant.MultibodyPlant_[AutoDiffXd], time_step: float) None
This constructor creates a plant with a single “world” body. Therefore, right after creation, num_bodies() returns one.
MultibodyPlant offers two different modalities to model mechanical systems in time. These are: 1. As a discrete system with periodic updates,
time_step
is strictly greater than zero. 2. As a continuous system,time_step
equals exactly zero.Currently the discrete model is preferred for simulation given its robustness and speed in problems with frictional contact. However this might change as we work towards developing better strategies to model contact. See multibody_simulation for further details.
Warning
Users should be aware of current limitations in either modeling modality. While the discrete model is often the preferred option for problems with frictional contact given its robustness and speed, it might become unstable when using large feedback gains, high damping or large external forcing. MultibodyPlant will throw an exception whenever the discrete solver is detected to fail. Conversely, the continuous modality has the potential to leverage the robustness and accuracy control provide by Drake’s integrators. However thus far this has proved difficult in practice and especially due to poor performance.
- Parameter
time_step
: Indicates whether
this
plant is modeled as a continuous system (time_step = 0
) or as a discrete system with periodic updates of periodtime_step > 0
. See multibody_simulation for further details.
Warning
Currently the continuous modality with
time_step = 0
does not support joint limits for simulation, these are ignored. MultibodyPlant prints a warning to console if joint limits are provided. If your simulation requires joint limits currently you must use a discrete MultibodyPlant model.- Raises
RuntimeError if time_step is negative. –
- Parameter
- AddBallConstraint(self: pydrake.multibody.plant.MultibodyPlant_[AutoDiffXd], body_A: pydrake.multibody.tree.RigidBody_[AutoDiffXd], p_AP: numpy.ndarray[numpy.float64[3, 1]], body_B: pydrake.multibody.tree.RigidBody_[AutoDiffXd], p_BQ: Optional[numpy.ndarray[numpy.float64[3, 1]]] = None) pydrake.multibody.tree.MultibodyConstraintId
Defines a constraint such that point P affixed to body A is coincident at all times with point Q affixed to body B, effectively modeling a ball-and-socket joint.
- Parameter
body_A
: RigidBody to which point P is rigidly attached.
- Parameter
p_AP
: Position of point P in body A’s frame.
- Parameter
body_B
: RigidBody to which point Q is rigidly attached.
- Parameter
p_BQ
: (optional) Position of point Q in body B’s frame. If p_BQ is std::nullopt, then p_BQ will be computed so that the constraint is satisfied for the default configuration at Finalize() time; subsequent changes to the default configuration will not change the computed p_BQ.
- Returns
the id of the newly added constraint.
- Raises
RuntimeError if bodies A and B are the same body. –
RuntimeError if the MultibodyPlant has already been finalized. –
RuntimeError if this MultibodyPlant is not a discrete model –
(is_discrete() == false) –
RuntimeError if this MultibodyPlant's underlying contact –
solver is not SAP. (i.e. get_discrete_contact_solver() != –
DiscreteContactSolver::kSap) –
- Parameter
- AddCouplerConstraint(self: pydrake.multibody.plant.MultibodyPlant_[AutoDiffXd], joint0: pydrake.multibody.tree.Joint_[AutoDiffXd], joint1: pydrake.multibody.tree.Joint_[AutoDiffXd], gear_ratio: float, offset: float = 0.0) pydrake.multibody.tree.MultibodyConstraintId
Defines a holonomic constraint between two single-dof joints
joint0
andjoint1
with positions q₀ and q₁, respectively, such that q₀ = ρ⋅q₁ + Δq, where ρ is the gear ratio and Δq is a fixed offset. The gear ratio can have units if the units of q₀ and q₁ are different. For instance, between a prismatic and a revolute joint the gear ratio will specify the “pitch” of the resulting mechanism. As defined,offset
has units ofq₀
.Note
joint0 and/or joint1 can still be actuated, regardless of whether we have coupler constraint among them. That is, one or both of these joints can have external actuation applied to them.
Note
Generally, to couple (q0, q1, q2), the user would define a coupler between (q0, q1) and a second coupler between (q1, q2), or any combination therein.
- Raises
if joint0 and joint1 are not both single-dof joints. –
RuntimeError if the MultibodyPlant has already been finalized. –
RuntimeError if this MultibodyPlant is not a discrete model –
(is_discrete() == false) –
RuntimeError if this MultibodyPlant's underlying contact –
solver is not SAP. (i.e. get_discrete_contact_solver() != –
DiscreteContactSolver::kSap) –
- AddDistanceConstraint(self: pydrake.multibody.plant.MultibodyPlant_[AutoDiffXd], body_A: pydrake.multibody.tree.RigidBody_[AutoDiffXd], p_AP: numpy.ndarray[numpy.float64[3, 1]], body_B: pydrake.multibody.tree.RigidBody_[AutoDiffXd], p_BQ: numpy.ndarray[numpy.float64[3, 1]], distance: float, stiffness: float = inf, damping: float = 0.0) pydrake.multibody.tree.MultibodyConstraintId
Defines a distance constraint between a point P on a body A and a point Q on a body B.
This constraint can be compliant, modeling a spring with free length
distance
and givenstiffness
anddamping
parameters between points P and Q. For d = ‖p_PQ‖, then a compliant distance constraint models a spring with force along p_PQ given by:f = −stiffness ⋅ d − damping ⋅ ḋ
- Parameter
body_A
: RigidBody to which point P is rigidly attached.
- Parameter
p_AP
: Position of point P in body A’s frame.
- Parameter
body_B
: RigidBody to which point Q is rigidly attached.
- Parameter
p_BQ
: Position of point Q in body B’s frame.
- Parameter
distance
: Fixed length of the distance constraint, in meters. It must be strictly positive.
- Parameter
stiffness
: For modeling a spring with free length equal to
distance
, the stiffness parameter in N/m. Optional, with its default value being infinite to model a rigid massless rod of lengthdistance
connecting points A and B.- Parameter
damping
: For modeling a spring with free length equal to
distance
, damping parameter in N⋅s/m. Optional, with its default value being zero for a non-dissipative constraint.
- Returns
the id of the newly added constraint.
Warning
Currently, it is the user’s responsibility to initialize the model’s context in a configuration compatible with the newly added constraint.
Warning
A distance constraint is the wrong modeling choice if the distance needs to go through zero. To constrain two points to be coincident we need a 3-dof ball constraint, the 1-dof distance constraint is singular in this case. Therefore we require the distance parameter to be strictly positive.
- Raises
RuntimeError if bodies A and B are the same body. –
RuntimeError if distance is not strictly positive. –
RuntimeError if stiffness is not positive or zero. –
RuntimeError if damping is not positive or zero. –
RuntimeError if the MultibodyPlant has already been finalized. –
RuntimeError if this MultibodyPlant is not a discrete model –
(is_discrete() == false) –
RuntimeError if this MultibodyPlant's underlying contact –
solver is not SAP. (i.e. get_discrete_contact_solver() != –
DiscreteContactSolver::kSap) –
- Parameter
- AddForceElement(self: pydrake.multibody.plant.MultibodyPlant_[AutoDiffXd], force_element: pydrake.multibody.tree.ForceElement_[AutoDiffXd]) pydrake.multibody.tree.ForceElement_[AutoDiffXd]
Adds a new force element model of type
ForceElementType
tothis
MultibodyPlant. The arguments to this methodargs
are forwarded to ``ForceElementType`’s constructor.- Parameter
args
: Zero or more parameters provided to the constructor of the new force element. It must be the case that ForceElementType<T>(args)` is a valid constructor.
- Template parameter
ForceElementType
: The type of the ForceElement to add. As there is always a UniformGravityFieldElement present (accessible through gravity_field()), an exception will be thrown if this function is called to add another UniformGravityFieldElement.
- Returns
A constant reference to the new ForceElement just added, of type
ForceElementType<T>
specialized on the scalar type T ofthis
MultibodyPlant. It will remain valid for the lifetime ofthis
MultibodyPlant.
See also
The ForceElement class’s documentation for further details on how a force element is defined.
- Parameter
- AddFrame(self: pydrake.multibody.plant.MultibodyPlant_[AutoDiffXd], frame: pydrake.multibody.tree.Frame_[AutoDiffXd]) pydrake.multibody.tree.Frame_[AutoDiffXd]
This method adds a Frame of type
FrameType<T>
. For more information, please see the corresponding constructor ofFrameType
.- Template parameter
FrameType
: Template which will be instantiated on
T
.- Parameter
frame
: Unique pointer frame instance.
- Returns
A constant reference to the new Frame just added, which will remain valid for the lifetime of
this
MultibodyPlant.
- Template parameter
- AddJoint(self: pydrake.multibody.plant.MultibodyPlant_[AutoDiffXd], joint: pydrake.multibody.tree.Joint_[AutoDiffXd]) pydrake.multibody.tree.Joint_[AutoDiffXd]
This method adds a Joint of type
JointType
between two bodies. For more information, see the below overload ofAddJoint<>
.
- AddJointActuator(self: pydrake.multibody.plant.MultibodyPlant_[AutoDiffXd], name: str, joint: pydrake.multibody.tree.Joint_[AutoDiffXd], effort_limit: float = inf) pydrake.multibody.tree.JointActuator_[AutoDiffXd]
Creates and adds a JointActuator model for an actuator acting on a given
joint
. This method returns a constant reference to the actuator just added, which will remain valid for the lifetime ofthis
plant.- Parameter
name
: A string that uniquely identifies the new actuator to be added to
this
model. A RuntimeError is thrown if an actuator with the same name already exists in the model. See HasJointActuatorNamed().- Parameter
joint
: The Joint to be actuated by the new JointActuator.
- Parameter
effort_limit
: The maximum effort for the actuator. It must be strictly positive, otherwise an RuntimeError is thrown. If +∞, the actuator has no limit, which is the default. The effort limit has physical units in accordance to the joint type it actuates. For instance, it will have units of N⋅m (torque) for revolute joints while it will have units of N (force) for prismatic joints.
Note
The effort limit is unused by MultibodyPlant and is simply provided here for bookkeeping purposes. It will not, for instance, saturate external actuation inputs based on this value. If, for example, a user intends to saturate the force/torque that is applied to the MultibodyPlant via this actuator, the user-level code (e.g., a controller) should query this effort limit and impose the saturation there.
- Returns
A constant reference to the new JointActuator just added, which will remain valid for the lifetime of
this
plant or until the JointActuator has been removed from the plant with RemoveJointActuator().- Raises
RuntimeError if joint.num_velocities() > 1 since for now we –
only support actuators for single dof joints. –
See also
RemoveJointActuator()
- Parameter
- AddModelInstance(self: pydrake.multibody.plant.MultibodyPlant_[AutoDiffXd], name: str) pydrake.multibody.tree.ModelInstanceIndex
Creates a new model instance. Returns the index for the model instance.
- Parameter
name
: A string that uniquely identifies the new instance to be added to
this
model. An exception is thrown if an instance with the same name already exists in the model. See HasModelInstanceNamed().
- Parameter
- AddRigidBody(*args, **kwargs)
Overloaded function.
AddRigidBody(self: pydrake.multibody.plant.MultibodyPlant_[AutoDiffXd], name: str, M_BBo_B: pydrake.multibody.tree.SpatialInertia = SpatialInertia.Zero()) -> pydrake.multibody.tree.RigidBody_[AutoDiffXd]
Creates a rigid body with the provided name and spatial inertia. This method returns a constant reference to the body just added, which will remain valid for the lifetime of
this
MultibodyPlant. The body will use the default model instance (model_instance “more on model instances”).Example of usage:
Click to expand C++ code...
MultibodyPlant<T> plant; // ... Code to define spatial_inertia, a SpatialInertia<T> object ... const RigidBody<T>& body = plant.AddRigidBody("BodyName", spatial_inertia);
- Parameter
name
: A string that identifies the new body to be added to
this
model. A RuntimeError is thrown if a body namedname
already is part of the model in the default model instance. See HasBodyNamed(), RigidBody::name().- Parameter
M_BBo_B
: The SpatialInertia of the new rigid body to be added to
this
MultibodyPlant, computed about the body frame originBo
and expressed in the body frame B. When not provided, defaults to zero.
- Returns
A constant reference to the new RigidBody just added, which will remain valid for the lifetime of
this
MultibodyPlant.- Raises
RuntimeError if additional model instances have been created –
beyond the world and default instances. –
AddRigidBody(self: pydrake.multibody.plant.MultibodyPlant_[AutoDiffXd], name: str, model_instance: pydrake.multibody.tree.ModelInstanceIndex, M_BBo_B: pydrake.multibody.tree.SpatialInertia = SpatialInertia.Zero()) -> pydrake.multibody.tree.RigidBody_[AutoDiffXd]
Creates a rigid body with the provided name and spatial inertia. This method returns a constant reference to the body just added, which will remain valid for the lifetime of
this
MultibodyPlant.Example of usage:
Click to expand C++ code...
MultibodyPlant<T> plant; // ... Code to define spatial_inertia, a SpatialInertia<T> object ... ModelInstanceIndex model_instance = plant.AddModelInstance("instance"); const RigidBody<T>& body = plant.AddRigidBody("BodyName", model_instance, spatial_inertia);
- Parameter
name
: A string that identifies the new body to be added to
this
model. A RuntimeError is thrown if a body namedname
already is part ofmodel_instance
. See HasBodyNamed(), RigidBody::name().- Parameter
model_instance
: A model instance index which this body is part of.
- Parameter
M_BBo_B
: The SpatialInertia of the new rigid body to be added to
this
MultibodyPlant, computed about the body frame originBo
and expressed in the body frame B. When not provided, defaults to zero.
- Returns
A constant reference to the new RigidBody just added, which will remain valid for the lifetime of
this
MultibodyPlant.
- AddWeldConstraint(self: pydrake.multibody.plant.MultibodyPlant_[AutoDiffXd], body_A: pydrake.multibody.tree.RigidBody_[AutoDiffXd], X_AP: pydrake.math.RigidTransform, body_B: pydrake.multibody.tree.RigidBody_[AutoDiffXd], X_BQ: pydrake.math.RigidTransform) pydrake.multibody.tree.MultibodyConstraintId
Defines a constraint such that frame P affixed to body A is coincident at all times with frame Q affixed to body B, effectively modeling a weld joint.
- Parameter
body_A
: RigidBody to which frame P is rigidly attached.
- Parameter
X_AP
: Pose of frame P in body A’s frame.
- Parameter
body_B
: RigidBody to which frame Q is rigidly attached.
- Parameter
X_BQ
: Pose of frame Q in body B’s frame.
- Returns
the id of the newly added constraint.
- Raises
RuntimeError if bodies A and B are the same body. –
RuntimeError if the MultibodyPlant has already been finalized. –
RuntimeError if this MultibodyPlant is not a discrete model –
(is_discrete() == false) –
RuntimeError if this MultibodyPlant's underlying contact –
solver is not SAP. (i.e. get_discrete_contact_solver() != –
DiscreteContactSolver::kSap) –
- Parameter
- CalcBiasCenterOfMassTranslationalAcceleration(*args, **kwargs)
Overloaded function.
CalcBiasCenterOfMassTranslationalAcceleration(self: pydrake.multibody.plant.MultibodyPlant_[AutoDiffXd], context: pydrake.systems.framework.Context_[AutoDiffXd], with_respect_to: pydrake.multibody.tree.JacobianWrtVariable, frame_A: pydrake.multibody.tree.Frame_[AutoDiffXd], frame_E: pydrake.multibody.tree.Frame_[AutoDiffXd]) -> numpy.ndarray[object[3, 1]]
For the system S of all bodies other than the world body, calculates a𝑠Bias_AScm_E, Scm’s translational acceleration bias in frame A with respect to “speeds” 𝑠, expressed in frame E, where Scm is the center of mass of S and speeds 𝑠 is either q̇ or v.
- Parameter
context
: Contains the state of the multibody system.
- Parameter
with_respect_to
: Enum equal to JacobianWrtVariable::kQDot or JacobianWrtVariable::kV, indicating whether the accceleration bias is with respect to 𝑠 = q̇ or 𝑠 = v. Currently, an exception is thrown if with_respect_to is JacobianWrtVariable::kQDot.
- Parameter
frame_A
: The frame in which a𝑠Bias_AScm is measured.
- Parameter
frame_E
: The frame in which a𝑠Bias_AScm is expressed on output.
- Returns
a𝑠Bias_AScm_E Point Scm’s translational acceleration bias in frame A with respect to speeds 𝑠 (𝑠 = q̇ or 𝑠 = v), expressed in frame E.
- Raises
RuntimeError if this has no body except world_body() –
RuntimeError if mₛ ≤ 0, where mₛ is the mass of system S. –
RuntimeError if with_respect_to is JacobianWrtVariable::kQDot. –
See also
CalcJacobianCenterOfMassTranslationalVelocity() to compute J𝑠_v_Scm, point Scm’s translational velocity Jacobian in frame A with respect to 𝑠.
Note
The world_body() is ignored. asBias_AScm_E = ∑ (mᵢ aᵢ) / mₛ, where mₛ = ∑ mᵢ is the mass of system S, mᵢ is the mass of the iᵗʰ body, and aᵢ is the translational bias acceleration of Bᵢcm in frame A expressed in frame E for speeds 𝑠 (Bᵢcm is the center of mass of the iᵗʰ body).
Note
See bias_acceleration_functions “Bias acceleration functions” for theory and details.
CalcBiasCenterOfMassTranslationalAcceleration(self: pydrake.multibody.plant.MultibodyPlant_[AutoDiffXd], context: pydrake.systems.framework.Context_[AutoDiffXd], model_instances: list[pydrake.multibody.tree.ModelInstanceIndex], with_respect_to: pydrake.multibody.tree.JacobianWrtVariable, frame_A: pydrake.multibody.tree.Frame_[AutoDiffXd], frame_E: pydrake.multibody.tree.Frame_[AutoDiffXd]) -> numpy.ndarray[object[3, 1]]
For the system S containing the selected model instances, calculates a𝑠Bias_AScm_E, Scm’s translational acceleration bias in frame A with respect to “speeds” 𝑠, expressed in frame E, where Scm is the center of mass of S and speeds 𝑠 is either q̇ or v.
- Parameter
context
: Contains the state of the multibody system.
- Parameter
model_instances
: Vector of selected model instances. If a model instance is repeated in the vector (unusual), it is only counted once.
- Parameter
with_respect_to
: Enum equal to JacobianWrtVariable::kQDot or JacobianWrtVariable::kV, indicating whether the accceleration bias is with respect to 𝑠 = q̇ or 𝑠 = v. Currently, an exception is thrown if with_respect_to is JacobianWrtVariable::kQDot.
- Parameter
frame_A
: The frame in which a𝑠Bias_AScm is measured.
- Parameter
frame_E
: The frame in which a𝑠Bias_AScm is expressed on output.
- Returns
a𝑠Bias_AScm_E Point Scm’s translational acceleration bias in frame A with respect to speeds 𝑠 (𝑠 = q̇ or 𝑠 = v), expressed in frame E.
- Raises
RuntimeError if this has no body except world_body() –
RuntimeError if mₛ ≤ 0, where mₛ is the mass of system S. –
RuntimeError if with_respect_to is JacobianWrtVariable::kQDot. –
See also
CalcJacobianCenterOfMassTranslationalVelocity() to compute J𝑠_v_Scm, point Scm’s translational velocity Jacobian in frame A with respect to 𝑠.
Note
The world_body() is ignored. asBias_AScm_E = ∑ (mᵢ aᵢ) / mₛ, where mₛ = ∑ mᵢ is the mass of system S, mᵢ is the mass of the iᵗʰ body, and aᵢ is the translational bias acceleration of Bᵢcm in frame A expressed in frame E for speeds 𝑠 (Bᵢcm is the center of mass of the iᵗʰ body).
Note
See bias_acceleration_functions “Bias acceleration functions” for theory and details.
- CalcBiasSpatialAcceleration(self: pydrake.multibody.plant.MultibodyPlant_[AutoDiffXd], context: pydrake.systems.framework.Context_[AutoDiffXd], with_respect_to: pydrake.multibody.tree.JacobianWrtVariable, frame_B: pydrake.multibody.tree.Frame_[AutoDiffXd], p_BoBp_B: numpy.ndarray[object[3, 1]], frame_A: pydrake.multibody.tree.Frame_[AutoDiffXd], frame_E: pydrake.multibody.tree.Frame_[AutoDiffXd]) pydrake.multibody.math.SpatialAcceleration_[AutoDiffXd]
For one point Bp affixed/welded to a frame B, calculates A𝑠Bias_ABp, Bp’s spatial acceleration bias in frame A with respect to “speeds” 𝑠, expressed in frame E, where speeds 𝑠 is either q̇ or v.
- Parameter
context
: Contains the state of the multibody system.
- Parameter
with_respect_to
: Enum equal to JacobianWrtVariable::kQDot or JacobianWrtVariable::kV, indicating whether the spatial accceleration bias is with respect to 𝑠 = q̇ or 𝑠 = v. Currently, an exception is thrown if with_respect_to is JacobianWrtVariable::kQDot.
- Parameter
frame_B
: The frame on which point Bp is affixed/welded.
- Parameter
p_BoBp_B
: Position vector from Bo (frame_B’s origin) to point Bp (regarded as affixed/welded to B), expressed in frame_B.
- Parameter
frame_A
: The frame in which A𝑠Bias_ABp is measured.
- Parameter
frame_E
: The frame in which A𝑠Bias_ABp is expressed on output.
- Returns
A𝑠Bias_ABp_E Point Bp’s spatial acceleration bias in frame A with respect to speeds 𝑠 (𝑠 = q̇ or 𝑠 = v), expressed in frame E.
See also
CalcJacobianSpatialVelocity() to compute J𝑠_V_ABp, point Bp’s spatial velocity Jacobian in frame A with respect to 𝑠.
- Raises
RuntimeError if with_respect_to is JacobianWrtVariable::kQDot. –
Note
Use CalcBiasTranslationalAcceleration() to efficiently calculate bias translational accelerations for a list of points (each fixed to frame B). This function returns only one bias spatial acceleration, which contains both frame B’s bias angular acceleration and point Bp’s bias translational acceleration.
Note
See bias_acceleration_functions “Bias acceleration functions” for theory and details.
- Parameter
- CalcBiasTerm(self: pydrake.multibody.plant.MultibodyPlant_[AutoDiffXd], context: pydrake.systems.framework.Context_[AutoDiffXd]) numpy.ndarray[object[m, 1]]
Computes the bias term
C(q, v) v
containing Coriolis, centripetal, and gyroscopic effects in the multibody equations of motion:Click to expand C++ code...
M(q) v̇ + C(q, v) v = tau_app + ∑ (Jv_V_WBᵀ(q) ⋅ Fapp_Bo_W)
where
M(q)
is the multibody model’s mass matrix (including rigid body mass properties and reflected_inertia “reflected inertias”) andtau_app
is a vector of applied generalized forces. The last term is a summation over all bodies of the dot-product ofFapp_Bo_W
(applied spatial force on body B at Bo) withJv_V_WB(q)
(B’s spatial Jacobian in world W with respect to generalized velocities v). Note: B’s spatial velocity in W can be writtenV_WB = Jv_V_WB * v
.- Parameter
context
: Contains the state of the multibody system, including the generalized positions q and the generalized velocities v.
- Parameter
Cv
: On output,
Cv
will contain the productC(q, v)v
. It must be a valid (non-null) pointer to a column vector inℛⁿ
with n the number of generalized velocities (num_velocities()) of the model. This method aborts if Cv is nullptr or if it does not have the proper size.
- Parameter
- CalcBiasTranslationalAcceleration(self: pydrake.multibody.plant.MultibodyPlant_[AutoDiffXd], context: pydrake.systems.framework.Context_[AutoDiffXd], with_respect_to: pydrake.multibody.tree.JacobianWrtVariable, frame_B: pydrake.multibody.tree.Frame_[AutoDiffXd], p_BoBi_B: numpy.ndarray[object[3, n], flags.f_contiguous], frame_A: pydrake.multibody.tree.Frame_[AutoDiffXd], frame_E: pydrake.multibody.tree.Frame_[AutoDiffXd]) numpy.ndarray[object[3, n]]
For each point Bi affixed/welded to a frame B, calculates a𝑠Bias_ABi, Bi’s translational acceleration bias in frame A with respect to “speeds” 𝑠, expressed in frame E, where speeds 𝑠 is either q̇ or v.
- Parameter
context
: Contains the state of the multibody system.
- Parameter
with_respect_to
: Enum equal to JacobianWrtVariable::kQDot or JacobianWrtVariable::kV, indicating whether the translational acceleration bias is with respect to 𝑠 = q̇ or 𝑠 = v. Currently, an exception is thrown if with_respect_to is JacobianWrtVariable::kQDot.
- Parameter
frame_B
: The frame on which points Bi are affixed/welded.
- Parameter
p_BoBi_B
: A position vector or list of p position vectors from Bo (frame_B’s origin) to points Bi (regarded as affixed to B), where each position vector is expressed in frame_B. Each column in the
3 x p
matrix p_BoBi_B corresponds to a position vector.- Parameter
frame_A
: The frame in which a𝑠Bias_ABi is measured.
- Parameter
frame_E
: The frame in which a𝑠Bias_ABi is expressed on output.
- Returns
a𝑠Bias_ABi_E Point Bi’s translational acceleration bias in frame A with respect to speeds 𝑠 (𝑠 = q̇ or 𝑠 = v), expressed in frame E. a𝑠Bias_ABi_E is a
3 x p
matrix, where p is the number of points Bi.
See also
CalcJacobianTranslationalVelocity() to compute J𝑠_v_ABi, point Bi’s translational velocity Jacobian in frame A with respect to 𝑠.
- Precondition:
p_BoBi_B must have 3 rows.
- Raises
RuntimeError if with_respect_to is JacobianWrtVariable::kQDot. –
Note
See bias_acceleration_functions “Bias acceleration functions” for theory and details.
- Parameter
- CalcCenterOfMassPositionInWorld(*args, **kwargs)
Overloaded function.
CalcCenterOfMassPositionInWorld(self: pydrake.multibody.plant.MultibodyPlant_[AutoDiffXd], context: pydrake.systems.framework.Context_[AutoDiffXd]) -> numpy.ndarray[object[3, 1]]
Calculates the position vector from the world origin Wo to the center of mass of all bodies in this MultibodyPlant, expressed in the world frame W.
- Parameter
context
: Contains the state of the model.
- Returns
p_WoScm_W
: position vector from Wo to Scm expressed in world frame W, where Scm is the center of mass of the system S stored by
this
plant.
- Raises
RuntimeError if this has no body except world_body() –
RuntimeError if mₛ ≤ 0 (where mₛ is the mass of system S) –
Note
The world_body() is ignored. p_WoScm_W = ∑ (mᵢ pᵢ) / mₛ, where mₛ = ∑ mᵢ, mᵢ is the mass of the iᵗʰ body, and pᵢ is Bᵢcm’s position from Wo expressed in frame W (Bᵢcm is the center of mass of the iᵗʰ body).
CalcCenterOfMassPositionInWorld(self: pydrake.multibody.plant.MultibodyPlant_[AutoDiffXd], context: pydrake.systems.framework.Context_[AutoDiffXd], model_instances: list[pydrake.multibody.tree.ModelInstanceIndex]) -> numpy.ndarray[object[3, 1]]
Calculates the position vector from the world origin Wo to the center of mass of all non-world bodies contained in model_instances, expressed in the world frame W.
- Parameter
context
: Contains the state of the model.
- Parameter
model_instances
: Vector of selected model instances. If a model instance is repeated in the vector (unusual), it is only counted once.
- Returns
p_WoScm_W
: position vector from world origin Wo to Scm expressed in the world frame W, where Scm is the center of mass of the system S of non-world bodies contained in model_instances.
- Raises
RuntimeError if model_instances is empty or only has world body. –
RuntimeError if mₛ ≤ 0 (where mₛ is the mass of system S) –
Note
The world_body() is ignored. p_WoScm_W = ∑ (mᵢ pᵢ) / mₛ, where mₛ = ∑ mᵢ, mᵢ is the mass of the iᵗʰ body contained in model_instances, and pᵢ is Bᵢcm’s position vector from Wo expressed in frame W (Bᵢcm is the center of mass of the iᵗʰ body).
- CalcCenterOfMassTranslationalAccelerationInWorld(*args, **kwargs)
Overloaded function.
CalcCenterOfMassTranslationalAccelerationInWorld(self: pydrake.multibody.plant.MultibodyPlant_[AutoDiffXd], context: pydrake.systems.framework.Context_[AutoDiffXd]) -> numpy.ndarray[object[3, 1]]
For the system S contained in this MultibodyPlant, calculates Scm’s translational acceleration in the world frame W expressed in W, where Scm is the center of mass of S.
- Parameter
context
: The context contains the state of the model.
- Returns
a_WScm_W
: Scm’s translational acceleration in the world frame W expressed in the world frame W.
- Raises
RuntimeError if this has no body except world_body() –
RuntimeError if mₛ ≤ 0, where mₛ is the mass of system S. –
Note
The world_body() is ignored. a_WScm_W = ∑ (mᵢ aᵢ) / mₛ, where mₛ = ∑ mᵢ is the mass of system S, mᵢ is the mass of the iᵗʰ body, and aᵢ is the translational acceleration of Bᵢcm in world W expressed in W (Bᵢcm is the center of mass of the iᵗʰ body).
Note
When cached values are out of sync with the state stored in context, this method performs an expensive forward dynamics computation, whereas once evaluated, successive calls to this method are inexpensive.
CalcCenterOfMassTranslationalAccelerationInWorld(self: pydrake.multibody.plant.MultibodyPlant_[AutoDiffXd], context: pydrake.systems.framework.Context_[AutoDiffXd], model_instances: list[pydrake.multibody.tree.ModelInstanceIndex]) -> numpy.ndarray[object[3, 1]]
For the system S containing the selected model instances, calculates Scm’s translational acceleration in the world frame W expressed in W, where Scm is the center of mass of S.
- Parameter
context
: The context contains the state of the model.
- Parameter
model_instances
: Vector of selected model instances. If a model instance is repeated in the vector (unusual), it is only counted once.
- Returns
a_WScm_W
: Scm’s translational acceleration in the world frame W expressed in the world frame W.
- Raises
RuntimeError if model_instances is empty or only has world body. –
RuntimeError if mₛ ≤ 0, where mₛ is the mass of system S. –
Note
The world_body() is ignored. a_WScm_W = ∑ (mᵢ aᵢ) / mₛ, where mₛ = ∑ mᵢ is the mass of system S, mᵢ is the mass of the iᵗʰ body in model_instances, and aᵢ is the translational acceleration of Bᵢcm in world W expressed in W (Bᵢcm is the center of mass of the iᵗʰ body).
Note
When cached values are out of sync with the state stored in context, this method performs an expensive forward dynamics computation, whereas once evaluated, successive calls to this method are inexpensive.
- CalcCenterOfMassTranslationalVelocityInWorld(*args, **kwargs)
Overloaded function.
CalcCenterOfMassTranslationalVelocityInWorld(self: pydrake.multibody.plant.MultibodyPlant_[AutoDiffXd], context: pydrake.systems.framework.Context_[AutoDiffXd]) -> numpy.ndarray[object[3, 1]]
Calculates system center of mass translational velocity in world frame W.
- Parameter
context
: The context contains the state of the model.
- Returns
v_WScm_W
: Scm’s translational velocity in frame W, expressed in W, where Scm is the center of mass of the system S stored by
this
plant.
- Raises
RuntimeError if this has no body except world_body() –
RuntimeError if mₛ ≤ 0 (where mₛ is the mass of system S) –
Note
The world_body() is ignored. v_WScm_W = ∑ (mᵢ vᵢ) / mₛ, where mₛ = ∑ mᵢ, mᵢ is the mass of the iᵗʰ body, and vᵢ is Bᵢcm’s velocity in world W (Bᵢcm is the center of mass of the iᵗʰ body).
CalcCenterOfMassTranslationalVelocityInWorld(self: pydrake.multibody.plant.MultibodyPlant_[AutoDiffXd], context: pydrake.systems.framework.Context_[AutoDiffXd], model_instances: list[pydrake.multibody.tree.ModelInstanceIndex]) -> numpy.ndarray[object[3, 1]]
Calculates system center of mass translational velocity in world frame W.
- Parameter
context
: The context contains the state of the model.
- Parameter
model_instances
: Vector of selected model instances. If a model instance is repeated in the vector (unusual), it is only counted once.
- Returns
v_WScm_W
: Scm’s translational velocity in frame W, expressed in W, where Scm is the center of mass of the system S of non-world bodies contained in model_instances.
- Raises
RuntimeError if model_instances is empty or only has world body. –
RuntimeError if mₛ ≤ 0 (where mₛ is the mass of system S) –
Note
The world_body() is ignored. v_WScm_W = ∑ (mᵢ vᵢ) / mₛ, where mₛ = ∑ mᵢ, mᵢ is the mass of the iᵗʰ body contained in model_instances, and vᵢ is Bᵢcm’s velocity in world W expressed in frame W (Bᵢcm is the center of mass of the iᵗʰ body).
- CalcForceElementsContribution(self: pydrake.multibody.plant.MultibodyPlant_[AutoDiffXd], context: pydrake.systems.framework.Context_[AutoDiffXd], forces: pydrake.multibody.tree.MultibodyForces_[AutoDiffXd]) None
Computes the combined force contribution of ForceElement objects in the model. A ForceElement can apply forces as a spatial force per body or as generalized forces, depending on the ForceElement model. ForceElement contributions are a function of the state and time only. The output from this method can immediately be used as input to CalcInverseDynamics() to include the effect of applied forces by force elements.
- Parameter
context
: The context containing the state of this model.
- Parameter
forces
: A pointer to a valid, non nullptr, multibody forces object. On output
forces
will store the forces exerted by all the ForceElement objects in the model.
- Raises
RuntimeError if forces is null or not compatible with this –
model, per MultibodyForces::CheckInvariants() –
- Parameter
- CalcGeneralizedForces(self: pydrake.multibody.plant.MultibodyPlant_[AutoDiffXd], context: pydrake.systems.framework.Context_[AutoDiffXd], forces: pydrake.multibody.tree.MultibodyForces_[AutoDiffXd]) numpy.ndarray[object[m, 1]]
Computes the generalized forces result of a set of MultibodyForces applied to this model.
MultibodyForces stores applied forces as both generalized forces τ and spatial forces F on each body, refer to documentation in MultibodyForces for details. Users of MultibodyForces will use MultibodyForces::mutable_generalized_forces() to mutate the stored generalized forces directly and will use RigidBody::AddInForceInWorld() to append spatial forces.
For a given set of forces stored as MultibodyForces, this method will compute the total generalized forces on this model. More precisely, if J_WBo is the Jacobian (with respect to velocities) for this model, including all bodies, then this method computes:
Click to expand C++ code...
τᵣₑₛᵤₗₜ = τ + J_WBo⋅F
- Parameter
context
: Context that stores the state of the model.
- Parameter
forces
: Set of multibody forces, including both generalized forces and per-body spatial forces.
- Parameter
generalized_forces
: The total generalized forces on the model that would result from applying
forces
. In other words,forces
can be replaced by the equivalentgeneralized_forces
. On output,generalized_forces
is resized to num_velocities().
- Raises
RuntimeError if forces is null or not compatible with this –
model. –
RuntimeError if generalized_forces is not a valid non-null –
pointer. –
- Parameter
- CalcGravityGeneralizedForces(self: pydrake.multibody.plant.MultibodyPlant_[AutoDiffXd], context: pydrake.systems.framework.Context_[AutoDiffXd]) numpy.ndarray[object[m, 1]]
Computes the generalized forces
tau_g(q)
due to gravity as a function of the generalized positionsq
stored in the inputcontext
. The vector of generalized forces due to gravitytau_g(q)
is defined such that it appears on the right hand side of the equations of motion together with any other generalized forces, like so:Click to expand C++ code...
Mv̇ + C(q, v)v = tau_g(q) + tau_app
where
tau_app
includes any other generalized forces applied on the system.- Parameter
context
: The context storing the state of the model.
- Returns
tau_g A vector containing the generalized forces due to gravity. The generalized forces are consistent with the vector of generalized velocities
v
forthis
so that the inner productv⋅tau_g
corresponds to the power applied by the gravity forces on the mechanical system. That is,v⋅tau_g > 0
corresponds to potential energy going into the system, as either mechanical kinetic energy, some other potential energy, or heat, and therefore to a decrease of the gravitational potential energy.
- Parameter
- CalcInverseDynamics(self: pydrake.multibody.plant.MultibodyPlant_[AutoDiffXd], context: pydrake.systems.framework.Context_[AutoDiffXd], known_vdot: numpy.ndarray[object[m, 1]], external_forces: pydrake.multibody.tree.MultibodyForces_[AutoDiffXd]) numpy.ndarray[object[m, 1]]
Given the state of this model in
context
and a known vector of generalized accelerationsvdot
, this method computes the set of generalized forcestau
that would need to be applied in order to attain the specified generalized accelerations. Mathematically, this method computes:Click to expand C++ code...
tau = M(q)v̇ + C(q, v)v - tau_app - ∑ J_WBᵀ(q) Fapp_Bo_W
where
M(q)
is the model’s mass matrix (including rigid body mass properties and reflected_inertia “reflected inertias”),C(q, v)v
is the bias term for Coriolis and gyroscopic effects andtau_app
consists of a vector applied generalized forces. The last term is a summation over all bodies in the model whereFapp_Bo_W
is an applied spatial force on body B atBo
which gets projected into the space of generalized forces with the transpose ofJv_V_WB(q)
(whereJv_V_WB
is B’s spatial velocity Jacobian in W with respect to generalized velocities v). Note: B’s spatial velocity in W can be written asV_WB = Jv_V_WB * v
.This method does not compute explicit expressions for the mass matrix nor for the bias term, which would be of at least
O(n²)
complexity, but it implements anO(n)
Newton-Euler recursive algorithm, where n is the number of bodies in the model. The explicit formation of the mass matrixM(q)
would require the calculation ofO(n²)
entries while explicitly forming the productC(q, v) * v
could require up toO(n³)
operations (see [Featherstone 1987, §4]), depending on the implementation. The recursive Newton-Euler algorithm is the most efficient currently known general method for solving inverse dynamics [Featherstone 2008].- Parameter
context
: The context containing the state of the model.
- Parameter
known_vdot
: A vector with the known generalized accelerations
vdot
for the full model. Use the provided Joint APIs in order to access entries into this array.- Parameter
external_forces
: A set of forces to be applied to the system either as body spatial forces
Fapp_Bo_W
or generalized forcestau_app
, see MultibodyForces for details.
- Returns
the vector of generalized forces that would need to be applied to the mechanical system in order to achieve the desired acceleration given by
known_vdot
.
- Parameter
- CalcJacobianAngularVelocity(self: pydrake.multibody.plant.MultibodyPlant_[AutoDiffXd], context: pydrake.systems.framework.Context_[AutoDiffXd], with_respect_to: pydrake.multibody.tree.JacobianWrtVariable, frame_B: pydrake.multibody.tree.Frame_[AutoDiffXd], frame_A: pydrake.multibody.tree.Frame_[AutoDiffXd], frame_E: pydrake.multibody.tree.Frame_[AutoDiffXd]) numpy.ndarray[object[3, n]]
Calculates J𝑠_w_AB, a frame B’s angular velocity Jacobian in a frame A with respect to “speeds” 𝑠.
Click to expand C++ code...
J𝑠_w_AB ≜ [ ∂(w_AB)/∂𝑠₁, ... ∂(w_AB)/∂𝑠ₙ ] (n is j or k) w_AB = J𝑠_w_AB ⋅ 𝑠 w_AB is linear in 𝑠 ≜ [𝑠₁ ... 𝑠ₙ]ᵀ
w_AB
is B’s angular velocity in frame A and “speeds” 𝑠 is either q̇ ≜ [q̇₁ … q̇ⱼ]ᵀ (time-derivatives of j generalized positions) or v ≜ [v₁ … vₖ]ᵀ (k generalized velocities).- Parameter
context
: The state of the multibody system.
- Parameter
with_respect_to
: Enum equal to JacobianWrtVariable::kQDot or JacobianWrtVariable::kV, indicating whether the Jacobian
J𝑠_w_AB
is partial derivatives with respect to 𝑠 = q̇ (time-derivatives of generalized positions) or with respect to 𝑠 = v (generalized velocities).- Parameter
frame_B
: The frame B in
w_AB
(B’s angular velocity in A).- Parameter
frame_A
: The frame A in
w_AB
(B’s angular velocity in A).- Parameter
frame_E
: The frame in which
w_AB
is expressed on input and the frame in which the JacobianJ𝑠_w_AB
is expressed on output.- Parameter
J𝑠_w_AB_E
: Frame B’s angular velocity Jacobian in frame A with respect to speeds 𝑠 (which is either q̇ or v), expressed in frame E. The Jacobian is a function of only generalized positions q (which are pulled from the context). The previous definition shows
J𝑠_w_AB_E
is a matrix of size3 x n
, where n is the number of elements in 𝑠.
See also
See Jacobian_functions “Jacobian functions” for related functions.
- Raises
RuntimeError if J𝑠_w_AB_E is nullptr or not of size 3 x n. –
- Parameter
- CalcJacobianCenterOfMassTranslationalVelocity(*args, **kwargs)
Overloaded function.
CalcJacobianCenterOfMassTranslationalVelocity(self: pydrake.multibody.plant.MultibodyPlant_[AutoDiffXd], context: pydrake.systems.framework.Context_[AutoDiffXd], with_respect_to: pydrake.multibody.tree.JacobianWrtVariable, frame_A: pydrake.multibody.tree.Frame_[AutoDiffXd], frame_E: pydrake.multibody.tree.Frame_[AutoDiffXd]) -> numpy.ndarray[object[3, n]]
Calculates J𝑠_v_ACcm_E, point Ccm’s translational velocity Jacobian in frame A with respect to “speeds” 𝑠, expressed in frame E, where point CCm is the center of mass of the system of all non-world bodies contained in
this
MultibodyPlant.- Parameter
context
: contains the state of the model.
- Parameter
with_respect_to
: Enum equal to JacobianWrtVariable::kQDot or JacobianWrtVariable::kV, indicating whether the Jacobian
J𝑠_v_ACcm_E
is partial derivatives with respect to 𝑠 = q̇ (time-derivatives of generalized positions) or with respect to 𝑠 = v (generalized velocities).- Parameter
frame_A
: The frame in which the translational velocity v_ACcm and its Jacobian J𝑠_v_ACcm are measured.
- Parameter
frame_E
: The frame in which the Jacobian J𝑠_v_ACcm is expressed on output.
- Parameter
J𝑠_v_ACcm_E
: Point Ccm’s translational velocity Jacobian in frame A with respect to speeds 𝑠 (𝑠 = q̇ or 𝑠 = v), expressed in frame E. J𝑠_v_ACcm_E is a 3 x n matrix, where n is the number of elements in 𝑠. The Jacobian is a function of only generalized positions q (which are pulled from the context).
- Raises
RuntimeError if CCm does not exist, which occurs if there are no –
massive bodies in MultibodyPlant (except world_body()) –
RuntimeError if mₛ ≤ 0 (where mₛ is the mass of all non-world –
bodies contained in this MultibodyPlant) –
See also
See Jacobian_functions “Jacobian functions” for related functions.
CalcJacobianCenterOfMassTranslationalVelocity(self: pydrake.multibody.plant.MultibodyPlant_[AutoDiffXd], context: pydrake.systems.framework.Context_[AutoDiffXd], model_instances: list[pydrake.multibody.tree.ModelInstanceIndex], with_respect_to: pydrake.multibody.tree.JacobianWrtVariable, frame_A: pydrake.multibody.tree.Frame_[AutoDiffXd], frame_E: pydrake.multibody.tree.Frame_[AutoDiffXd]) -> numpy.ndarray[object[3, n]]
Calculates J𝑠_v_ACcm_E, point Ccm’s translational velocity Jacobian in frame A with respect to “speeds” 𝑠, expressed in frame E, where point CCm is the center of mass of the system of all non-world bodies contained in model_instances.
- Parameter
context
: contains the state of the model.
- Parameter
model_instances
: Vector of selected model instances. If a model instance is repeated in the vector (unusual), it is only counted once.
- Parameter
with_respect_to
: Enum equal to JacobianWrtVariable::kQDot or JacobianWrtVariable::kV, indicating whether the Jacobian
J𝑠_v_ACcm_E
is partial derivatives with respect to 𝑠 = q̇ (time-derivatives of generalized positions) or with respect to 𝑠 = v (generalized velocities).- Parameter
frame_A
: The frame in which the translational velocity v_ACcm and its Jacobian J𝑠_v_ACcm are measured.
- Parameter
frame_E
: The frame in which the Jacobian J𝑠_v_ACcm is expressed on output.
- Parameter
J𝑠_v_ACcm_E
: Point Ccm’s translational velocity Jacobian in frame A with respect to speeds 𝑠 (𝑠 = q̇ or 𝑠 = v), expressed in frame E. J𝑠_v_ACcm_E is a 3 x n matrix, where n is the number of elements in 𝑠. The Jacobian is a function of only generalized positions q (which are pulled from the context).
- Raises
RuntimeError if mₛ ≤ 0 (where mₛ is the mass of all non-world –
bodies contained in model_instances) –
RuntimeError if model_instances is empty or only has world body. –
Note
The world_body() is ignored. J𝑠_v_ACcm_ = ∑ (mᵢ Jᵢ) / mₛ, where mₛ = ∑ mᵢ, mᵢ is the mass of the iᵗʰ body contained in model_instances, and Jᵢ is Bᵢcm’s translational velocity Jacobian in frame A, expressed in frame E (Bᵢcm is the center of mass of the iᵗʰ body).
See also
See Jacobian_functions “Jacobian functions” for related functions.
- CalcJacobianPositionVector(self: pydrake.multibody.plant.MultibodyPlant_[AutoDiffXd], context: pydrake.systems.framework.Context_[AutoDiffXd], frame_B: pydrake.multibody.tree.Frame_[AutoDiffXd], p_BoBi_B: numpy.ndarray[object[3, n], flags.f_contiguous], frame_A: pydrake.multibody.tree.Frame_[AutoDiffXd], frame_E: pydrake.multibody.tree.Frame_[AutoDiffXd]) numpy.ndarray[object[m, n]]
For each point Bi affixed/welded to a frame B, calculates Jq_p_AoBi, Bi’s position vector Jacobian in frame A with respect to the generalized positions q ≜ [q₁ … qₙ]ᵀ as
Click to expand C++ code...
Jq_p_AoBi ≜ [ ᴬ∂(p_AoBi)/∂q₁, ... ᴬ∂(p_AoBi)/∂qₙ ]
where p_AoBi is Bi’s position vector from point Ao (frame A’s origin) and ᴬ∂(p_AoBi)/∂qᵣ denotes the partial derivative in frame A of p_AoBi with respect to the generalized position qᵣ, where qᵣ is one of q₁ … qₙ.
- Parameter
context
: The state of the multibody system.
- Parameter
frame_B
: The frame on which point Bi is affixed/welded.
- Parameter
p_BoBi_B
: A position vector or list of k position vectors from Bo (frame_B’s origin) to points Bi (Bi is regarded as affixed to B), where each position vector is expressed in frame_B.
- Parameter
frame_A
: The frame in which partial derivatives are calculated and the frame in which point Ao is affixed.
- Parameter
frame_E
: The frame in which the Jacobian Jq_p_AoBi is expressed on output.
- Parameter
Jq_p_AoBi_E
: Point Bi’s position vector Jacobian in frame A with generalized positions q, expressed in frame E. Jq_p_AoBi_E is a
3*k x n
matrix, where k is the number of points Bi and n is the number of elements in q. The Jacobian is a function of only generalized positions q (which are pulled from the context).
- Raises
RuntimeError if Jq_p_AoBi_E is nullptr or not sized 3*k x n. –
Note
Jq̇_v_ABi = Jq_p_AoBi. In other words, point Bi’s velocity Jacobian in frame A with respect to q̇ is equal to point Bi’s position vector Jacobian in frame A with respect to q.
Click to expand C++ code...
[∂(v_ABi)/∂q̇₁, ... ∂(v_ABi)/∂q̇ₙ] = [ᴬ∂(p_AoBi)/∂q₁, ... ᴬ∂(p_AoBi)/∂qₙ]
See also
CalcJacobianTranslationalVelocity() for details on Jq̇_v_ABi. Note: Jq_p_AaBi = Jq_p_AoBi, where point Aa is any point fixed/welded to frame A, i.e., this calculation’s result is the same if point Ao is replaced with any point fixed on frame A.
See also
See Jacobian_functions “Jacobian functions” for related functions.
- Parameter
- CalcJacobianSpatialVelocity(self: pydrake.multibody.plant.MultibodyPlant_[AutoDiffXd], context: pydrake.systems.framework.Context_[AutoDiffXd], with_respect_to: pydrake.multibody.tree.JacobianWrtVariable, frame_B: pydrake.multibody.tree.Frame_[AutoDiffXd], p_BoBp_B: numpy.ndarray[object[3, 1]], frame_A: pydrake.multibody.tree.Frame_[AutoDiffXd], frame_E: pydrake.multibody.tree.Frame_[AutoDiffXd]) numpy.ndarray[object[m, n]]
For one point Bp fixed/welded to a frame B, calculates J𝑠_V_ABp, Bp’s spatial velocity Jacobian in frame A with respect to “speeds” 𝑠.
Click to expand C++ code...
J𝑠_V_ABp ≜ [ ∂(V_ABp)/∂𝑠₁, ... ∂(V_ABp)/∂𝑠ₙ ] (n is j or k) V_ABp = J𝑠_V_ABp ⋅ 𝑠 V_ABp is linear in 𝑠 ≜ [𝑠₁ ... 𝑠ₙ]ᵀ
V_ABp
is Bp’s spatial velocity in frame A and “speeds” 𝑠 is either q̇ ≜ [q̇₁ … q̇ⱼ]ᵀ (time-derivatives of j generalized positions) or v ≜ [v₁ … vₖ]ᵀ (k generalized velocities).- Parameter
context
: The state of the multibody system.
- Parameter
with_respect_to
: Enum equal to JacobianWrtVariable::kQDot or JacobianWrtVariable::kV, indicating whether the Jacobian
J𝑠_V_ABp
is partial derivatives with respect to 𝑠 = q̇ (time-derivatives of generalized positions) or with respect to 𝑠 = v (generalized velocities).- Parameter
frame_B
: The frame on which point Bp is fixed/welded.
- Parameter
p_BoBp_B
: A position vector from Bo (frame_B’s origin) to point Bp (regarded as fixed/welded to B), expressed in frame_B.
- Parameter
frame_A
: The frame that measures
v_ABp
(Bp’s velocity in A). Note: It is natural to wonder why there is no parameter p_AoAp_A (similar to the parameter p_BoBp_B for frame_B). There is no need for p_AoAp_A because Bp’s velocity in A is defined as the derivative in frame A of Bp’s position vector from any point fixed to A.- Parameter
frame_E
: The frame in which
v_ABp
is expressed on input and the frame in which the JacobianJ𝑠_V_ABp
is expressed on output.- Parameter
J𝑠_V_ABp_E
: Point Bp’s spatial velocity Jacobian in frame A with respect to speeds 𝑠 (which is either q̇ or v), expressed in frame E.
J𝑠_V_ABp_E
is a6 x n
matrix, where n is the number of elements in 𝑠. The Jacobian is a function of only generalized positions q (which are pulled from the context).
Note
The returned
6 x n
matrix stores frame B’s angular velocity Jacobian in A in rows 1-3 and stores point Bp’s translational velocity Jacobian in A in rows 4-6, i.e.,Click to expand C++ code...
J𝑠_w_AB_E = J𝑠_V_ABp_E.topRows<3>(); J𝑠_v_ABp_E = J𝑠_V_ABp_E.bottomRows<3>();
Note
Consider CalcJacobianTranslationalVelocity() for multiple points fixed to frame B and consider CalcJacobianAngularVelocity() to calculate frame B’s angular velocity Jacobian.
See also
See Jacobian_functions “Jacobian functions” for related functions.
- Raises
RuntimeError if J𝑠_V_ABp_E is nullptr or not sized 6 x n. –
- Parameter
- CalcJacobianTranslationalVelocity(self: pydrake.multibody.plant.MultibodyPlant_[AutoDiffXd], context: pydrake.systems.framework.Context_[AutoDiffXd], with_respect_to: pydrake.multibody.tree.JacobianWrtVariable, frame_B: pydrake.multibody.tree.Frame_[AutoDiffXd], p_BoBi_B: numpy.ndarray[object[3, n], flags.f_contiguous], frame_A: pydrake.multibody.tree.Frame_[AutoDiffXd], frame_E: pydrake.multibody.tree.Frame_[AutoDiffXd]) numpy.ndarray[object[m, n]]
For each point Bi affixed/welded to a frame B, calculates J𝑠_v_ABi, Bi’s translational velocity Jacobian in frame A with respect to “speeds” 𝑠.
Click to expand C++ code...
J𝑠_v_ABi ≜ [ ∂(v_ABi)/∂𝑠₁, ... ∂(v_ABi)/∂𝑠ₙ ] (n is j or k) v_ABi = J𝑠_v_ABi ⋅ 𝑠 v_ABi is linear in 𝑠 ≜ [𝑠₁ ... 𝑠ₙ]ᵀ
v_ABi
is Bi’s translational velocity in frame A and “speeds” 𝑠 is either q̇ ≜ [q̇₁ … q̇ⱼ]ᵀ (time-derivatives of j generalized positions) or v ≜ [v₁ … vₖ]ᵀ (k generalized velocities).- Parameter
context
: The state of the multibody system.
- Parameter
with_respect_to
: Enum equal to JacobianWrtVariable::kQDot or JacobianWrtVariable::kV, indicating whether the Jacobian
J𝑠_v_ABi
is partial derivatives with respect to 𝑠 = q̇ (time-derivatives of generalized positions) or with respect to 𝑠 = v (generalized velocities).- Parameter
frame_B
: The frame on which point Bi is affixed/welded.
- Parameter
p_BoBi_B
: A position vector or list of p position vectors from Bo (frame_B’s origin) to points Bi (regarded as affixed to B), where each position vector is expressed in frame_B.
- Parameter
frame_A
: The frame that measures
v_ABi
(Bi’s velocity in A). Note: It is natural to wonder why there is no parameter p_AoAi_A (similar to the parameter p_BoBi_B for frame_B). There is no need for p_AoAi_A because Bi’s velocity in A is defined as the derivative in frame A of Bi’s position vector from any point affixed to A.- Parameter
frame_E
: The frame in which
v_ABi
is expressed on input and the frame in which the JacobianJ𝑠_v_ABi
is expressed on output.- Parameter
J𝑠_v_ABi_E
: Point Bi’s velocity Jacobian in frame A with respect to speeds 𝑠 (which is either q̇ or v), expressed in frame E.
J𝑠_v_ABi_E
is a3*p x n
matrix, where p is the number of points Bi and n is the number of elements in 𝑠. The Jacobian is a function of only generalized positions q (which are pulled from the context).
- Raises
RuntimeError if J𝑠_v_ABi_E is nullptr or not sized ``3*p x –
n``. –
Note
When 𝑠 = q̇,
Jq̇_v_ABi = Jq_p_AoBi
. In other words, point Bi’s velocity Jacobian in frame A with respect to q̇ is equal to point Bi’s position Jacobian from Ao (A’s origin) in frame A with respect to q.Click to expand C++ code...
[∂(v_ABi)/∂q̇₁, ... ∂(v_ABi)/∂q̇ⱼ] = [∂(p_AoBi)/∂q₁, ... ∂(p_AoBi)/∂qⱼ]
Note: Each partial derivative of p_AoBi is taken in frame A.
See also
CalcJacobianPositionVector() for details on Jq_p_AoBi.
See also
See Jacobian_functions “Jacobian functions” for related functions.
- Parameter
- CalcMassMatrix(self: pydrake.multibody.plant.MultibodyPlant_[AutoDiffXd], context: pydrake.systems.framework.Context_[AutoDiffXd]) numpy.ndarray[object[m, n]]
Efficiently computes the mass matrix
M(q)
of the model. The generalized positions q are taken from the givencontext
. M includes the mass properties of rigid bodies and reflected_inertia “reflected inertias” as provided with JointActuator specifications.This method employs the Composite Body Algorithm, which we believe to be the fastest O(n²) algorithm to compute the mass matrix of a multibody system.
- Parameter
context
: The Context containing the state of the model from which generalized coordinates q are extracted.
- Parameter
M
: A pointer to a square matrix in
ℛⁿˣⁿ
with n the number of generalized velocities (num_velocities()) of the model. Although symmetric, the matrix is filled in completely on return.- Precondition:
M is non-null and has the right size.
Warning
This is an O(n²) algorithm. Avoid the explicit computation of the mass matrix whenever possible.
See also
CalcMassMatrixViaInverseDynamics() (slower)
- Parameter
- CalcMassMatrixViaInverseDynamics(self: pydrake.multibody.plant.MultibodyPlant_[AutoDiffXd], context: pydrake.systems.framework.Context_[AutoDiffXd]) numpy.ndarray[object[m, n]]
Computes the mass matrix
M(q)
of the model using a slow method (inverse dynamics). The generalized positions q are taken from the givencontext
. M includes the mass properties of rigid bodies and reflected_inertia “reflected inertias” as provided with JointActuator specifications.Use CalcMassMatrix() for a faster implementation using the Composite Body Algorithm.
- Parameter
context
: The Context containing the state of the model from which generalized coordinates q are extracted.
- Parameter
M
: A pointer to a square matrix in
ℛⁿˣⁿ
with n the number of generalized velocities (num_velocities()) of the model. Although symmetric, the matrix is filled in completely on return.- Precondition:
M is non-null and has the right size.
The algorithm used to build
M(q)
consists in computing one column ofM(q)
at a time using inverse dynamics. The result from inverse dynamics, with no applied forces, is the vector of generalized forces:Click to expand C++ code...
tau = M(q)v̇ + C(q, v)v
where q and v are the generalized positions and velocities, respectively. When
v = 0
the Coriolis and gyroscopic forces termC(q, v)v
is zero. Therefore thei-th
column ofM(q)
can be obtained performing inverse dynamics with an acceleration vectorv̇ = eᵢ
, witheᵢ
the standard (or natural) basis ofℛⁿ
with n the number of generalized velocities. We write this as:Click to expand C++ code...
M.ᵢ(q) = M(q) * e_i
where
M.ᵢ(q)
(notice the dot for the rows index) denotes thei-th
column in M(q).Warning
This is an O(n²) algorithm. Avoid the explicit computation of the mass matrix whenever possible.
See also
CalcMassMatrix(), CalcInverseDynamics()
- Parameter
- CalcPointsPositions(self: pydrake.multibody.plant.MultibodyPlant_[AutoDiffXd], context: pydrake.systems.framework.Context_[AutoDiffXd], frame_B: pydrake.multibody.tree.Frame_[AutoDiffXd], p_BQi: numpy.ndarray[object[m, n], flags.f_contiguous], frame_A: pydrake.multibody.tree.Frame_[AutoDiffXd]) numpy.ndarray[object[m, n]]
Given the positions
p_BQi
for a set of pointsQi
measured and expressed in a frame B, this method computes the positionsp_AQi(q)
of each pointQi
in the set as measured and expressed in another frame A, as a function of the generalized positions q of the model.- Parameter
context
: The context containing the state of the model. It stores the generalized positions q of the model.
- Parameter
frame_B
: The frame B in which the positions
p_BQi
of a set of pointsQi
are given.- Parameter
p_BQi
: The input positions of each point
Qi
in frame B.p_BQi ∈ ℝ³ˣⁿᵖ
withnp
the number of points in the set. Each column ofp_BQi
corresponds to a vector in ℝ³ holding the position of one of the points in the set as measured and expressed in frame B.- Parameter
frame_A
: The frame A in which it is desired to compute the positions
p_AQi
of each pointQi
in the set.- Parameter
p_AQi
: The output positions of each point
Qi
now computed as measured and expressed in frame A. The outputp_AQi
must have the same size as the inputp_BQi
or otherwise this method aborts. That isp_AQi
must be inℝ³ˣⁿᵖ
.
Note
Both
p_BQi
andp_AQi
must have three rows. Otherwise this method will throw a RuntimeError. This method also throws a RuntimeError ifp_BQi
andp_AQi
differ in the number of columns.- Parameter
- CalcRelativeRotationMatrix(self: pydrake.multibody.plant.MultibodyPlant_[AutoDiffXd], context: pydrake.systems.framework.Context_[AutoDiffXd], frame_A: pydrake.multibody.tree.Frame_[AutoDiffXd], frame_B: pydrake.multibody.tree.Frame_[AutoDiffXd]) pydrake.math.RotationMatrix_[AutoDiffXd]
Calculates the rotation matrix
R_AB
relating frame A and frame B.- Parameter
context
: The state of the multibody system, which includes the system’s generalized positions q. Note:
R_AB
is a function of q.- Parameter
frame_A
: The frame A designated in the rigid transform
R_AB
.- Parameter
frame_B
: The frame G designated in the rigid transform
R_AB
.- Returns
R_AB
: The RigidTransform relating frame A and frame B.
- Parameter
- CalcRelativeTransform(self: pydrake.multibody.plant.MultibodyPlant_[AutoDiffXd], context: pydrake.systems.framework.Context_[AutoDiffXd], frame_A: pydrake.multibody.tree.Frame_[AutoDiffXd], frame_B: pydrake.multibody.tree.Frame_[AutoDiffXd]) pydrake.math.RigidTransform_[AutoDiffXd]
Calculates the rigid transform (pose)
X_AB
relating frame A and frame B.- Parameter
context
: The state of the multibody system, which includes the system’s generalized positions q. Note:
X_AB
is a function of q.- Parameter
frame_A
: The frame A designated in the rigid transform
X_AB
.- Parameter
frame_B
: The frame G designated in the rigid transform
X_AB
.- Returns
X_AB
: The RigidTransform relating frame A and frame B.
- Parameter
- CalcSpatialAccelerationsFromVdot(self: pydrake.multibody.plant.MultibodyPlant_[AutoDiffXd], context: pydrake.systems.framework.Context_[AutoDiffXd], known_vdot: numpy.ndarray[object[m, 1]]) list[pydrake.multibody.math.SpatialAcceleration_[AutoDiffXd]]
Given the state of this model in
context
and a known vector of generalized accelerationsknown_vdot
, this method computes the spatial accelerationA_WB
for each body as measured and expressed in the world frame W.- Parameter
context
: The context containing the state of this model.
- Parameter
known_vdot
: A vector with the generalized accelerations for the full model.
- Parameter
A_WB_array
: A pointer to a valid, non nullptr, vector of spatial accelerations containing the spatial acceleration
A_WB
for each body. It must be of size equal to the number of bodies in the model. On output, entries will be ordered by BodyIndex.
- Raises
RuntimeError if A_WB_array is not of size num_bodies() –
- Parameter
- CalcSpatialInertia(self: pydrake.multibody.plant.MultibodyPlant_[AutoDiffXd], context: pydrake.systems.framework.Context_[AutoDiffXd], frame_F: pydrake.multibody.tree.Frame_[AutoDiffXd], body_indexes: list[pydrake.multibody.tree.BodyIndex]) pydrake.multibody.tree.SpatialInertia_[AutoDiffXd]
Returns M_SFo_F, the spatial inertia of a set S of bodies about point Fo (the origin of a frame F), expressed in frame F. You may regard M_SFo_F as measuring spatial inertia as if the set S of bodies were welded into a single composite body at the configuration specified in the
context
.- Parameter
context
: Contains the configuration of the set S of bodies.
- Parameter
frame_F
: specifies the about-point Fo (frame_F’s origin) and the expressed-in frame for the returned spatial inertia.
- Parameter
body_indexes
: Array of selected bodies. This method does not distinguish between welded bodies, joint-connected bodies, etc.
- Raises
RuntimeError if body_indexes contains an invalid BodyIndex or if –
there is a repeated BodyIndex. –
Note
The mass and inertia of the world_body() does not contribute to the the returned spatial inertia.
- Parameter
- CalcSpatialMomentumInWorldAboutPoint(*args, **kwargs)
Overloaded function.
CalcSpatialMomentumInWorldAboutPoint(self: pydrake.multibody.plant.MultibodyPlant_[AutoDiffXd], context: pydrake.systems.framework.Context_[AutoDiffXd], p_WoP_W: numpy.ndarray[object[3, 1]]) -> pydrake.multibody.math.SpatialMomentum_[AutoDiffXd]
This method returns the spatial momentum of
this
MultibodyPlant in the world frame W, about a designated point P, expressed in the world frame W.- Parameter
context
: Contains the state of the model.
- Parameter
p_WoP_W
: Position from Wo (origin of the world frame W) to an arbitrary point P, expressed in the world frame W.
- Returns
L_WSP_W
: , spatial momentum of the system S represented by
this
plant, measured in the world frame W, about point P, expressed in W.
Note
To calculate the spatial momentum of this system S in W about Scm (the system’s center of mass), use something like:
Click to expand C++ code...
MultibodyPlant<T> plant; // ... code to load a model .... const Vector3<T> p_WoScm_W = plant.CalcCenterOfMassPositionInWorld(context); const SpatialMomentum<T> L_WScm_W = plant.CalcSpatialMomentumInWorldAboutPoint(context, p_WoScm_W);
CalcSpatialMomentumInWorldAboutPoint(self: pydrake.multibody.plant.MultibodyPlant_[AutoDiffXd], context: pydrake.systems.framework.Context_[AutoDiffXd], model_instances: list[pydrake.multibody.tree.ModelInstanceIndex], p_WoP_W: numpy.ndarray[object[3, 1]]) -> pydrake.multibody.math.SpatialMomentum_[AutoDiffXd]
This method returns the spatial momentum of a set of model instances in the world frame W, about a designated point P, expressed in frame W.
- Parameter
context
: Contains the state of the model.
- Parameter
model_instances
: Set of selected model instances.
- Parameter
p_WoP_W
: Position from Wo (origin of the world frame W) to an arbitrary point P, expressed in the world frame W.
- Returns
L_WSP_W
: , spatial momentum of the system S represented by the model_instances, measured in world frame W, about point P, expressed in W.
Note
To calculate the spatial momentum of this system S in W about Scm (the system’s center of mass), use something like:
Click to expand C++ code...
MultibodyPlant<T> plant; // ... code to create a set of selected model instances, e.g., ... const ModelInstanceIndex gripper_model_instance = plant.GetModelInstanceByName("gripper"); const ModelInstanceIndex robot_model_instance = plant.GetBodyByName("end_effector").model_instance(); const std::vector<ModelInstanceIndex> model_instances{ gripper_model_instance, robot_model_instance}; const Vector3<T> p_WoScm_W = plant.CalcCenterOfMassPositionInWorld(context, model_instances); SpatialMomentum<T> L_WScm_W = plant.CalcSpatialMomentumInWorldAboutPoint(context, model_instances, p_WoScm_W);
- Raises
RuntimeError if model_instances contains an invalid –
ModelInstanceIndex. –
- CalcTotalMass(*args, **kwargs)
Overloaded function.
CalcTotalMass(self: pydrake.multibody.plant.MultibodyPlant_[AutoDiffXd], context: pydrake.systems.framework.Context_[AutoDiffXd]) -> pydrake.autodiffutils.AutoDiffXd
Calculates the total mass of all bodies in this MultibodyPlant.
- Parameter
context
: Contains the state of the model.
- Returns
The
: total mass of all bodies or 0 if there are none.
Note
The mass of the world_body() does not contribute to the total mass.
CalcTotalMass(self: pydrake.multibody.plant.MultibodyPlant_[AutoDiffXd], context: pydrake.systems.framework.Context_[AutoDiffXd], model_instances: list[pydrake.multibody.tree.ModelInstanceIndex]) -> pydrake.autodiffutils.AutoDiffXd
Calculates the total mass of all bodies contained in model_instances.
- Parameter
context
: Contains the state of the model.
- Parameter
model_instances
: Vector of selected model instances. This method does not distinguish between welded, joint connected, or floating bodies.
- Returns
The
: total mass of all bodies belonging to a model instance in model_instances or 0 if model_instances is empty.
Note
The mass of the world_body() does not contribute to the total mass and each body only contributes to the total mass once, even if the body has repeated occurrence (instance) in model_instances.
- CollectRegisteredGeometries(self: pydrake.multibody.plant.MultibodyPlant_[AutoDiffXd], bodies: list[pydrake.multibody.tree.RigidBody_[AutoDiffXd]]) pydrake.geometry.GeometrySet
For each of the provided
bodies
, collects up all geometries that have been registered to that body. Intended to be used in conjunction with CollisionFilterDeclaration and CollisionFilterManager::Apply() to filter collisions between the geometries registered to the bodies.For example:
Click to expand C++ code...
// Don't report on collisions between geometries affixed to `body1`, // `body2`, or `body3`. std::vector<const RigidBody<T>*> bodies{&body1, &body2, &body3}; geometry::GeometrySet set = plant.CollectRegisteredGeometries(bodies); scene_graph.collision_filter_manager().Apply( CollisionFilterDeclaration().ExcludeWithin(set));
Note
There is a very specific order of operations:
Bodies and geometries must be added to the MultibodyPlant.
Create GeometrySet instances from bodies (via this method).
Invoke SceneGraph::ExcludeCollisions*() to filter collisions.
Allocate context.
Changing the order will cause exceptions to be thrown.
- Raises
RuntimeError if this MultibodyPlant was not registered with a –
SceneGraph. –
- deformable_model(self: pydrake.multibody.plant.MultibodyPlant_[AutoDiffXd]) drake::multibody::DeformableModel<Eigen::AutoDiffScalar<Eigen::Matrix<double, -1, 1, 0, -1, 1> > >
Returns the DeformableModel owned by this plant.
- Raises
RuntimeError if this plant doesn't own a DeformableModel. –
Warning
This feature is considered to be experimental and may change or be removed at any time, without any deprecation notice ahead of time.
- EvalBodyPoseInWorld(self: pydrake.multibody.plant.MultibodyPlant_[AutoDiffXd], context: pydrake.systems.framework.Context_[AutoDiffXd], body: pydrake.multibody.tree.RigidBody_[AutoDiffXd]) pydrake.math.RigidTransform_[AutoDiffXd]
Evaluate the pose
X_WB
of a body B in the world frame W.- Parameter
context
: The context storing the state of the model.
- Parameter
body_B
: The body B for which the pose is requested.
- Returns
X_WB
: The pose of body frame B in the world frame W.
- Raises
RuntimeError if Finalize() was not called on this model or if –
body_B` does not belong to this model –
- Parameter
- EvalBodySpatialAccelerationInWorld(self: pydrake.multibody.plant.MultibodyPlant_[AutoDiffXd], context: pydrake.systems.framework.Context_[AutoDiffXd], body: pydrake.multibody.tree.RigidBody_[AutoDiffXd]) pydrake.multibody.math.SpatialAcceleration_[AutoDiffXd]
Evaluates A_WB, body B’s spatial acceleration in the world frame W.
- Parameter
context
: The context storing the state of the model.
- Parameter
body_B
: The body for which spatial acceleration is requested.
- Returns
A_WB_W
: RigidBody B’s spatial acceleration in the world frame W, expressed in W (for point Bo, the body’s origin).
- Raises
RuntimeError if Finalize() was not called on this model or if –
body_B` does not belong to this model –
Note
When cached values are out of sync with the state stored in context, this method performs an expensive forward dynamics computation, whereas once evaluated, successive calls to this method are inexpensive.
- Parameter
- EvalBodySpatialVelocityInWorld(self: pydrake.multibody.plant.MultibodyPlant_[AutoDiffXd], context: pydrake.systems.framework.Context_[AutoDiffXd], body: pydrake.multibody.tree.RigidBody_[AutoDiffXd]) pydrake.multibody.math.SpatialVelocity_[AutoDiffXd]
Evaluates V_WB, body B’s spatial velocity in the world frame W.
- Parameter
context
: The context storing the state of the model.
- Parameter
body_B
: The body B for which the spatial velocity is requested.
- Returns
V_WB_W
: RigidBody B’s spatial velocity in the world frame W, expressed in W (for point Bo, the body’s origin).
- Raises
RuntimeError if Finalize() was not called on this model or if –
body_B` does not belong to this model –
- Parameter
- EvalSceneGraphInspector(self: pydrake.multibody.plant.MultibodyPlant_[AutoDiffXd], context: pydrake.systems.framework.Context_[AutoDiffXd]) pydrake.geometry.SceneGraphInspector_[AutoDiffXd]
Returns the inspector from the
context
for the SceneGraph associated with this plant, via this plant’s “geometry_query” input port. (In the future, the inspector might come from a different context source that is more efficient than the “geometry_query” input port.)
- Finalize(self: pydrake.multibody.plant.MultibodyPlant_[AutoDiffXd]) None
This method must be called after all elements in the model (joints, bodies, force elements, constraints, etc.) are added and before any computations are performed. It essentially compiles all the necessary “topological information”, i.e. how bodies, joints and, any other elements connect with each other, and performs all the required pre-processing to enable computations at a later stage.
If the finalize stage is successful, the topology of this MultibodyPlant is valid, meaning that the topology is up-to-date after this call. No more multibody elements can be added after a call to Finalize().
At Finalize(), state and input/output ports for
this
plant are declared.For a full account of the effects of Finalize(), see mbp_finalize_stage “Finalize() stage”.
See also
is_finalized(), mbp_finalize_stage “Finalize() stage”.
- Raises
RuntimeError if the MultibodyPlant has already been finalized. –
- geometry_source_is_registered(self: pydrake.multibody.plant.MultibodyPlant_[AutoDiffXd]) bool
Returns
True
ifthis
MultibodyPlant was registered with a SceneGraph. This method can be called at any time during the lifetime ofthis
plant to query ifthis
plant has been registered with a SceneGraph, either pre- or post-finalize, see Finalize().
- get_actuation_input_port(*args, **kwargs)
Overloaded function.
get_actuation_input_port(self: pydrake.multibody.plant.MultibodyPlant_[AutoDiffXd]) -> pydrake.systems.framework.InputPort_[AutoDiffXd]
Returns a constant reference to the input port for external actuation for all actuated dofs. This input port is a vector valued port and can be set with JointActuator::set_actuation_vector(). The actuation value for a particular actuator can be found at offset JointActuator::input_start() in this vector. Refer to mbp_actuation “Actuation” for further details.
- Precondition:
Finalize() was already called on
this
plant.
- Raises
RuntimeError if called before Finalize() –
get_actuation_input_port(self: pydrake.multibody.plant.MultibodyPlant_[AutoDiffXd], model_instance: pydrake.multibody.tree.ModelInstanceIndex) -> pydrake.systems.framework.InputPort_[AutoDiffXd]
Returns a constant reference to the input port for external actuation for a specific model instance. This is a vector valued port with entries ordered by monotonically increasing JointActuatorIndex within
model_instance
. Refer to mbp_actuation “Actuation” for further details.Every model instance in
this
plant model has an actuation input port, even if zero sized (for model instance with no actuators).See also
GetJointActuatorIndices(), GetActuatedJointIndices().
- Precondition:
Finalize() was already called on
this
plant.
- Raises
RuntimeError if called before Finalize() –
RuntimeError if the model instance does not exist. –
- get_adjacent_bodies_collision_filters(self: pydrake.multibody.plant.MultibodyPlant_[AutoDiffXd]) bool
Returns whether to apply collision filters to topologically adjacent bodies at Finalize() time.
- get_applied_generalized_force_input_port(self: pydrake.multibody.plant.MultibodyPlant_[AutoDiffXd]) pydrake.systems.framework.InputPort_[AutoDiffXd]
Returns a constant reference to the vector-valued input port for applied generalized forces, and the vector will be added directly into
tau
(see mbp_equations_of_motion “System dynamics”). This vector is ordered using the same convention as the plant velocities: you can set the generalized forces that will be applied to model instance i using, e.g.,SetVelocitiesInArray(i, model_forces, &force_array)
.- Raises
RuntimeError if called before Finalize() –
- get_applied_spatial_force_input_port(self: pydrake.multibody.plant.MultibodyPlant_[AutoDiffXd]) pydrake.systems.framework.InputPort_[AutoDiffXd]
Returns a constant reference to the input port for applying spatial forces to bodies in the plant. The data type for the port is an std::vector of ExternallyAppliedSpatialForce; any number of spatial forces can be applied to any number of bodies in the plant.
- get_body(self: pydrake.multibody.plant.MultibodyPlant_[AutoDiffXd], body_index: pydrake.multibody.tree.BodyIndex) pydrake.multibody.tree.RigidBody_[AutoDiffXd]
Returns a constant reference to the body with unique index
body_index
.- Raises
RuntimeError if body_index does not correspond to a body in –
this model. –
- get_body_poses_output_port(self: pydrake.multibody.plant.MultibodyPlant_[AutoDiffXd]) pydrake.systems.framework.OutputPort_[AutoDiffXd]
Returns the output port of all body poses in the world frame. You can obtain the pose
X_WB
of a body B in the world frame W with:Click to expand C++ code...
const auto& X_WB_all = plant.get_body_poses_output_port(). .Eval<std::vector<math::RigidTransform<double>>>(plant_context); const BodyIndex arm_body_index = plant.GetBodyByName("arm").index(); const math::RigidTransform<double>& X_WArm = X_WB_all[arm_body_index];
As shown in the example above, the resulting
std::vector
of body poses is indexed by BodyIndex, and it has size num_bodies(). BodyIndex “zero” (0) always corresponds to the world body, with pose equal to the identity at all times.- Raises
RuntimeError if called pre-finalize. –
- get_body_spatial_accelerations_output_port(self: pydrake.multibody.plant.MultibodyPlant_[AutoDiffXd]) pydrake.systems.framework.OutputPort_[AutoDiffXd]
Returns the output port of all body spatial accelerations in the world frame. You can obtain the spatial acceleration
A_WB
of a body B (for point Bo, the body’s origin) in the world frame W with:Click to expand C++ code...
const auto& A_WB_all = plant.get_body_spatial_accelerations_output_port(). .Eval<std::vector<SpatialAcceleration<double>>>(plant_context); const BodyIndex arm_body_index = plant.GetBodyByName("arm").index(); const SpatialVelocity<double>& A_WArm = A_WB_all[arm_body_index];
As shown in the example above, the resulting
std::vector
of body spatial accelerations is indexed by BodyIndex, and it has size num_bodies(). BodyIndex “zero” (0) always corresponds to the world body, with zero spatial acceleration at all times.In a discrete-time plant, the use_sampled_output_ports setting affects the output of this port. See output_port_sampling “Output port sampling” for details. When sampling is enabled and the plant has not yet taken a step, the output value will be all zeros.
- Raises
RuntimeError if called pre-finalize. –
- get_body_spatial_velocities_output_port(self: pydrake.multibody.plant.MultibodyPlant_[AutoDiffXd]) pydrake.systems.framework.OutputPort_[AutoDiffXd]
Returns the output port of all body spatial velocities in the world frame. You can obtain the spatial velocity
V_WB
of a body B in the world frame W with:Click to expand C++ code...
const auto& V_WB_all = plant.get_body_spatial_velocities_output_port(). .Eval<std::vector<SpatialVelocity<double>>>(plant_context); const BodyIndex arm_body_index = plant.GetBodyByName("arm").index(); const SpatialVelocity<double>& V_WArm = V_WB_all[arm_body_index];
As shown in the example above, the resulting
std::vector
of body spatial velocities is indexed by BodyIndex, and it has size num_bodies(). BodyIndex “zero” (0) always corresponds to the world body, with zero spatial velocity at all times.- Raises
RuntimeError if called pre-finalize. –
- get_contact_model(self: pydrake.multibody.plant.MultibodyPlant_[AutoDiffXd]) pydrake.multibody.plant.ContactModel
Returns the model used for contact. See documentation for ContactModel.
- get_contact_penalty_method_time_scale(self: pydrake.multibody.plant.MultibodyPlant_[AutoDiffXd]) float
Returns a time-scale estimate
tc
based on the requested penetration allowance δ set with set_penetration_allowance(). For the compliant contact model to enforce non-penetration, this time scale relates to the time it takes the relative normal velocity between two bodies to go to zero. This time scaletc
is a global estimate of the dynamics introduced by the compliant contact model and goes to zero in the limit to ideal rigid contact. Since numerical integration methods for continuum systems must be able to resolve a system’s dynamics, the time step used by an integrator must in general be much smaller than the time scaletc
. How much smaller will depend on the details of the problem and the convergence characteristics of the integrator and should be tuned appropriately. Another factor to take into account for setting up the simulation’s time step is the speed of the objects in your simulation. Ifvn
represents a reference velocity scale for the normal relative velocity between bodies, the new time scaletn = δ / vn
represents the time it would take for the distance between two bodies approaching with relative normal velocityvn
to decrease by the penetration_allowance δ. In this case a user should choose a time step for simulation that can resolve the smallest of the two time scalestc
andtn
.
- get_contact_results_output_port(self: pydrake.multibody.plant.MultibodyPlant_[AutoDiffXd]) pydrake.systems.framework.OutputPort_[AutoDiffXd]
Returns a constant reference to the port that outputs ContactResults.
In a discrete-time plant, the use_sampled_output_ports setting affects the output of this port. See output_port_sampling “Output port sampling” for details. When sampling is enabled and the plant has not yet taken a step, the output value will be empty (no contacts).
- Raises
RuntimeError if called pre-finalize, see Finalize() –
- get_contact_surface_representation(self: pydrake.multibody.plant.MultibodyPlant_[AutoDiffXd]) pydrake.geometry.HydroelasticContactRepresentation
Gets the current representation of contact surfaces used by
this
MultibodyPlant.
- get_deformable_body_configuration_output_port(self: pydrake.multibody.plant.MultibodyPlant_[AutoDiffXd]) pydrake.systems.framework.OutputPort_[AutoDiffXd]
Returns the output port for vertex positions (configurations), measured and expressed in the World frame, of the deformable bodies in
this
plant as a GeometryConfigurationVector.
- get_desired_state_input_port(self: pydrake.multibody.plant.MultibodyPlant_[AutoDiffXd], model_instance: pydrake.multibody.tree.ModelInstanceIndex) pydrake.systems.framework.InputPort_[AutoDiffXd]
For models with PD controlled joint actuators, returns the port to provide the desired state for the full
model_instance
. Refer to mbp_actuation “Actuation” for further details.For consistency with get_actuation_input_port(), each model instance in
this
plant model has a desired states input port, even if zero sized (for model instance with no actuators.)Note
This is a vector valued port of size 2*num_actuators(model_instance), where we assumed 1-DOF actuated joints. This is true even for unactuated models, for which this port is zero sized. This port must provide one desired position and one desired velocity per joint actuator. Desired state is assumed to be packed as xd = [qd, vd] that is, configurations first followed by velocities. The actuation value for a particular actuator can be found at offset JointActuator::input_start() in both qd and vd. For example:
Click to expand C++ code...
const double qd_actuator = xd[actuator.input_start()]; const double vd_actuator = xd[actuator.input_start() + plant.num_actuated_dofs()];
Warning
If a user specifies a PD controller for an actuator from a given model instance, then all actuators of that model instance are required to be PD controlled.
Warning
It is required to connect this port for PD controlled model instances.
- get_discrete_contact_approximation(self: pydrake.multibody.plant.MultibodyPlant_[AutoDiffXd]) pydrake.multibody.plant.DiscreteContactApproximation
- Returns
the discrete contact solver approximation.
- get_discrete_contact_solver(self: pydrake.multibody.plant.MultibodyPlant_[AutoDiffXd]) pydrake.multibody.plant.DiscreteContactSolver
Returns the contact solver type used for discrete MultibodyPlant models.
- get_force_element(self: pydrake.multibody.plant.MultibodyPlant_[AutoDiffXd], force_element_index: pydrake.multibody.tree.ForceElementIndex) pydrake.multibody.tree.ForceElement_[AutoDiffXd]
Returns a constant reference to the force element with unique index
force_element_index
.- Raises
RuntimeError when force_element_index does not correspond to a –
force element in this model. –
- get_frame(self: pydrake.multibody.plant.MultibodyPlant_[AutoDiffXd], frame_index: pydrake.multibody.tree.FrameIndex) pydrake.multibody.tree.Frame_[AutoDiffXd]
Returns a constant reference to the frame with unique index
frame_index
.- Raises
RuntimeError if frame_index does not correspond to a frame in –
this plant. –
- get_generalized_acceleration_output_port(*args, **kwargs)
Overloaded function.
get_generalized_acceleration_output_port(self: pydrake.multibody.plant.MultibodyPlant_[AutoDiffXd]) -> pydrake.systems.framework.OutputPort_[AutoDiffXd]
Returns a constant reference to the output port for generalized accelerations v̇ of the model.
In a discrete-time plant, the use_sampled_output_ports setting affects the output of this port. See output_port_sampling “Output port sampling” for details. When sampling is enabled and the plant has not yet taken a step, the output value will be all zeros.
- Precondition:
Finalize() was already called on
this
plant.
- Raises
RuntimeError if called before Finalize() –
get_generalized_acceleration_output_port(self: pydrake.multibody.plant.MultibodyPlant_[AutoDiffXd], model_instance: pydrake.multibody.tree.ModelInstanceIndex) -> pydrake.systems.framework.OutputPort_[AutoDiffXd]
Returns a constant reference to the output port for the generalized accelerations v̇ᵢ ⊆ v̇ for model instance i.
In a discrete-time plant, the use_sampled_output_ports setting affects the output of this port. See output_port_sampling “Output port sampling” for details. When sampling is enabled and the plant has not yet taken a step, the output value will be all zeros.
- Precondition:
Finalize() was already called on
this
plant.
- Raises
RuntimeError if called before Finalize() –
RuntimeError if the model instance does not exist. –
- get_generalized_contact_forces_output_port(self: pydrake.multibody.plant.MultibodyPlant_[AutoDiffXd], model_instance: pydrake.multibody.tree.ModelInstanceIndex) pydrake.systems.framework.OutputPort_[AutoDiffXd]
Returns a constant reference to the output port of generalized contact forces for a specific model instance.
In a discrete-time plant, the use_sampled_output_ports setting affects the output of this port. See output_port_sampling “Output port sampling” for details. When sampling is enabled and the plant has not yet taken a step, the output value will be all zeros.
- Precondition:
Finalize() was already called on
this
plant.
- Raises
RuntimeError if called before Finalize() –
RuntimeError if the model instance does not exist. –
- get_geometry_pose_output_port(self: pydrake.multibody.plant.MultibodyPlant_[AutoDiffXd]) pydrake.systems.framework.OutputPort_[AutoDiffXd]
Returns the output port of frames’ poses to communicate with a SceneGraph.
- get_geometry_query_input_port(self: pydrake.multibody.plant.MultibodyPlant_[AutoDiffXd]) pydrake.systems.framework.InputPort_[AutoDiffXd]
Returns a constant reference to the input port used to perform geometric queries on a SceneGraph. See SceneGraph::get_query_output_port(). Refer to section mbp_geometry “Geometry” of this class’s documentation for further details on collision geometry registration and connection with a SceneGraph.
- get_joint(self: pydrake.multibody.plant.MultibodyPlant_[AutoDiffXd], joint_index: pydrake.multibody.tree.JointIndex) pydrake.multibody.tree.Joint_[AutoDiffXd]
Returns a constant reference to the joint with unique index
joint_index
.- Raises
RuntimeError when joint_index does not correspond to a joint –
in this model. –
- get_joint_actuator(self: pydrake.multibody.plant.MultibodyPlant_[AutoDiffXd], actuator_index: pydrake.multibody.tree.JointActuatorIndex) pydrake.multibody.tree.JointActuator_[AutoDiffXd]
Returns a constant reference to the joint actuator with unique index
actuator_index
.- Raises
RuntimeError if actuator_index does not correspond to a joint –
actuator in this tree. –
- get_mutable_joint(self: pydrake.multibody.plant.MultibodyPlant_[AutoDiffXd], joint_index: pydrake.multibody.tree.JointIndex) pydrake.multibody.tree.Joint_[AutoDiffXd]
Returns a mutable reference to the joint with unique index
joint_index
.- Raises
RuntimeError when joint_index does not correspond to a joint –
in this model. –
- get_mutable_joint_actuator(self: pydrake.multibody.plant.MultibodyPlant_[AutoDiffXd], actuator_index: pydrake.multibody.tree.JointActuatorIndex) pydrake.multibody.tree.JointActuator_[AutoDiffXd]
Returns a mutable reference to the joint actuator with unique index
actuator_index
.- Raises
RuntimeError if actuator_index does not correspond to a joint –
actuator in this tree. –
- get_net_actuation_output_port(*args, **kwargs)
Overloaded function.
get_net_actuation_output_port(self: pydrake.multibody.plant.MultibodyPlant_[AutoDiffXd]) -> pydrake.systems.framework.OutputPort_[AutoDiffXd]
Returns a constant reference to the output port that reports actuation values applied through joint actuators. This output port is a vector valued port. The actuation value for a particular actuator can be found at offset JointActuator::input_start() in this vector. Models that include PD controllers will include their contribution in this port, refer to mbp_actuation “Actuation” for further details.
In a discrete-time plant, the use_sampled_output_ports setting affects the output of this port. See output_port_sampling “Output port sampling” for details. When sampling is enabled and the plant has not yet taken a step, the output value will be all zeros.
Note
PD controllers are not considered for actuators on locked joints, see Joint::Lock(). Therefore they do not contribute to this port.
- Precondition:
Finalize() was already called on
this
plant.
- Raises
RuntimeError if called before Finalize() –
get_net_actuation_output_port(self: pydrake.multibody.plant.MultibodyPlant_[AutoDiffXd], model_instance: pydrake.multibody.tree.ModelInstanceIndex) -> pydrake.systems.framework.OutputPort_[AutoDiffXd]
Returns a constant reference to the output port that reports actuation values applied through joint actuators, for a specific model instance. Models that include PD controllers will include their contribution in this port, refer to mbp_actuation “Actuation” for further details. This is a vector valued port with entries ordered by monotonically increasing JointActuatorIndex within
model_instance
.Every model instance in
this
plant model has a net actuation output port, even if zero sized (for model instance with no actuators).In a discrete-time plant, the use_sampled_output_ports setting affects the output of this port. See output_port_sampling “Output port sampling” for details. When sampling is enabled and the plant has not yet taken a step, the output value will be all zeros.
Note
PD controllers are not considered for actuators on locked joints, see Joint::Lock(). Therefore they do not contribute to this port.
- Precondition:
Finalize() was already called on
this
plant.
- Raises
RuntimeError if called before Finalize() –
- get_reaction_forces_output_port(self: pydrake.multibody.plant.MultibodyPlant_[AutoDiffXd]) pydrake.systems.framework.OutputPort_[AutoDiffXd]
Returns the port for joint reaction forces. A Joint models the kinematical relationship which characterizes the possible relative motion between two bodies. In Drake, a joint connects a frame
Jp
on parent body P with a frameJc
on a child body C. This usage of the terms parent and child is just a convention and implies nothing about the inboard-outboard relationship between the bodies. Since a Joint imposes a kinematical relationship which characterizes the possible relative motion between frames Jp and Jc, reaction forces on each body are established. That is, we could cut the model at the joint and replace it with equivalent forces equal to these reaction forces in order to attain the same motions of the mechanical system.This output port allows to evaluate the reaction force
F_CJc_Jc
on the child body C, atJc
, and expressed in Jc for all joints in the model. This port evaluates to a vector of type std::vector<SpatialForce<T>> and size num_joints() indexed by JointIndex, see Joint::index(). Each entry corresponds to the spatial forceF_CJc_Jc
applied on the joint’s child body C (Joint::child_body()), at the joint’s child frameJc
(Joint::frame_on_child()) and expressed in frameJc
.In a discrete-time plant, the use_sampled_output_ports setting affects the output of this port. See output_port_sampling “Output port sampling” for details. When sampling is enabled and the plant has not yet taken a step, the output value will be all zeros.
- Raises
RuntimeError if called pre-finalize. –
- get_sap_near_rigid_threshold(self: pydrake.multibody.plant.MultibodyPlant_[AutoDiffXd]) float
- Returns
the SAP near rigid regime threshold.
See also
See set_sap_near_rigid_threshold().
- get_source_id(self: pydrake.multibody.plant.MultibodyPlant_[AutoDiffXd]) Optional[pydrake.geometry.SourceId]
Returns the unique id identifying
this
plant as a source for a SceneGraph. Returnsnullopt
ifthis
plant did not register any geometry. This method can be called at any time during the lifetime ofthis
plant to query ifthis
plant has been registered with a SceneGraph, either pre- or post-finalize, see Finalize(). However, a geometry::SourceId is only assigned once at the first call of any of this plant’s geometry registration methods, and it does not change after that. Post-finalize calls will always return the same value.
- get_state_output_port(*args, **kwargs)
Overloaded function.
get_state_output_port(self: pydrake.multibody.plant.MultibodyPlant_[AutoDiffXd]) -> pydrake.systems.framework.OutputPort_[AutoDiffXd]
Returns a constant reference to the output port for the multibody state x = [q, v] of the model.
- Precondition:
Finalize() was already called on
this
plant.
- Raises
RuntimeError if called before Finalize() –
get_state_output_port(self: pydrake.multibody.plant.MultibodyPlant_[AutoDiffXd], model_instance: pydrake.multibody.tree.ModelInstanceIndex) -> pydrake.systems.framework.OutputPort_[AutoDiffXd]
Returns a constant reference to the output port for the state xᵢ = [qᵢ vᵢ] of model instance i. (Here qᵢ ⊆ q and vᵢ ⊆ v.)
- Precondition:
Finalize() was already called on
this
plant.
- Raises
RuntimeError if called before Finalize() –
RuntimeError if the model instance does not exist. –
- GetAccelerationLowerLimits(self: pydrake.multibody.plant.MultibodyPlant_[AutoDiffXd]) numpy.ndarray[numpy.float64[m, 1]]
Returns a vector of size
num_velocities()
containing the lower acceleration limits for every generalized velocity coordinate. These include joint and free body coordinates. Any unbounded or unspecified limits will be -infinity.- Raises
RuntimeError if called pre-finalize. –
- GetAccelerationUpperLimits(self: pydrake.multibody.plant.MultibodyPlant_[AutoDiffXd]) numpy.ndarray[numpy.float64[m, 1]]
Upper limit analog of GetAccelerationsLowerLimits(), where any unbounded or unspecified limits will be +infinity.
See also
GetAccelerationLowerLimits() for more information.
- GetActuatedJointIndices(self: pydrake.multibody.plant.MultibodyPlant_[AutoDiffXd], model_instance: pydrake.multibody.tree.ModelInstanceIndex) list[pydrake.multibody.tree.JointIndex]
Returns a list of actuated joint indices associated with
model_instance
.- Raises
RuntimeError if called pre-finalize. –
- GetActuatorNames(*args, **kwargs)
Overloaded function.
GetActuatorNames(self: pydrake.multibody.plant.MultibodyPlant_[AutoDiffXd], add_model_instance_prefix: bool = True) -> list[str]
Returns a list of string names corresponding to each element of the actuation vector. These strings take the form
{model_instance_name}_{joint_actuator_name}
, but the prefix may optionally be withheld usingadd_model_instance_prefix
.The returned names are guaranteed to be unique if
add_model_instance_prefix
isTrue
(the default).- Raises
RuntimeError if the plant is not finalized. –
GetActuatorNames(self: pydrake.multibody.plant.MultibodyPlant_[AutoDiffXd], model_instance: pydrake.multibody.tree.ModelInstanceIndex, add_model_instance_prefix: bool = False) -> list[str]
Returns a list of string names corresponding to each element of the actuation vector. These strings take the form
{model_instance_name}_{joint_actuator_name}
, but the prefix may optionally be withheld usingadd_model_instance_prefix
.The returned names are guaranteed to be unique.
- Raises
RuntimeError if the plant is not finalized or if the –
model_instance` is invalid –
- GetBodiesKinematicallyAffectedBy(self: pydrake.multibody.plant.MultibodyPlant_[AutoDiffXd], joint_indexes: list[pydrake.multibody.tree.JointIndex]) list[pydrake.multibody.tree.BodyIndex]
Returns all bodies whose kinematics are transitively affected by the given vector of Joints. The affected bodies are returned in increasing order of body indexes. Note that this is a kinematic relationship rather than a dynamic one. For example, if one of the inboard joints is a free (6dof) joint, the kinematic influence is still felt even though dynamically there would be no influence on the outboard body. This function can be only be called post-finalize, see Finalize().
- Raises
RuntimeError if any of the given joint has an invalid index, –
doesn't correspond to a mobilizer, or is welded. –
- GetBodiesWeldedTo(self: pydrake.multibody.plant.MultibodyPlant_[AutoDiffXd], body: pydrake.multibody.tree.RigidBody_[AutoDiffXd]) list[pydrake.multibody.tree.RigidBody_[AutoDiffXd]]
Returns all bodies that are transitively welded, or rigidly affixed, to
body
, per these two definitions:A body is always considered welded to itself.
2. Two unique bodies are considered welded together exclusively by the presence of a weld joint, not by other constructs that prevent mobility (e.g. constraints).
This method can be called at any time during the lifetime of
this
plant, either pre- or post-finalize, see Finalize().Meant to be used with
CollectRegisteredGeometries
.The following example demonstrates filtering collisions between all bodies rigidly affixed to a door (which could be moving) and all bodies rigidly affixed to the world:
Click to expand C++ code...
GeometrySet g_world = plant.CollectRegisteredGeometries( plant.GetBodiesWeldedTo(plant.world_body())); GeometrySet g_door = plant.CollectRegisteredGeometries( plant.GetBodiesWeldedTo(plant.GetBodyByName("door"))); scene_graph.ExcludeCollisionsBetweeen(g_world, g_door);
Note
Usages akin to this example may introduce redundant collision filtering; this will not have a functional impact, but may have a minor performance impact.
- Returns
all bodies rigidly fixed to
body
. This does not return the bodies in any prescribed order.- Raises
RuntimeError if body is not part of this plant. –
- GetBodyByName(*args, **kwargs)
Overloaded function.
GetBodyByName(self: pydrake.multibody.plant.MultibodyPlant_[AutoDiffXd], name: str) -> pydrake.multibody.tree.RigidBody_[AutoDiffXd]
Returns a constant reference to a body that is identified by the string
name
inthis
MultibodyPlant.- Raises
RuntimeError if there is no body with the requested name. –
RuntimeError if the body name occurs in multiple model instances. –
See also
HasBodyNamed() to query if there exists a body in
this
MultibodyPlant with a given specified name.GetBodyByName(self: pydrake.multibody.plant.MultibodyPlant_[AutoDiffXd], name: str, model_instance: pydrake.multibody.tree.ModelInstanceIndex) -> pydrake.multibody.tree.RigidBody_[AutoDiffXd]
Returns a constant reference to the body that is uniquely identified by the string
name
andmodel_instance
inthis
MultibodyPlant.- Raises
RuntimeError if there is no body with the requested name. –
See also
HasBodyNamed() to query if there exists a body in
this
MultibodyPlant with a given specified name.
- GetBodyFrameIdIfExists(self: pydrake.multibody.plant.MultibodyPlant_[AutoDiffXd], body_index: pydrake.multibody.tree.BodyIndex) Optional[pydrake.geometry.FrameId]
If the body with
body_index
belongs to the called plant, it returns the geometry::FrameId associated with it. Otherwise, it returns nullopt.
- GetBodyFrameIdOrThrow(self: pydrake.multibody.plant.MultibodyPlant_[AutoDiffXd], body_index: pydrake.multibody.tree.BodyIndex) pydrake.geometry.FrameId
If the body with
body_index
belongs to the called plant, it returns the geometry::FrameId associated with it. Otherwise this method throws an exception.- Raises
RuntimeError if the called plant does not have the body indicated –
by body_index. –
- GetBodyFromFrameId(self: pydrake.multibody.plant.MultibodyPlant_[AutoDiffXd], arg0: pydrake.geometry.FrameId) pydrake.multibody.tree.RigidBody_[AutoDiffXd]
Given a geometry frame identifier, returns a pointer to the body associated with that id (nullptr if there is no such body).
- GetBodyIndices(self: pydrake.multibody.plant.MultibodyPlant_[AutoDiffXd], model_instance: pydrake.multibody.tree.ModelInstanceIndex) list[pydrake.multibody.tree.BodyIndex]
Returns a list of body indices associated with
model_instance
.
- GetCollisionGeometriesForBody(self: pydrake.multibody.plant.MultibodyPlant_[AutoDiffXd], body: pydrake.multibody.tree.RigidBody_[AutoDiffXd]) list[pydrake.geometry.GeometryId]
Returns an array of GeometryId’s identifying the different contact geometries for
body
previously registered with a SceneGraph.Note
This method can be called at any time during the lifetime of
this
plant, either pre- or post-finalize, see Finalize(). Post-finalize calls will always return the same value.See also
RegisterCollisionGeometry(), Finalize()
- GetConstraintActiveStatus(self: pydrake.multibody.plant.MultibodyPlant_[AutoDiffXd], context: pydrake.systems.framework.Context_[AutoDiffXd], id: pydrake.multibody.tree.MultibodyConstraintId) bool
Returns the active status of the constraint given by
id
incontext
.- Raises
RuntimeError if the MultibodyPlant has not been finalized. –
RuntimeError if id does not belong to any multibody constraint –
in context. –
- GetConstraintIds(self: pydrake.multibody.plant.MultibodyPlant_[AutoDiffXd]) list[pydrake.multibody.tree.MultibodyConstraintId]
Returns a list of all constraint identifiers. The returned vector becomes invalid after any calls to Add*Constraint() or RemoveConstraint().
- static GetDefaultContactSurfaceRepresentation(time_step: float) pydrake.geometry.HydroelasticContactRepresentation
Return the default value for contact representation, given the desired time step. Discrete systems default to use polygons; continuous systems default to use triangles.
- GetDefaultFreeBodyPose(self: pydrake.multibody.plant.MultibodyPlant_[AutoDiffXd], body: pydrake.multibody.tree.RigidBody_[AutoDiffXd]) pydrake.math.RigidTransform
Gets the default pose of
body
as set by SetDefaultFreeBodyPose(). If no pose is specified for the body, returns the identity pose.- Parameter
body
: RigidBody whose default pose will be retrieved.
- Returns
X_PB
: The pose of the free body relative to its parent frame.
Note
The parent frame is not necessarily the world frame. See mbp_working_with_free_bodies “above for details”.
- Parameter
- GetDefaultPositions(*args, **kwargs)
Overloaded function.
GetDefaultPositions(self: pydrake.multibody.plant.MultibodyPlant_[AutoDiffXd]) -> numpy.ndarray[object[m, 1]]
Gets the default positions for the plant, which can be changed via SetDefaultPositions().
- Raises
RuntimeError if the plant is not finalized. –
GetDefaultPositions(self: pydrake.multibody.plant.MultibodyPlant_[AutoDiffXd], model_instance: pydrake.multibody.tree.ModelInstanceIndex) -> numpy.ndarray[object[m, 1]]
Gets the default positions for the plant for a given model instance, which can be changed via SetDefaultPositions().
- Raises
RuntimeError if the plant is not finalized, or if the –
model_instance is invalid, –
- GetEffortLowerLimits(self: pydrake.multibody.plant.MultibodyPlant_[AutoDiffXd]) numpy.ndarray[numpy.float64[m, 1]]
Returns a vector of size
num_actuated_dofs()
containing the lower effort limits for every actuator. Any unbounded or unspecified limits will be -∞. The returned vector is indexed by JointActuatorIndex, see JointActuator::index().See also
GetEffortUpperLimits()
- Raises
RuntimeError if called pre-finalize. –
- GetEffortUpperLimits(self: pydrake.multibody.plant.MultibodyPlant_[AutoDiffXd]) numpy.ndarray[numpy.float64[m, 1]]
Returns a vector of size
num_actuated_dofs()
containing the upper effort limits for every actuator. Any unbounded or unspecified limits will be +∞. The returned vector is indexed by JointActuatorIndex, see JointActuator::index().See also
GetEffortLowerLimits()
- Raises
RuntimeError if called pre-finalize. –
- GetFloatingBaseBodies(self: pydrake.multibody.plant.MultibodyPlant_[AutoDiffXd]) set[pydrake.multibody.tree.BodyIndex]
Returns the set of body indices corresponding to the floating base bodies in the model, in no particular order.
- Raises
RuntimeError if called pre-finalize, see Finalize() –
- GetFrameByName(*args, **kwargs)
Overloaded function.
GetFrameByName(self: pydrake.multibody.plant.MultibodyPlant_[AutoDiffXd], name: str) -> pydrake.multibody.tree.Frame_[AutoDiffXd]
Returns a constant reference to a frame that is identified by the string
name
inthis
model.- Raises
RuntimeError if there is no frame with the requested name. –
RuntimeError if the frame name occurs in multiple model instances. –
See also
HasFrameNamed() to query if there exists a frame in
this
model with a given specified name.GetFrameByName(self: pydrake.multibody.plant.MultibodyPlant_[AutoDiffXd], name: str, model_instance: pydrake.multibody.tree.ModelInstanceIndex) -> pydrake.multibody.tree.Frame_[AutoDiffXd]
Returns a constant reference to the frame that is uniquely identified by the string
name
inmodel_instance
.- Raises
RuntimeError if there is no frame with the requested name. –
RuntimeError if model_instance is not valid for this model. –
See also
HasFrameNamed() to query if there exists a frame in
this
model with a given specified name.
- GetFrameIndices(self: pydrake.multibody.plant.MultibodyPlant_[AutoDiffXd], model_instance: pydrake.multibody.tree.ModelInstanceIndex) list[pydrake.multibody.tree.FrameIndex]
Returns a list of frame indices associated with
model_instance
.
- GetFreeBodyPose(self: pydrake.multibody.plant.MultibodyPlant_[AutoDiffXd], context: pydrake.systems.framework.Context_[AutoDiffXd], body: pydrake.multibody.tree.RigidBody_[AutoDiffXd]) pydrake.math.RigidTransform_[AutoDiffXd]
Gets the pose of a given
body
in the parent frame P.Note
The parent frame is not necessarily the world frame. See mbp_working_with_free_bodies “above for details”. To acquire X_WB, regardless of what P is, kinematics need to be evaluated by calling EvalBodyPoseInWorld().
- Raises
RuntimeError if body is not a free body in the model. –
RuntimeError if called pre-finalize. –
- GetJointActuatorByName(*args, **kwargs)
Overloaded function.
GetJointActuatorByName(self: pydrake.multibody.plant.MultibodyPlant_[AutoDiffXd], name: str) -> pydrake.multibody.tree.JointActuator_[AutoDiffXd]
Returns a constant reference to an actuator that is identified by the string
name
inthis
MultibodyPlant.- Raises
RuntimeError if there is no actuator with the requested name. –
RuntimeError if the actuator name occurs in multiple model –
instances. –
See also
HasJointActuatorNamed() to query if there exists an actuator in
this
MultibodyPlant with a given specified name.GetJointActuatorByName(self: pydrake.multibody.plant.MultibodyPlant_[AutoDiffXd], name: str, model_instance: pydrake.multibody.tree.ModelInstanceIndex) -> pydrake.multibody.tree.JointActuator_[AutoDiffXd]
Returns a constant reference to the actuator that is uniquely identified by the string
name
andmodel_instance
inthis
MultibodyPlant.- Raises
RuntimeError if there is no actuator with the requested name. –
RuntimeError if model_instance is not valid for this model. –
See also
HasJointActuatorNamed() to query if there exists an actuator in
this
MultibodyPlant with a given specified name.
- GetJointActuatorIndices(*args, **kwargs)
Overloaded function.
GetJointActuatorIndices(self: pydrake.multibody.plant.MultibodyPlant_[AutoDiffXd]) -> list[pydrake.multibody.tree.JointActuatorIndex]
Returns a list of all joint actuator indices. The vector is ordered by monotonically increasing JointActuatorIndex, but the indices will in general not be consecutive due to actuators that were removed.
GetJointActuatorIndices(self: pydrake.multibody.plant.MultibodyPlant_[AutoDiffXd], model_instance: pydrake.multibody.tree.ModelInstanceIndex) -> list[pydrake.multibody.tree.JointActuatorIndex]
Returns a list of joint actuator indices associated with
model_instance
. The vector is ordered by monotonically increasing JointActuatorIndex.- Raises
RuntimeError if called pre-finalize. –
- GetJointByName(self: pydrake.multibody.plant.MultibodyPlant_[AutoDiffXd], name: str, model_instance: Optional[pydrake.multibody.tree.ModelInstanceIndex] = None) pydrake.multibody.tree.Joint_[AutoDiffXd]
Returns a constant reference to a joint that is identified by the string
name
inthis
MultibodyPlant. If the optional template argument is supplied, then the returned value is downcast to the specifiedJointType
.- Template parameter
JointType
: The specific type of the Joint to be retrieved. It must be a subclass of Joint.
- Raises
RuntimeError if the named joint is not of type JointType or if –
there is no Joint with that name. –
RuntimeError if model_instance is not valid for this model. –
See also
HasJointNamed() to query if there exists a joint in
this
MultibodyPlant with a given specified name.- Template parameter
- GetJointIndices(*args, **kwargs)
Overloaded function.
GetJointIndices(self: pydrake.multibody.plant.MultibodyPlant_[AutoDiffXd]) -> list[pydrake.multibody.tree.JointIndex]
Returns a list of all joint indices. The vector is ordered by monotonically increasing JointIndex, but the indices will in general not be consecutive due to joints that were removed.
GetJointIndices(self: pydrake.multibody.plant.MultibodyPlant_[AutoDiffXd], model_instance: pydrake.multibody.tree.ModelInstanceIndex) -> list[pydrake.multibody.tree.JointIndex]
Returns a list of joint indices associated with
model_instance
.
- GetModelInstanceByName(self: pydrake.multibody.plant.MultibodyPlant_[AutoDiffXd], name: str) pydrake.multibody.tree.ModelInstanceIndex
Returns the index to the model instance that is uniquely identified by the string
name
inthis
MultibodyPlant.- Raises
RuntimeError if there is no instance with the requested name. –
See also
HasModelInstanceNamed() to query if there exists an instance in
this
MultibodyPlant with a given specified name.
- GetModelInstanceName(self: pydrake.multibody.plant.MultibodyPlant_[AutoDiffXd], model_instance: pydrake.multibody.tree.ModelInstanceIndex) str
Returns the name of a
model_instance
.- Raises
RuntimeError when model_instance does not correspond to a –
model in this model. –
- GetMutableJointByName(self: pydrake.multibody.plant.MultibodyPlant_[AutoDiffXd], name: str, model_instance: Optional[pydrake.multibody.tree.ModelInstanceIndex] = None) pydrake.multibody.tree.Joint_[AutoDiffXd]
Returns a constant reference to a joint that is identified by the string
name
inthis
MultibodyPlant. If the optional template argument is supplied, then the returned value is downcast to the specifiedJointType
.- Template parameter
JointType
: The specific type of the Joint to be retrieved. It must be a subclass of Joint.
- Raises
RuntimeError if the named joint is not of type JointType or if –
there is no Joint with that name. –
RuntimeError if model_instance is not valid for this model. –
See also
HasJointNamed() to query if there exists a joint in
this
MultibodyPlant with a given specified name.- Template parameter
- GetPositionLowerLimits(self: pydrake.multibody.plant.MultibodyPlant_[AutoDiffXd]) numpy.ndarray[numpy.float64[m, 1]]
Returns a vector of size
num_positions()
containing the lower position limits for every generalized position coordinate. These include joint and free body coordinates. Any unbounded or unspecified limits will be -infinity.- Raises
RuntimeError if called pre-finalize. –
- GetPositionNames(*args, **kwargs)
Overloaded function.
GetPositionNames(self: pydrake.multibody.plant.MultibodyPlant_[AutoDiffXd], add_model_instance_prefix: bool = True, always_add_suffix: bool = True) -> list[str]
Returns a list of string names corresponding to each element of the position vector. These strings take the form
{model_instance_name}_{joint_name}_{joint_position_suffix}
, but the prefix and suffix may optionally be withheld usingadd_model_instance_prefix
andalways_add_suffix
.- Parameter
always_add_suffix
: (optional). If true, then the suffix is always added. If false, then the suffix is only added for joints that have more than one position (in this case, not adding would lead to ambiguity).
The returned names are guaranteed to be unique if
add_model_instance_prefix
isTrue
(the default).- Raises
RuntimeError if the plant is not finalized. –
GetPositionNames(self: pydrake.multibody.plant.MultibodyPlant_[AutoDiffXd], model_instance: pydrake.multibody.tree.ModelInstanceIndex, add_model_instance_prefix: bool = False, always_add_suffix: bool = True) -> list[str]
Returns a list of string names corresponding to each element of the position vector. These strings take the form
{model_instance_name}_{joint_name}_{joint_position_suffix}
, but the prefix and suffix may optionally be withheld usingadd_model_instance_prefix
andalways_add_suffix
.- Parameter
always_add_suffix
: (optional). If true, then the suffix is always added. If false, then the suffix is only added for joints that have more than one position (in this case, not adding would lead to ambiguity).
The returned names are guaranteed to be unique.
- Raises
RuntimeError if the plant is not finalized or if the –
model_instance` is invalid –
- GetPositions(*args, **kwargs)
Overloaded function.
GetPositions(self: pydrake.multibody.plant.MultibodyPlant_[AutoDiffXd], context: pydrake.systems.framework.Context_[AutoDiffXd]) -> numpy.ndarray[object[m, 1]]
Returns a const vector reference to the vector of generalized positions q in a given Context.
Note
This method returns a reference to existing data, exhibits constant i.e., O(1) time complexity, and runs very quickly.
- Raises
RuntimeError if context does not correspond to the Context for –
a multibody model. –
GetPositions(self: pydrake.multibody.plant.MultibodyPlant_[AutoDiffXd], context: pydrake.systems.framework.Context_[AutoDiffXd], model_instance: pydrake.multibody.tree.ModelInstanceIndex) -> numpy.ndarray[object[m, 1]]
Returns a vector containing the generalized positions q of a specified model instance in a given Context.
Note
Returns a dense vector of dimension
num_positions(model_instance)
associated withmodel_instance
by copying fromcontext
.- Raises
RuntimeError if context does not correspond to the Context for –
a multibody model or model_instance is invalid. –
GetPositions(self: pydrake.multibody.plant.MultibodyPlant_[AutoDiffXd], context: pydrake.systems.framework.Context_[AutoDiffXd]) -> numpy.ndarray[object[m, 1]]
Returns a const vector reference to the vector of generalized positions q in a given Context.
Note
This method returns a reference to existing data, exhibits constant i.e., O(1) time complexity, and runs very quickly.
- Raises
RuntimeError if context does not correspond to the Context for –
a multibody model. –
GetPositions(self: pydrake.multibody.plant.MultibodyPlant_[AutoDiffXd], context: pydrake.systems.framework.Context_[AutoDiffXd], model_instance: pydrake.multibody.tree.ModelInstanceIndex) -> numpy.ndarray[object[m, 1]]
Returns a vector containing the generalized positions q of a specified model instance in a given Context.
Note
Returns a dense vector of dimension
num_positions(model_instance)
associated withmodel_instance
by copying fromcontext
.- Raises
RuntimeError if context does not correspond to the Context for –
a multibody model or model_instance is invalid. –
- GetPositionsAndVelocities(*args, **kwargs)
Overloaded function.
GetPositionsAndVelocities(self: pydrake.multibody.plant.MultibodyPlant_[AutoDiffXd], context: pydrake.systems.framework.Context_[AutoDiffXd]) -> numpy.ndarray[object[m, 1]]
Returns a const vector reference
[q; v]
to the generalized positions q and generalized velocities v in a given Context.Note
This method returns a reference to existing data, exhibits constant i.e., O(1) time complexity, and runs very quickly.
- Raises
RuntimeError if context does not correspond to the Context for –
a multibody model. –
GetPositionsAndVelocities(self: pydrake.multibody.plant.MultibodyPlant_[AutoDiffXd], context: pydrake.systems.framework.Context_[AutoDiffXd], model_instance: pydrake.multibody.tree.ModelInstanceIndex) -> numpy.ndarray[object[m, 1]]
Returns a vector
[q; v]
containing the generalized positions q and generalized velocities v of a specified model instance in a given Context.Note
Returns a dense vector of dimension
num_positions(model_instance) + num_velocities(model_instance)
associated withmodel_instance
by copying fromcontext
.- Raises
RuntimeError if context does not correspond to the Context for –
a multibody model or model_instance is invalid. –
- GetPositionsFromArray(self: pydrake.multibody.plant.MultibodyPlant_[AutoDiffXd], model_instance: pydrake.multibody.tree.ModelInstanceIndex, q: numpy.ndarray[object[m, 1]]) numpy.ndarray[object[m, 1]]
Returns a vector of generalized positions for
model_instance
from a vectorq_array
of generalized positions for the entire model model. This method throws an exception ifq
is not of size MultibodyPlant::num_positions().
- GetPositionUpperLimits(self: pydrake.multibody.plant.MultibodyPlant_[AutoDiffXd]) numpy.ndarray[numpy.float64[m, 1]]
Upper limit analog of GetPositionLowerLimits(), where any unbounded or unspecified limits will be +infinity.
See also
GetPositionLowerLimits() for more information.
- GetRigidBodyByName(*args, **kwargs)
Overloaded function.
GetRigidBodyByName(self: pydrake.multibody.plant.MultibodyPlant_[AutoDiffXd], name: str) -> pydrake.multibody.tree.RigidBody_[AutoDiffXd]
Returns a constant reference to a rigid body that is identified by the string
name
inthis
model.- Raises
RuntimeError if there is no body with the requested name. –
RuntimeError if the body name occurs in multiple model instances. –
RuntimeError if the requested body is not a RigidBody. –
See also
HasBodyNamed() to query if there exists a body in
this
model with a given specified name.GetRigidBodyByName(self: pydrake.multibody.plant.MultibodyPlant_[AutoDiffXd], name: str, model_instance: pydrake.multibody.tree.ModelInstanceIndex) -> pydrake.multibody.tree.RigidBody_[AutoDiffXd]
Returns a constant reference to the rigid body that is uniquely identified by the string
name
inmodel_instance
.- Raises
RuntimeError if there is no body with the requested name. –
RuntimeError if the requested body is not a RigidBody. –
RuntimeError if model_instance is not valid for this model. –
See also
HasBodyNamed() to query if there exists a body in
this
model with a given specified name.
- GetStateNames(*args, **kwargs)
Overloaded function.
GetStateNames(self: pydrake.multibody.plant.MultibodyPlant_[AutoDiffXd], add_model_instance_prefix: bool = True) -> list[str]
Returns a list of string names corresponding to each element of the multibody state vector. These strings take the form
{model_instance_name}_{joint_name}_{joint_position_suffix | joint_velocity_suffix}
, but the prefix may optionally be withheld usingadd_model_instance_prefix
.The returned names are guaranteed to be unique if
add_model_instance_prefix
isTrue
(the default).- Raises
RuntimeError if the plant is not finalized. –
GetStateNames(self: pydrake.multibody.plant.MultibodyPlant_[AutoDiffXd], model_instance: pydrake.multibody.tree.ModelInstanceIndex, add_model_instance_prefix: bool = False) -> list[str]
Returns a list of string names corresponding to each element of the multibody state vector. These strings take the form
{model_instance_name}_{joint_name}_{joint_position_suffix | joint_velocity_suffix}
, but the prefix may optionally be withheld usingadd_model_instance_prefix
.The returned names are guaranteed to be unique.
- Raises
RuntimeError if the plant is not finalized or if the –
model_instance` is invalid –
- GetTopologyGraphvizString(self: pydrake.multibody.plant.MultibodyPlant_[AutoDiffXd]) str
Returns a Graphviz string describing the topology of this plant. To render the string, use the Graphviz tool,
dot
. http://www.graphviz.org/Note: this method can be called either before or after
Finalize()
.
- GetUniqueFreeBaseBodyOrThrow(self: pydrake.multibody.plant.MultibodyPlant_[AutoDiffXd], model_instance: pydrake.multibody.tree.ModelInstanceIndex) pydrake.multibody.tree.RigidBody_[AutoDiffXd]
If there exists a unique base body that belongs to the model given by
model_instance
and that unique base body is free (see HasUniqueBaseBody()), return that free body. Throw an exception otherwise.- Raises
RuntimeError if called pre-finalize. –
RuntimeError if model_instance is not valid. –
RuntimeError if HasUniqueFreeBaseBody(model_instance) == false. –
- GetVelocities(*args, **kwargs)
Overloaded function.
GetVelocities(self: pydrake.multibody.plant.MultibodyPlant_[AutoDiffXd], context: pydrake.systems.framework.Context_[AutoDiffXd]) -> numpy.ndarray[object[m, 1]]
Returns a const vector reference to the generalized velocities v in a given Context.
Note
This method returns a reference to existing data, exhibits constant i.e., O(1) time complexity, and runs very quickly.
- Raises
RuntimeError if context does not correspond to the Context for –
a multibody model. –
GetVelocities(self: pydrake.multibody.plant.MultibodyPlant_[AutoDiffXd], context: pydrake.systems.framework.Context_[AutoDiffXd], model_instance: pydrake.multibody.tree.ModelInstanceIndex) -> numpy.ndarray[object[m, 1]]
Returns a vector containing the generalized velocities v of a specified model instance in a given Context.
Note
returns a dense vector of dimension
num_velocities(model_instance)
associated withmodel_instance
by copying fromcontext
.- Raises
RuntimeError if context does not correspond to the Context for –
a multibody model or model_instance is invalid. –
GetVelocities(self: pydrake.multibody.plant.MultibodyPlant_[AutoDiffXd], context: pydrake.systems.framework.Context_[AutoDiffXd]) -> numpy.ndarray[object[m, 1]]
Returns a const vector reference to the generalized velocities v in a given Context.
Note
This method returns a reference to existing data, exhibits constant i.e., O(1) time complexity, and runs very quickly.
- Raises
RuntimeError if context does not correspond to the Context for –
a multibody model. –
GetVelocities(self: pydrake.multibody.plant.MultibodyPlant_[AutoDiffXd], context: pydrake.systems.framework.Context_[AutoDiffXd], model_instance: pydrake.multibody.tree.ModelInstanceIndex) -> numpy.ndarray[object[m, 1]]
Returns a vector containing the generalized velocities v of a specified model instance in a given Context.
Note
returns a dense vector of dimension
num_velocities(model_instance)
associated withmodel_instance
by copying fromcontext
.- Raises
RuntimeError if context does not correspond to the Context for –
a multibody model or model_instance is invalid. –
- GetVelocitiesFromArray(self: pydrake.multibody.plant.MultibodyPlant_[AutoDiffXd], model_instance: pydrake.multibody.tree.ModelInstanceIndex, v: numpy.ndarray[object[m, 1]]) numpy.ndarray[object[m, 1]]
Returns a vector of generalized velocities for
model_instance
from a vectorv
of generalized velocities for the entire MultibodyPlant model. This method throws an exception if the input array is not of size MultibodyPlant::num_velocities().
- GetVelocityLowerLimits(self: pydrake.multibody.plant.MultibodyPlant_[AutoDiffXd]) numpy.ndarray[numpy.float64[m, 1]]
Returns a vector of size
num_velocities()
containing the lower velocity limits for every generalized velocity coordinate. These include joint and free body coordinates. Any unbounded or unspecified limits will be -infinity.- Raises
RuntimeError if called pre-finalize. –
- GetVelocityNames(*args, **kwargs)
Overloaded function.
GetVelocityNames(self: pydrake.multibody.plant.MultibodyPlant_[AutoDiffXd], add_model_instance_prefix: bool = True, always_add_suffix: bool = True) -> list[str]
Returns a list of string names corresponding to each element of the velocity vector. These strings take the form
{model_instance_name}_{joint_name}_{joint_velocity_suffix}
, but the prefix and suffix may optionally be withheld usingadd_model_instance_prefix
andalways_add_suffix
.- Parameter
always_add_suffix
: (optional). If true, then the suffix is always added. If false, then the suffix is only added for joints that have more than one position (in this case, not adding would lead to ambiguity).
The returned names are guaranteed to be unique if
add_model_instance_prefix
isTrue
(the default).- Raises
RuntimeError if the plant is not finalized. –
GetVelocityNames(self: pydrake.multibody.plant.MultibodyPlant_[AutoDiffXd], model_instance: pydrake.multibody.tree.ModelInstanceIndex, add_model_instance_prefix: bool = False, always_add_suffix: bool = True) -> list[str]
Returns a list of string names corresponding to each element of the velocity vector. These strings take the form
{model_instance_name}_{joint_name}_{joint_velocity_suffix}
, but the prefix and suffix may optionally be withheld usingadd_model_instance_prefix
andalways_add_suffix
.- Parameter
always_add_suffix
: (optional). If true, then the suffix is always added. If false, then the suffix is only added for joints that have more than one position (in this case, not adding would lead to ambiguity).
The returned names are guaranteed to be unique.
- Raises
RuntimeError if the plant is not finalized or if the –
model_instance` is invalid –
- GetVelocityUpperLimits(self: pydrake.multibody.plant.MultibodyPlant_[AutoDiffXd]) numpy.ndarray[numpy.float64[m, 1]]
Upper limit analog of GetVelocitysLowerLimits(), where any unbounded or unspecified limits will be +infinity.
See also
GetVelocityLowerLimits() for more information.
- GetVisualGeometriesForBody(self: pydrake.multibody.plant.MultibodyPlant_[AutoDiffXd], body: pydrake.multibody.tree.RigidBody_[AutoDiffXd]) list[pydrake.geometry.GeometryId]
Returns an array of GeometryId’s identifying the different visual geometries for
body
previously registered with a SceneGraph.Note
This method can be called at any time during the lifetime of
this
plant, either pre- or post-finalize, see Finalize(). Post-finalize calls will always return the same value.See also
RegisterVisualGeometry(), Finalize()
- gravity_field(self: pydrake.multibody.plant.MultibodyPlant_[AutoDiffXd]) pydrake.multibody.tree.UniformGravityFieldElement_[AutoDiffXd]
An accessor to the current gravity field.
- has_joint(self: pydrake.multibody.plant.MultibodyPlant_[AutoDiffXd], joint_index: pydrake.multibody.tree.JointIndex) bool
Returns true if plant has a joint with unique index
joint_index
. The value could be false if the joint was removed using RemoveJoint().
- has_joint_actuator(self: pydrake.multibody.plant.MultibodyPlant_[AutoDiffXd], actuator_index: pydrake.multibody.tree.JointActuatorIndex) bool
Returns true if plant has a joint actuator with unique index
actuator_index
. The value could be false if the actuator was removed using RemoveJointActuator().
- has_sampled_output_ports(self: pydrake.multibody.plant.MultibodyPlant_[AutoDiffXd]) bool
(Advanced) If
this
plant is continuous (i.e., is_discrete() isFalse
), returns false. Ifthis
plant is discrete, returns whether or not the output ports are sampled (change only at a time step boundary) or live (instantaneously reflect changes to the input ports). See output_port_sampling “Output port sampling” for details.
- HasBodyNamed(*args, **kwargs)
Overloaded function.
HasBodyNamed(self: pydrake.multibody.plant.MultibodyPlant_[AutoDiffXd], name: str) -> bool
- Returns
True
if a body namedname
was added to the MultibodyPlant.
See also
AddRigidBody().
- Raises
RuntimeError if the body name occurs in multiple model instances. –
HasBodyNamed(self: pydrake.multibody.plant.MultibodyPlant_[AutoDiffXd], name: str, model_instance: pydrake.multibody.tree.ModelInstanceIndex) -> bool
- Returns
True
if a body namedname
was added to the MultibodyPlant inmodel_instance
.
See also
AddRigidBody().
- Raises
RuntimeError if model_instance is not valid for this model. –
- HasFrameNamed(*args, **kwargs)
Overloaded function.
HasFrameNamed(self: pydrake.multibody.plant.MultibodyPlant_[AutoDiffXd], name: str) -> bool
- Returns
True
if a frame namedname
was added to the model.
See also
AddFrame().
- Raises
RuntimeError if the frame name occurs in multiple model instances. –
HasFrameNamed(self: pydrake.multibody.plant.MultibodyPlant_[AutoDiffXd], name: str, model_instance: pydrake.multibody.tree.ModelInstanceIndex) -> bool
- Returns
True
if a frame namedname
was added tomodel_instance
.
See also
AddFrame().
- Raises
RuntimeError if model_instance is not valid for this model. –
- HasJointActuatorNamed(*args, **kwargs)
Overloaded function.
HasJointActuatorNamed(self: pydrake.multibody.plant.MultibodyPlant_[AutoDiffXd], name: str) -> bool
- Returns
True
if an actuator namedname
was added to this model.
See also
AddJointActuator().
- Raises
RuntimeError if the actuator name occurs in multiple model –
instances. –
HasJointActuatorNamed(self: pydrake.multibody.plant.MultibodyPlant_[AutoDiffXd], name: str, model_instance: pydrake.multibody.tree.ModelInstanceIndex) -> bool
- Returns
True
if an actuator namedname
was added tomodel_instance
.
See also
AddJointActuator().
- Raises
RuntimeError if model_instance is not valid for this model. –
- HasJointNamed(*args, **kwargs)
Overloaded function.
HasJointNamed(self: pydrake.multibody.plant.MultibodyPlant_[AutoDiffXd], name: str) -> bool
- Returns
True
if a joint namedname
was added to this model.
See also
AddJoint().
- Raises
RuntimeError if the joint name occurs in multiple model instances. –
HasJointNamed(self: pydrake.multibody.plant.MultibodyPlant_[AutoDiffXd], name: str, model_instance: pydrake.multibody.tree.ModelInstanceIndex) -> bool
- Returns
True
if a joint namedname
was added tomodel_instance
.
See also
AddJoint().
- Raises
RuntimeError if model_instance is not valid for this model. –
- HasModelInstanceNamed(self: pydrake.multibody.plant.MultibodyPlant_[AutoDiffXd], name: str) bool
- Returns
True
if a model instance namedname
was added to this model.
See also
AddModelInstance().
- HasUniqueFreeBaseBody(self: pydrake.multibody.plant.MultibodyPlant_[AutoDiffXd], model_instance: pydrake.multibody.tree.ModelInstanceIndex) bool
Return true if there exists a unique base body in the model given by
model_instance
and that unique base body is free.- Raises
RuntimeError if called pre-finalize. –
RuntimeError if model_instance is not valid. –
- is_finalized(self: pydrake.multibody.plant.MultibodyPlant_[AutoDiffXd]) bool
Returns
True
if this MultibodyPlant was finalized with a call to Finalize().See also
Finalize().
- is_gravity_enabled(self: pydrake.multibody.plant.MultibodyPlant_[AutoDiffXd], model_instance: pydrake.multibody.tree.ModelInstanceIndex) bool
- Returns
True
iff gravity is enabled formodel_instance
.
See also
set_gravity_enabled().
- Raises
RuntimeError if the model instance is invalid. –
- IsAnchored(self: pydrake.multibody.plant.MultibodyPlant_[AutoDiffXd], body: pydrake.multibody.tree.RigidBody_[AutoDiffXd]) bool
Returns
True
ifbody
is anchored (i.e. the kinematic path betweenbody
and the world only contains weld joints.)- Raises
RuntimeError if called pre-finalize. –
- IsVelocityEqualToQDot(self: pydrake.multibody.plant.MultibodyPlant_[AutoDiffXd]) bool
Returns true iff the generalized velocity v is exactly the time derivative q̇ of the generalized coordinates q. In this case MapQDotToVelocity() and MapVelocityToQDot() implement the identity map. This method is, in the worst case, O(n), where n is the number of joints.
- MakeActuationMatrix(self: pydrake.multibody.plant.MultibodyPlant_[AutoDiffXd]) numpy.ndarray[object[m, n]]
This method creates an actuation matrix B mapping a vector of actuation values u into generalized forces
tau_u = B * u
, where B is a matrix of sizenv x nu
withnu
equal to num_actuated_dofs() andnv
equal to num_velocities(). The vector u of actuation values is of size num_actuated_dofs(). For a given JointActuator,u[JointActuator::input_start()]
stores the value for the external actuation corresponding to that actuator.tau_u
on the other hand is indexed by generalized velocity indices according toJoint::velocity_start()
.Warning
B is a permutation matrix. While making a permutation has
O(n)
complexity, making a full B matrix hasO(n²)
complexity. For most applications this cost can be neglected but it could become significant for very large systems.
- MakeActuationMatrixPseudoinverse(self: pydrake.multibody.plant.MultibodyPlant_[AutoDiffXd]) scipy.sparse.csc_matrix[numpy.float64]
Creates the pseudoinverse of the actuation matrix B directly (without requiring an explicit inverse calculation). See MakeActuationMatrix().
Notably, when B is full row rank (the system is fully actuated), then the pseudoinverse is a true inverse.
- MakeActuatorSelectorMatrix(*args, **kwargs)
Overloaded function.
MakeActuatorSelectorMatrix(self: pydrake.multibody.plant.MultibodyPlant_[AutoDiffXd], user_to_actuator_index_map: list[pydrake.multibody.tree.JointActuatorIndex]) -> numpy.ndarray[numpy.float64[m, n]]
This method allows user to map a vector
uₛ
containing the actuation for a set of selected actuators into the vector u containing the actuation values forthis
full model. The mapping, or selection, is returned in the form of a selector matrix Su such thatu = Su⋅uₛ
. The size nₛ of uₛ is always smaller or equal than the size of the full vector of actuation values u. That is, a user might be interested in only a given subset of actuators in the model.This selection matrix is particularly useful when adding PID control on a portion of the state, see systems::controllers::PidController.
A user specifies the preferred order in uₛ via
user_to_actuator_index_map
. The actuation values in uₛ are a concatenation of the values for each actuator in the order they appear inuser_to_actuator_index_map
. The actuation value in the full vector of actuation valuesu
for a particular actuator can be found at offset JointActuator::input_start().MakeActuatorSelectorMatrix(self: pydrake.multibody.plant.MultibodyPlant_[AutoDiffXd], user_to_joint_index_map: list[pydrake.multibody.tree.JointIndex]) -> numpy.ndarray[numpy.float64[m, n]]
Alternative signature to build an actuation selector matrix
Su
such thatu = Su⋅uₛ
, where u is the vector of actuation values for the full model (see get_actuation_input_port()) and uₛ is a vector of actuation values for the actuators acting on the joints listed byuser_to_joint_index_map
. It is assumed that all joints referenced byuser_to_joint_index_map
are actuated. See MakeActuatorSelectorMatrix(const std::vector<JointActuatorIndex>&) for details.- Raises
RuntimeError if any of the joints in user_to_joint_index_map –
does not have an actuator. –
- MakeStateSelectorMatrix(self: pydrake.multibody.plant.MultibodyPlant_[AutoDiffXd], user_to_joint_index_map: list[pydrake.multibody.tree.JointIndex]) numpy.ndarray[numpy.float64[m, n]]
This method allows users to map the state of
this
model, x, into a vector of selected state xₛ with a given preferred ordering. The mapping, or selection, is returned in the form of a selector matrix Sx such thatxₛ = Sx⋅x
. The size nₛ of xₛ is always smaller or equal than the size of the full state x. That is, a user might be interested in only a given portion of the full state x.This selection matrix is particularly useful when adding PID control on a portion of the state, see systems::controllers::PidController.
A user specifies the preferred order in xₛ via
user_to_joint_index_map
. The selected state is built such that selected positions are followed by selected velocities, as inxₛ = [qₛ, vₛ]
. The positions in qₛ are a concatenation of the positions for each joint in the order they appear inuser_to_joint_index_map
. That is, the positions foruser_to_joint_index_map[0]
are first, followed by the positions foruser_to_joint_index_map[1]
, etc. Similarly for the selected velocities vₛ.- Raises
RuntimeError if there are repeated indices in –
user_to_joint_index_map` –
- MapQDotToVelocity(self: pydrake.multibody.plant.MultibodyPlant_[AutoDiffXd], context: pydrake.systems.framework.Context_[AutoDiffXd], qdot: numpy.ndarray[object[m, 1]]) numpy.ndarray[object[m, 1]]
Transforms the time derivative
qdot
of the generalized positions vectorq
(stored incontext
) to generalized velocitiesv
. v andq̇
are related linearly byq̇ = N(q)⋅v
. AlthoughN(q)
is not necessarily square, its left pseudo-inverseN⁺(q)
can be used to invert that relationship without residual error, provided thatqdot
is in the range space ofN(q)
(that is, if it could have been produced asq̇ = N(q)⋅v
for somev
). Using the configurationq
stored in the givencontext
this method calculatesv = N⁺(q)⋅q̇
.- Parameter
context
: The context containing the state of the model.
- Parameter
qdot
: A vector containing the time derivatives of the generalized positions. This method aborts if
qdot
is not of size num_positions().- Parameter
v
: A valid (non-null) pointer to a vector in
ℛⁿ
with n the number of generalized velocities. This method aborts if v is nullptr or if it is not of size num_velocities().
See also
MapVelocityToQDot()
See also
Mobilizer::MapQDotToVelocity()
- Parameter
- MapVelocityToQDot(self: pydrake.multibody.plant.MultibodyPlant_[AutoDiffXd], context: pydrake.systems.framework.Context_[AutoDiffXd], v: numpy.ndarray[object[m, 1]]) numpy.ndarray[object[m, 1]]
Transforms generalized velocities v to time derivatives
qdot
of the generalized positions vectorq
(stored incontext
). v andqdot
are related linearly byq̇ = N(q)⋅v
. Using the configurationq
stored in the givencontext
this method calculatesq̇ = N(q)⋅v
.- Parameter
context
: The context containing the state of the model.
- Parameter
v
: A vector of generalized velocities for this model. This method aborts if v is not of size num_velocities().
- Parameter
qdot
: A valid (non-null) pointer to a vector in
ℝⁿ
with n being the number of generalized positions in this model, given bynum_positions()
. This method aborts ifqdot
is nullptr or if it is not of size num_positions().
See also
MapQDotToVelocity()
See also
Mobilizer::MapVelocityToQDot()
- Parameter
- mutable_deformable_model(self: pydrake.multibody.plant.MultibodyPlant_[AutoDiffXd]) drake::multibody::DeformableModel<Eigen::AutoDiffScalar<Eigen::Matrix<double, -1, 1, 0, -1, 1> > >
Returns a mutable reference to the DeformableModel owned by this plant.
- Raises
RuntimeError if the plant is finalized. –
Warning
This feature is considered to be experimental and may change or be removed at any time, without any deprecation notice ahead of time.
- mutable_gravity_field(self: pydrake.multibody.plant.MultibodyPlant_[AutoDiffXd]) pydrake.multibody.tree.UniformGravityFieldElement_[AutoDiffXd]
A mutable accessor to the current gravity field.
- num_actuated_dofs(*args, **kwargs)
Overloaded function.
num_actuated_dofs(self: pydrake.multibody.plant.MultibodyPlant_[AutoDiffXd]) -> int
Returns the total number of actuated degrees of freedom. That is, the vector of actuation values u has this size. See AddJointActuator().
num_actuated_dofs(self: pydrake.multibody.plant.MultibodyPlant_[AutoDiffXd], model_instance: pydrake.multibody.tree.ModelInstanceIndex) -> int
Returns the total number of actuated degrees of freedom for a specific model instance. That is, the vector of actuation values u has this size. See AddJointActuator().
- Raises
RuntimeError if called pre-finalize. –
- num_actuators(*args, **kwargs)
Overloaded function.
num_actuators(self: pydrake.multibody.plant.MultibodyPlant_[AutoDiffXd]) -> int
Returns the number of joint actuators in the model.
See also
AddJointActuator().
num_actuators(self: pydrake.multibody.plant.MultibodyPlant_[AutoDiffXd], model_instance: pydrake.multibody.tree.ModelInstanceIndex) -> int
Returns the number of actuators for a specific model instance.
- Raises
RuntimeError if called pre-finalize. –
- num_bodies(self: pydrake.multibody.plant.MultibodyPlant_[AutoDiffXd]) int
Returns the number of RigidBody elements in the model, including the “world” RigidBody, which is always part of the model.
See also
AddRigidBody().
- num_collision_geometries(self: pydrake.multibody.plant.MultibodyPlant_[AutoDiffXd]) int
Returns the number of geometries registered for contact modeling. This method can be called at any time during the lifetime of
this
plant, either pre- or post-finalize, see Finalize(). Post-finalize calls will always return the same value.
- num_constraints(self: pydrake.multibody.plant.MultibodyPlant_[AutoDiffXd]) int
Returns the total number of constraints specified by the user.
- num_force_elements(self: pydrake.multibody.plant.MultibodyPlant_[AutoDiffXd]) int
Returns the number of ForceElement objects.
See also
AddForceElement().
- num_frames(self: pydrake.multibody.plant.MultibodyPlant_[AutoDiffXd]) int
Returns the number of Frame objects in this model. Frames include body frames associated with each of the bodies, including the world body. This means the minimum number of frames is one.
- num_joints(self: pydrake.multibody.plant.MultibodyPlant_[AutoDiffXd]) int
Returns the number of joints in the model.
See also
AddJoint().
- num_model_instances(self: pydrake.multibody.plant.MultibodyPlant_[AutoDiffXd]) int
Returns the number of model instances in the model.
See also
AddModelInstance().
- num_multibody_states(*args, **kwargs)
Overloaded function.
num_multibody_states(self: pydrake.multibody.plant.MultibodyPlant_[AutoDiffXd]) -> int
Returns the size of the multibody system state vector x = [q v]. This will be
num_positions()
plusnum_velocities()
.- Raises
RuntimeError if called pre-finalize. –
num_multibody_states(self: pydrake.multibody.plant.MultibodyPlant_[AutoDiffXd], model_instance: pydrake.multibody.tree.ModelInstanceIndex) -> int
Returns the size of the multibody system state vector xᵢ = [qᵢ vᵢ] for model instance i. (Here qᵢ ⊆ q and vᵢ ⊆ v.) will be
num_positions(model_instance)
plusnum_velocities(model_instance)
.- Raises
RuntimeError if called pre-finalize. –
- num_positions(*args, **kwargs)
Overloaded function.
num_positions(self: pydrake.multibody.plant.MultibodyPlant_[AutoDiffXd]) -> int
Returns the size of the generalized position vector q for this model.
- Raises
RuntimeError if called pre-finalize. –
num_positions(self: pydrake.multibody.plant.MultibodyPlant_[AutoDiffXd], model_instance: pydrake.multibody.tree.ModelInstanceIndex) -> int
Returns the size of the generalized position vector qᵢ for model instance i.
- Raises
RuntimeError if called pre-finalize. –
- num_velocities(*args, **kwargs)
Overloaded function.
num_velocities(self: pydrake.multibody.plant.MultibodyPlant_[AutoDiffXd]) -> int
Returns the size of the generalized velocity vector v for this model.
- Raises
RuntimeError if called pre-finalize. –
num_velocities(self: pydrake.multibody.plant.MultibodyPlant_[AutoDiffXd], model_instance: pydrake.multibody.tree.ModelInstanceIndex) -> int
Returns the size of the generalized velocity vector vᵢ for model instance i.
- Raises
RuntimeError if called pre-finalize. –
- NumBodiesWithName(self: pydrake.multibody.plant.MultibodyPlant_[AutoDiffXd], name: str) int
- Returns
The total number of bodies (across all model instances) with the given name.
- RegisterAsSourceForSceneGraph(self: pydrake.multibody.plant.MultibodyPlant_[AutoDiffXd], scene_graph: pydrake.geometry.SceneGraph_[AutoDiffXd]) pydrake.geometry.SourceId
Registers
this
plant to serve as a source for an instance of SceneGraph. This registration allows MultibodyPlant to register geometry withscene_graph
for visualization and/or collision queries. The string returned bythis->get_name()
is passed to SceneGraph’s RegisterSource, so it is highly recommended that you give the plant a recognizable name before calling this. Successive registration calls with SceneGraph must be performed on the same instance to which the pointer argumentscene_graph
points to. Failure to do so will result in runtime exceptions.- Parameter
scene_graph
: A valid non nullptr to the SceneGraph instance for which
this
plant will sever as a source, see SceneGraph documentation for further details.
- Returns
the SourceId of
this
plant inscene_graph
. It can also later on be retrieved with get_source_id().- Raises
RuntimeError if called post-finalize. –
RuntimeError if scene_graph is the nullptr. –
RuntimeError if called more than once. –
- Parameter
- RegisterCollisionGeometry(*args, **kwargs)
Overloaded function.
RegisterCollisionGeometry(self: pydrake.multibody.plant.MultibodyPlant_[AutoDiffXd], body: pydrake.multibody.tree.RigidBody_[AutoDiffXd], X_BG: pydrake.math.RigidTransform, shape: pydrake.geometry.Shape, name: str, properties: pydrake.geometry.ProximityProperties) -> pydrake.geometry.GeometryId
Registers geometry in a SceneGraph with a given geometry::Shape to be used for the contact modeling of a given
body
. More than one geometry can be registered with a body, in which case the body’s contact geometry is the union of all geometries registered to that body.- Parameter
body
: The body for which geometry is being registered.
- Parameter
X_BG
: The fixed pose of the geometry frame G in the body frame B.
- Parameter
shape
: The geometry::Shape used for visualization. E.g.: geometry::Sphere, geometry::Cylinder, etc.
- Parameter
properties
: The proximity properties associated with the collision geometry. They must include the (
material
, coulomb_friction) property of type CoulombFriction<double>.
- Raises
RuntimeError if called post-finalize or if the properties are –
missing the coulomb friction property (or if it is of the wrong –
type) –
RegisterCollisionGeometry(self: pydrake.multibody.plant.MultibodyPlant_[AutoDiffXd], body: pydrake.multibody.tree.RigidBody_[AutoDiffXd], X_BG: pydrake.math.RigidTransform, shape: pydrake.geometry.Shape, name: str, coulomb_friction: pydrake.multibody.plant.CoulombFriction) -> pydrake.geometry.GeometryId
Overload which specifies a single property: coulomb_friction.
- RegisterVisualGeometry(*args, **kwargs)
Overloaded function.
RegisterVisualGeometry(self: pydrake.multibody.plant.MultibodyPlant_[AutoDiffXd], body: pydrake.multibody.tree.RigidBody_[AutoDiffXd], X_BG: pydrake.math.RigidTransform, shape: pydrake.geometry.Shape, name: str, diffuse_color: numpy.ndarray[numpy.float64[4, 1]]) -> pydrake.geometry.GeometryId
Overload for visual geometry registration. The following properties are set: - (“phong”, “diffuse”) =
diffuse_color
in both sets of properties. - (“label”, “id”) in perception properties as documented above.See mbp_geometry “the overview” for more details.
RegisterVisualGeometry(self: pydrake.multibody.plant.MultibodyPlant_[AutoDiffXd], body: pydrake.multibody.tree.RigidBody_[AutoDiffXd], geometry_instance: pydrake.geometry.GeometryInstance) -> pydrake.geometry.GeometryId
Registers the given
geometry_instance
in a SceneGraph to be used for visualization of a givenbody
.The roles that
geometry_instance
gets assigned (illustration/perception) in SceneGraph depend solely on the properties that have already been assigned togeometry_instance
. If any visual roles have been assigned, those will be the only roles used. If no visual roles have been assigned, then both roles will be assigned using the default set of property values.If the registered geometry has the perception role, it will have the (“label”, “id”) property. Possibly assigned as documented above.
See mbp_geometry “the overview” for more details.
- Parameter
body
: The body for which geometry is being registered.
- Parameter
geometry_instance
: The geometry to associate with the visual appearance of
body
.
- Raises
RuntimeError if geometry_instance is null. –
RuntimeError if called post-finalize. –
- Returns
the id for the registered geometry.
- RemoveConstraint(self: pydrake.multibody.plant.MultibodyPlant_[AutoDiffXd], id: pydrake.multibody.tree.MultibodyConstraintId) None
Removes the constraint
id
from the plant. Note that this will not remove constraints registered directly with DeformableModel.- Raises
RuntimeError if the MultibodyPlant has already been finalized. –
RuntimeError if id does not identify any multibody constraint –
in this plant. –
- RemoveJoint(self: pydrake.multibody.plant.MultibodyPlant_[AutoDiffXd], joint: pydrake.multibody.tree.Joint_[AutoDiffXd]) None
Removes and deletes
joint
from this MultibodyPlant. Any existing references tojoint
will become invalid, and future calls toget_joint(joint_index)
will throw an exception. Other elements of the plant may depend onjoint
at the time of removal and should be removed first. For example, a JointActuator that depends onjoint
should be removed with RemoveJointActuator(). Currently, we do not provide joint dependency tracking for force elements or constraints, so this function will throw an exception if there are any user-added force elements or constraints in the plant.- Raises
RuntimeError if the plant is already finalized. –
RuntimeError if the plant contains a non-zero number of user-added –
force elements or user-added constraints. –
RuntimeError if joint has a dependent JointActuator. –
See also
AddJoint()
Note
It is important to note that the JointIndex assigned to a joint is immutable. New joint indices are assigned in increasing order, even if a joint with a lower index has been removed. This has the consequence that when a joint is removed from the plant, the sequence
[0, num_joints())
is not necessarily the correct set of un-removed joint indices in the plant. Thus, it is important NOT to loop over joint indices sequentially from0
tonum_joints() - 1
. Instead users should use the provided GetJointIndices() and GetJointIndices(ModelIndex) functions:Click to expand C++ code...
for (JointIndex index : plant.GetJointIndices()) { const Joint<double>& joint = plant.get_joint(index); ... }
- RemoveJointActuator(self: pydrake.multibody.plant.MultibodyPlant_[AutoDiffXd], actuator: pydrake.multibody.tree.JointActuator_[AutoDiffXd]) None
Removes and deletes
actuator
from this MultibodyPlant. Any existing references toactuator
will become invalid, and future calls toget_joint_actuator(actuator_index)
will throw an exception.- Raises
RuntimeError if the plant is already finalized. –
See also
AddJointActuator()
- RenameModelInstance(self: pydrake.multibody.plant.MultibodyPlant_[AutoDiffXd], model_instance: pydrake.multibody.tree.ModelInstanceIndex, name: str) None
Renames an existing model instance.
- Parameter
model_instance
: The instance to rename.
- Parameter
name
: A string that uniquely identifies the instance within
this
model.
- Raises
RuntimeError if called after Finalize() –
RuntimeError if model_instance is not a valid index. –
RuntimeError if HasModelInstanceNamed(name) is true. –
- Parameter
- set_adjacent_bodies_collision_filters(self: pydrake.multibody.plant.MultibodyPlant_[AutoDiffXd], value: bool) None
Sets whether to apply collision filters to topologically adjacent bodies at Finalize() time. Filters are applied when there exists a joint between bodies, except in the case of 6-dof joints or joints in which the parent body is
world
.- Raises
RuntimeError iff called post-finalize. –
- set_contact_model(self: pydrake.multibody.plant.MultibodyPlant_[AutoDiffXd], model: pydrake.multibody.plant.ContactModel) None
Sets the contact model to be used by
this
MultibodyPlant, see ContactModel for available options. The default contact model is ContactModel::kHydroelasticWithFallback.- Raises
RuntimeError iff called post-finalize. –
- set_contact_surface_representation(self: pydrake.multibody.plant.MultibodyPlant_[AutoDiffXd], surface_representation: pydrake.geometry.HydroelasticContactRepresentation) None
Sets the representation of contact surfaces to be used by
this
MultibodyPlant. See geometry::HydroelasticContactRepresentation for available options. See GetDefaultContactSurfaceRepresentation() for explanation of default values.- Raises
RuntimeError if called post-finalize. –
- set_discrete_contact_approximation(self: pydrake.multibody.plant.MultibodyPlant_[AutoDiffXd], approximation: pydrake.multibody.plant.DiscreteContactApproximation) None
Sets the discrete contact model approximation.
Note
Calling this method also sets the contact solver type (see set_discrete_contact_solver()) according to: - DiscreteContactApproximation::kTamsi sets the solver to DiscreteContactSolver::kTamsi. - DiscreteContactApproximation::kSap, DiscreteContactApproximation::kSimilar and DiscreteContactApproximation::kLagged set the solver to DiscreteContactSolver::kSap.
- Raises
iff this plant is continuous (i.e. is_discrete() is –
False`. –
RuntimeError iff called post-finalize. –
- set_discrete_contact_solver(self: pydrake.multibody.plant.MultibodyPlant_[AutoDiffXd], contact_solver: pydrake.multibody.plant.DiscreteContactSolver) None
Sets the contact solver type used for discrete MultibodyPlant models.
Note
Calling this method also sets a default discrete approximation of contact (see set_discrete_contact_approximation()) according to: - DiscreteContactSolver::kTamsi sets the approximation to DiscreteContactApproximation::kTamsi. - DiscreteContactSolver::kSap sets the approximation to DiscreteContactApproximation::kSap.
Warning
This function is a no-op for continuous models (when is_discrete() is false.)
- Raises
RuntimeError iff called post-finalize. (Deprecated.) –
- Deprecated:
Use set_discrete_contact_approximation() to set the contact model approximation. The underlying solver will be inferred automatically. This will be removed from Drake on or after 2024-04-01.
- set_gravity_enabled(self: pydrake.multibody.plant.MultibodyPlant_[AutoDiffXd], model_instance: pydrake.multibody.tree.ModelInstanceIndex, is_enabled: bool) None
Sets is_gravity_enabled() for
model_instance
tois_enabled
. The effect ofis_enabled = false
is effectively equivalent to disabling (or making zero) gravity for all bodies in the specified model instance. By default is_gravity_enabled() equalsTrue
for all model instances.- Raises
RuntimeError if called post-finalize. –
RuntimeError if the model instance is invalid. –
- set_penetration_allowance(self: pydrake.multibody.plant.MultibodyPlant_[AutoDiffXd], penetration_allowance: float = 0.001) None
Sets the penetration allowance used to estimate the coefficients in the penalty method used to impose non-penetration among bodies. Refer to the section point_contact_defaults “Point Contact Default Parameters” for further details.
- Raises
RuntimeError if penetration_allowance is not positive. –
- set_sap_near_rigid_threshold(self: pydrake.multibody.plant.MultibodyPlant_[AutoDiffXd], near_rigid_threshold: float = 1.0) None
Non-negative dimensionless number typically in the range [0.0, 1.0], though larger values are allowed even if uncommon. This parameter controls the “near rigid” regime of the SAP solver, β in section V.B of [Castro et al., 2021]. It essentially controls a threshold value for the maximum amount of stiffness SAP can handle robustly. Beyond this value, stiffness saturates as explained in [Castro et al., 2021]. A value of 1.0 is a conservative choice to avoid ill-conditioning that might lead to softer than expected contact. If this is your case, consider turning off this approximation by setting this parameter to zero. For difficult cases where ill-conditioning is a problem, a small but non-zero number can be used, e.g. 1.0e-3.
- Raises
RuntimeError if near_rigid_threshold is negative. –
RuntimeError if called post-finalize. –
- set_stiction_tolerance(self: pydrake.multibody.plant.MultibodyPlant_[AutoDiffXd], v_stiction: float = 0.001) None
**** Stribeck model of friction
Currently MultibodyPlant uses the Stribeck approximation to model dry friction. The Stribeck model of friction is an approximation to Coulomb’s law of friction that allows using continuous time integration without the need to specify complementarity constraints. While this results in a simpler model immediately tractable with standard numerical methods for integration of ODE’s, it often leads to stiff dynamics that require an explicit integrator to take very small time steps. It is therefore recommended to use error controlled integrators when using this model or the discrete time stepping (see multibody_simulation). See stribeck_approximation for a detailed discussion of the Stribeck model.
Sets the stiction tolerance
v_stiction
for the Stribeck model, wherev_stiction
must be specified in m/s (meters per second.)v_stiction
defaults to a value of 1 millimeter per second. In selecting a value forv_stiction
, you must ask yourself the question, “When two objects are ostensibly in stiction, how much slip am I willing to allow?” There are two opposing design issues in picking a value for vₛ. On the one hand, small values of vₛ make the problem numerically stiff during stiction, potentially increasing the integration cost. On the other hand, it should be picked to be appropriate for the scale of the problem. For example, a car simulation could allow a “large” value for vₛ of 1 cm/s (1×10⁻² m/s), but reasonable stiction for grasping a 10 cm box might require limiting residual slip to 1×10⁻³ m/s or less. Ultimately, picking the largest viable value will allow your simulation to run faster and more robustly. Note thatv_stiction
is the slip velocity that we’d have when we are at edge of the friction cone. For cases when the friction force is well within the friction cone the slip velocity will always be smaller than this value. See also stribeck_approximation.- Raises
RuntimeError if v_stiction is non-positive. –
- SetActuationInArray(self: pydrake.multibody.plant.MultibodyPlant_[AutoDiffXd], model_instance: pydrake.multibody.tree.ModelInstanceIndex, u_instance: numpy.ndarray[object[m, 1]], u: Optional[numpy.ndarray[object[m, 1], flags.writeable]]) None
Given actuation values
u_instance
for the actuators inmodel_instance
, this function updates the actuation vector u for the entire plant model to which this actuator belongs to. Refer to mbp_actuation “Actuation” for further details.- Parameter
u_instance
: Actuation values for the model instance. Values are ordered by monotonically increasing JointActuatorIndex within the model instance.
- Parameter
u
: Actuation values for the entire plant model. The actuation value in
u
for a particular actuator must be found at offset JointActuator::input_start(). Only values corresponding tomodel_instance
are changed.
- Raises
RuntimeError if the size of u_instance is not equal to the –
number of actuation inputs for the joints of model_instance. –
- Parameter
- SetConstraintActiveStatus(self: pydrake.multibody.plant.MultibodyPlant_[AutoDiffXd], context: pydrake.systems.framework.Context_[AutoDiffXd], id: pydrake.multibody.tree.MultibodyConstraintId, status: bool) None
Sets the active status of the constraint given by
id
incontext
.- Raises
RuntimeError if the MultibodyPlant has not been finalized. –
RuntimeError if context == nullptr –
RuntimeError if id does not belong to any multibody constraint –
in context. –
- SetDefaultFreeBodyPose(*args, **kwargs)
Overloaded function.
SetDefaultFreeBodyPose(self: pydrake.multibody.plant.MultibodyPlant_[AutoDiffXd], body: pydrake.multibody.tree.RigidBody_[AutoDiffXd], X_PB: pydrake.math.RigidTransform) -> None
Sets the default pose of
body
. Ifbody.is_floating()
is true, this will affect subsequent calls to SetDefaultState(); otherwise, the only effect of the call is that the value will be echoed back in GetDefaultFreeBodyPose().Note
The parent frame is not necessarily the world frame. See mbp_working_with_free_bodies “above for details”.
- Parameter
body
: RigidBody whose default pose will be set.
- Parameter
X_PB
: Default pose of the body.
SetDefaultFreeBodyPose(self: pydrake.multibody.plant.MultibodyPlant_[AutoDiffXd], body: pydrake.multibody.tree.RigidBody_[AutoDiffXd], X_WB: pydrake.math.RigidTransform) -> None
Sets
context
to store the poseX_PB
of a givenbody
B in the parent frame P.Note
The parent frame is not necessarily the world frame. See mbp_working_with_free_bodies “above for details”.
- Raises
RuntimeError if body is not a free body in the model. –
RuntimeError if called pre-finalize. –
- SetDefaultPositions(*args, **kwargs)
Overloaded function.
SetDefaultPositions(self: pydrake.multibody.plant.MultibodyPlant_[AutoDiffXd], q: numpy.ndarray[numpy.float64[m, 1]]) -> None
Sets the default positions for the plant. Calls to CreateDefaultContext or SetDefaultContext/SetDefaultState will return a Context populated with these position values. They have no other effects on the dynamics of the system.
- Raises
RuntimeError if the plant is not finalized or if q is not of size –
num_positions() –
SetDefaultPositions(self: pydrake.multibody.plant.MultibodyPlant_[AutoDiffXd], model_instance: pydrake.multibody.tree.ModelInstanceIndex, q_instance: numpy.ndarray[numpy.float64[m, 1]]) -> None
Sets the default positions for the model instance. Calls to CreateDefaultContext or SetDefaultContext/SetDefaultState will return a Context populated with these position values. They have no other effects on the dynamics of the system.
- Raises
RuntimeError if the plant is not finalized, if the model_instance –
is invalid, or if the length of q_instance is not equal to –
num_positions(model_instance)` –
- SetDefaultState(self: pydrake.multibody.plant.MultibodyPlant_[AutoDiffXd], context: pydrake.systems.framework.Context_[AutoDiffXd], state: pydrake.systems.framework.State_[AutoDiffXd]) None
Sets
state
according to defaults set by the user for joints (e.g. RevoluteJoint::set_default_angle()) and free bodies (SetDefaultFreeBodyPose()). If the user does not specify defaults, the state corresponds to zero generalized positions and velocities.- Raises
RuntimeError if called pre-finalize. See Finalize() –
- SetFreeBodyPose(*args, **kwargs)
Overloaded function.
SetFreeBodyPose(self: pydrake.multibody.plant.MultibodyPlant_[AutoDiffXd], context: pydrake.systems.framework.Context_[AutoDiffXd], body: pydrake.multibody.tree.RigidBody_[AutoDiffXd], X_PB: pydrake.math.RigidTransform_[AutoDiffXd]) -> None
Sets
context
to store the poseX_PB
of a givenbody
B in the parent frame P.Note
The parent frame is not necessarily the world frame. See mbp_working_with_free_bodies “above for details”.
- Raises
RuntimeError if body is not a free body in the model. –
RuntimeError if called pre-finalize. –
SetFreeBodyPose(self: pydrake.multibody.plant.MultibodyPlant_[AutoDiffXd], context: pydrake.systems.framework.Context_[AutoDiffXd], body: pydrake.multibody.tree.RigidBody_[AutoDiffXd], X_WB: pydrake.math.RigidTransform_[AutoDiffXd]) -> None
Sets
context
to store the poseX_PB
of a givenbody
B in the parent frame P.Note
The parent frame is not necessarily the world frame. See mbp_working_with_free_bodies “above for details”.
- Raises
RuntimeError if body is not a free body in the model. –
RuntimeError if called pre-finalize. –
- SetFreeBodySpatialVelocity(*args, **kwargs)
Overloaded function.
SetFreeBodySpatialVelocity(self: pydrake.multibody.plant.MultibodyPlant_[AutoDiffXd], body: pydrake.multibody.tree.RigidBody_[AutoDiffXd], V_PB: pydrake.multibody.math.SpatialVelocity_[AutoDiffXd], context: pydrake.systems.framework.Context_[AutoDiffXd]) -> None
Sets
context
to store the spatial velocityV_PB
of a givenbody
B in its parent frame P.Note
The parent frame is not necessarily the world frame. See mbp_working_with_free_bodies “above for details”.
- Raises
RuntimeError if body is not a free body in the model. –
RuntimeError if called pre-finalize. –
SetFreeBodySpatialVelocity(self: pydrake.multibody.plant.MultibodyPlant_[AutoDiffXd], body: pydrake.multibody.tree.RigidBody_[AutoDiffXd], V_WB: pydrake.multibody.math.SpatialVelocity_[AutoDiffXd], context: pydrake.systems.framework.Context_[AutoDiffXd]) -> None
Sets
context
to store the spatial velocityV_PB
of a givenbody
B in its parent frame P.Note
The parent frame is not necessarily the world frame. See mbp_working_with_free_bodies “above for details”.
- Raises
RuntimeError if body is not a free body in the model. –
RuntimeError if called pre-finalize. –
- SetPositions(*args, **kwargs)
Overloaded function.
SetPositions(self: pydrake.multibody.plant.MultibodyPlant_[AutoDiffXd], context: pydrake.systems.framework.Context_[AutoDiffXd], q: numpy.ndarray[object[m, 1]]) -> None
Sets the generalized positions q in a given Context from a given vector. Prefer this method over GetMutablePositions().
- Raises
RuntimeError if context is nullptr, if context does not –
correspond to the Context for a multibody model, or if the length –
of q is not equal to num_positions() –
SetPositions(self: pydrake.multibody.plant.MultibodyPlant_[AutoDiffXd], context: pydrake.systems.framework.Context_[AutoDiffXd], model_instance: pydrake.multibody.tree.ModelInstanceIndex, q: numpy.ndarray[object[m, 1]]) -> None
Sets the generalized positions q in a given Context from a given vector. Prefer this method over GetMutablePositions().
- Raises
RuntimeError if context is nullptr, if context does not –
correspond to the Context for a multibody model, or if the length –
of q is not equal to num_positions() –
- SetPositionsAndVelocities(*args, **kwargs)
Overloaded function.
SetPositionsAndVelocities(self: pydrake.multibody.plant.MultibodyPlant_[AutoDiffXd], context: pydrake.systems.framework.Context_[AutoDiffXd], q_v: numpy.ndarray[object[m, 1]]) -> None
Sets generalized positions q and generalized velocities v in a given Context from a given vector [q; v]. Prefer this method over GetMutablePositionsAndVelocities().
- Raises
RuntimeError if context is nullptr, if context does not –
correspond to the context for a multibody model, or if the length –
of q_v is not equal to num_positions() + num_velocities() –
SetPositionsAndVelocities(self: pydrake.multibody.plant.MultibodyPlant_[AutoDiffXd], context: pydrake.systems.framework.Context_[AutoDiffXd], model_instance: pydrake.multibody.tree.ModelInstanceIndex, q_v: numpy.ndarray[object[m, 1]]) -> None
Sets generalized positions q and generalized velocities v from a given vector [q; v] for a specified model instance in a given Context.
- Raises
RuntimeError if context is nullptr, if context does not –
correspond to the Context for a multibody model, if the model –
instance index is invalid, or if the length of q_v is not –
equal to ``num_positions(model_instance) + –
num_velocities(model_instance)``. –
- SetPositionsInArray(self: pydrake.multibody.plant.MultibodyPlant_[AutoDiffXd], model_instance: pydrake.multibody.tree.ModelInstanceIndex, q_instance: numpy.ndarray[object[m, 1]], q: Optional[numpy.ndarray[object[m, 1], flags.writeable]]) None
Sets the vector of generalized positions for
model_instance
inq
usingq_instance
, leaving all other elements in the array untouched. This method throws an exception ifq
is not of size MultibodyPlant::num_positions() orq_instance
is not of sizeMultibodyPlant::num_positions(model_instance)
.
- SetUseSampledOutputPorts(self: pydrake.multibody.plant.MultibodyPlant_[AutoDiffXd], use_sampled_output_ports: bool) None
(Advanced) For a discrete-time plant, configures whether the output ports are sampled (the default) or live (opt-in). See output_port_sampling “Output port sampling” for details.
- Raises
RuntimeError if the plant is already finalized. –
RuntimeError if use_sampled_output_ports is True but –
this` MultibodyPlant is not a discrete model (is_discrete() = –
false) –
- SetVelocities(*args, **kwargs)
Overloaded function.
SetVelocities(self: pydrake.multibody.plant.MultibodyPlant_[AutoDiffXd], context: pydrake.systems.framework.Context_[AutoDiffXd], v: numpy.ndarray[object[m, 1]]) -> None
Sets the generalized velocities v in a given Context from a given vector. Prefer this method over GetMutableVelocities().
- Raises
RuntimeError if the context is nullptr, if the context does –
not correspond to the context for a multibody model, or if the –
length of v is not equal to num_velocities() –
SetVelocities(self: pydrake.multibody.plant.MultibodyPlant_[AutoDiffXd], context: pydrake.systems.framework.Context_[AutoDiffXd], model_instance: pydrake.multibody.tree.ModelInstanceIndex, v: numpy.ndarray[object[m, 1]]) -> None
Sets the generalized velocities v for a particular model instance in a given Context from a given vector.
- Raises
RuntimeError if the context is nullptr, if context does –
not correspond to the Context for a multibody model, if the model –
instance index is invalid, or if the length of v_instance is –
not equal to num_velocities(model_instance) –
- SetVelocitiesInArray(self: pydrake.multibody.plant.MultibodyPlant_[AutoDiffXd], model_instance: pydrake.multibody.tree.ModelInstanceIndex, v_instance: numpy.ndarray[object[m, 1]], v: Optional[numpy.ndarray[object[m, 1], flags.writeable]]) None
Sets the vector of generalized velocities for
model_instance
inv
usingv_instance
, leaving all other elements in the array untouched. This method throws an exception ifv
is not of size MultibodyPlant::num_velocities() orv_instance
is not of sizeMultibodyPlant::num_positions(model_instance)
.
- time_step(self: pydrake.multibody.plant.MultibodyPlant_[AutoDiffXd]) float
The time step (or period) used to model
this
plant as a discrete system with periodic updates. Returns 0 (zero) if the plant is modeled as a continuous system. This property of the plant is specified at construction and therefore this query can be performed either pre- or post-finalize, see Finalize().See also
MultibodyPlant::MultibodyPlant(double)
- WeldFrames(self: pydrake.multibody.plant.MultibodyPlant_[AutoDiffXd], frame_on_parent_F: pydrake.multibody.tree.Frame_[AutoDiffXd], frame_on_child_M: pydrake.multibody.tree.Frame_[AutoDiffXd], X_FM: pydrake.math.RigidTransform = RigidTransform(R=RotationMatrix([[1.0, 0.0, 0.0], [0.0, 1.0, 0.0], [0.0, 0.0, 1.0]]), p=[0.0, 0.0, 0.0])) pydrake.multibody.tree.WeldJoint_[AutoDiffXd]
Welds
frame_on_parent_F
andframe_on_child_M
with relative poseX_FM
. That is, the pose of frame M in frame F is fixed, with valueX_FM
. IfX_FM
is omitted, the identity transform will be used. The call to this method creates and adds a new WeldJoint to the model. The new WeldJoint is named as: frame_on_parent_F.name() + “_welds_to_” + frame_on_child_M.name().- Returns
a constant reference to the WeldJoint welding frames F and M.
- Raises
RuntimeError if the weld produces a duplicate joint name. –
- world_body(self: pydrake.multibody.plant.MultibodyPlant_[AutoDiffXd]) pydrake.multibody.tree.RigidBody_[AutoDiffXd]
Returns a constant reference to the world body.
- world_frame(self: pydrake.multibody.plant.MultibodyPlant_[AutoDiffXd]) pydrake.multibody.tree.RigidBodyFrame_[AutoDiffXd]
Returns a constant reference to the world frame.
- class pydrake.multibody.plant.MultibodyPlant_[Expression]
Bases:
pydrake.systems.framework.LeafSystem_[Expression]
MultibodyPlant is a Drake system framework representation (see systems::System) for the model of a physical system consisting of a collection of interconnected bodies. See multibody for an overview of concepts/notation.
actuation→ applied_generalized_force→ applied_spatial_force→ model_instance_name[i]_actuation→ model_instance_name[i]_desired_state→ geometry_query→ MultibodyPlant → state → body_poses → body_spatial_velocities → body_spatial_accelerations → generalized_acceleration → net_actuation → reaction_forces → contact_results → model_instance_name[i]_state → model_instance_name[i]_generalized_acceleration → model_instance_name[i]_generalized_contact_forces → model_instance_name[i]_net_actuation → geometry_pose → deformable_body_configuration The ports whose names begin with <em style=”color:gray”> model_instance_name[i]</em> represent groups of ports, one for each of the model_instances “model instances”, with i ∈ {0, …, N-1} for the N model instances. If a model instance does not contain any data of the indicated type the port will still be present but its value will be a zero-length vector. (Model instances
world_model_instance()
anddefault_model_instance()
always exist.)The ports shown in <span style=”color:green”>green</span> are for communication with Drake’s geometry::SceneGraph “SceneGraph” system for dealing with geometry.
MultibodyPlant provides a user-facing API for:
mbp_input_and_output_ports “Ports”:
Access input and output ports. - mbp_construction “Construction”: Add bodies, joints, frames, force elements, and actuators. - mbp_geometry “Geometry”: Register geometries to a provided SceneGraph instance. - mbp_contact_modeling “Contact modeling”: Select and parameterize contact models. - mbp_state_accessors_and_mutators “State access and modification”: Obtain and manipulate position and velocity state variables. - mbp_parameters “Parameters” Working with system parameters for various multibody elements. - mbp_working_with_free_bodies “Free bodies”: Work conveniently with free (floating) bodies. - mbp_kinematic_and_dynamic_computations “Kinematics and dynamics”: Perform systems::Context “Context”-dependent kinematic and dynamic queries. - mbp_system_matrix_computations “System matrices”: Explicitly form matrices that appear in the equations of motion. - mbp_introspection “Introspection”: Perform introspection to find out what’s in the MultibodyPlant.
**** Model Instances
A MultiBodyPlant may contain multiple model instances. Each model instance corresponds to a set of bodies and their connections (joints). Model instances provide methods to get or set the state of the set of bodies (e.g., through GetPositionsAndVelocities() and SetPositionsAndVelocities()), connecting controllers (through get_state_output_port() and get_actuation_input_port()), and organizing duplicate models (read through a parser). In fact, many MultibodyPlant methods are overloaded to allow operating on the entire plant or just the subset corresponding to the model instance; for example, one GetPositions() method obtains the generalized positions for the entire plant while another GetPositions() method obtains the generalized positions for model instance.
Model instances are frequently defined through SDFormat files (using the
model
tag) and are automatically created when SDFormat files are parsed (by Parser). There are two special multibody::ModelInstanceIndex values. The world body is always multibody::ModelInstanceIndex 0. multibody::ModelInstanceIndex 1 is reserved for all elements with no explicit model instance and is generally only relevant for elements created programmatically (and only when a model instance is not explicitly specified). Note that Parser creates model instances (resulting in a multibody::ModelInstanceIndex ≥ 2) as needed.See num_model_instances(), num_positions(), num_velocities(), num_actuated_dofs(), AddModelInstance() GetPositionsAndVelocities(), GetPositions(), GetVelocities(), SetPositionsAndVelocities(), SetPositions(), SetVelocities(), GetPositionsFromArray(), GetVelocitiesFromArray(), SetPositionsInArray(), SetVelocitiesInArray(), SetActuationInArray(), HasModelInstanceNamed(), GetModelInstanceName(), get_state_output_port(), get_actuation_input_port().
**** System dynamics
The state of a multibody system
x = [q; v]
is given by its generalized positions vector q, of sizenq
(see num_positions()), and by its generalized velocities vector v, of sizenv
(see num_velocities()).A MultibodyPlant can be constructed to be either continuous or discrete. The choice is indicated by the time_step passed to the constructor – a non-zero time_step indicates a discrete plant, while a zero time_step indicates continuous. A systems::Simulator “Simulator” will step a discrete plant using the indicated time_step, but will allow a numerical integrator to choose how to advance time for a continuous MultibodyPlant.
We’ll discuss continuous plant dynamics in this section. Discrete dynamics is more complicated and gets its own section below.
As a Drake systems::System “System”, MultibodyPlant implements the governing equations for a multibody dynamical system in the form
ẋ = f(t, x, u)
with t being time and u external inputs such as actuation forces. The governing equations for the dynamics of a multibody system modeled with MultibodyPlant are [Featherstone 2008, Jain 2010]:Click to expand C++ code...
q̇ = N(q)v (1) M(q)v̇ + C(q, v)v = τ
where
M(q)
is the mass matrix of the multibody system (including rigid body mass properties and reflected_inertia “reflected inertias”),C(q, v)v
contains Coriolis, centripetal, and gyroscopic terms andN(q)
is the kinematic coupling matrix describing the relationship between q̇ (the time derivatives of the generalized positions) and the generalized velocities v, [Seth 2010].N(q)
is annq x nv
matrix. The vectorτ ∈ ℝⁿᵛ
on the right hand side of Eq. (1) is the system’s generalized forces. These incorporate gravity, springs, externally applied body forces, constraint forces, and contact forces.**** Discrete system dynamics
We’ll start with the basic difference equation interpretation of a discrete plant and then explain some Drake-specific subtleties.
Note
We use “kinematics” here to refer to quantities that involve only position or velocity, and “dynamics” to refer to quantities that also involve forces.
By default, a discrete MultibodyPlant has these update dynamics:
x[0] = initial kinematics state variables x (={q, v}), s s[0] = empty (no sample yet)
s[n+1] = g(t[n], x[n], u[n]) record sample x[n+1] = f(t[n], x[n], u[n]) update kinematics yd[n+1] = gd(s) dynamic outputs use sampled values yk[n+1] = gk(x) kinematic outputs use current x
Optionally, output port sampling can be disabled. In that case we have:
x[n+1] = f(t[n], x[n], u[n]) update kinematics yd[n+1] = gd(g(t, x, u)) dynamic outputs use current values yk[n+1] = gk(x) kinematic outputs use current x
We’re using
yd
andyk
above to represent the calculated values of dynamic and kinematic output ports, resp. Kinematic output ports are those that depend only on position and velocity:state
, body_poses,body_spatial_velocities
. Everything else depends on forces so is a dynamic output port:body_spatial_accelerations
, generalized_acceleration,net_actuation
, reaction_forces, andcontact_results
.Use the function SetUseSampledOutputPorts() to choose which dynamics you prefer. The default behavior (output port sampling) is more efficient for simulation, but use slightly-different kinematics for the dynamic output port computations versus the kinematic output ports. Disabling output port sampling provides “live” output port results that are recalculated from the current state and inputs whenever changes occur. It also eliminates the sampling state variable (s above). Note that kinematic output ports (that is, those depending only on position and velocity) are always “live” – they are calculated as needed from the current (updated) state.
The reason that the default mode is more efficient for simulation is that the sample variable s records expensive-to-compute results (such as hydroelastic contact forces) that are needed to advance the state x. Those results are thus available for free at the start of step n. If instead we wait until after the state is updated to n+1, we would have to recalculate those expensive results at the new state in order to report them. Thus sampling means the output ports show the results that were calculated using kinematics values x[n], although the Context has been updated to kinematics values x[n+1]. If that isn’t tolerable you should disable output port sampling. You can also force an update to occur using ExecuteForcedEvents().
See output_port_sampling “Output port sampling” below for more practical considerations.
Minor details most users won’t care about:
The sample variable s is a Drake Abstract state variable. When it is
present, the plant update is performed using an Unrestricted update; when it is absent we are able to use a Discrete update. Some Drake features (e.g. linearization of discrete systems) may be restricted to systems that use only Discrete (numeric) state variables and Discrete update. - The sample variable s is used only by output ports. It does not affect the behavior of any MultibodyPlant “Calc” or “Eval” functions – those are always calculated using the current values of time, kinematic state, and input port values.
**** Output port sampling
As described in mbp_discrete_dynamics “Discrete system dynamics” above, the semantics of certain MultibodyPlant output ports depends on whether the plant is configured to advance using continuous time integration or discrete time steps (see is_discrete()). This section explains the details, focusing on the practical aspects moreso than the equations.
Output ports that only depend on the [q, v] kinematic state (such as get_body_poses_output_port() or get_body_spatial_velocities_output_port()) do not change semantics for continuous vs discrete time. In all cases, the output value is a function of the kinematic state in the context.
Output ports that incorporate dynamics (i.e., forces) do change semantics based on the plant mode. Imagine that the get_applied_spatial_force_input_port() provides a continuously time-varying input force. The get_body_spatial_accelerations_output_port() output is dependent on that force. We could return a snapshot of the acceleration that was used in the last time step, or we could recalculate the acceleration to immediately reflect the changing forces. We call the former a “sampled” port and the latter a “live” port.
For a continuous-time plant, there is no distinction – the output port is always live – it immediately reflects the instantaneous input value. It is a “direct feedthrough” output port (see SystemBase::GetDirectFeedthroughs()).
For a discrete-time plant, the user can choose whether the output should be sampled or live: Use the function SetUseSampledOutputPorts() to change whether output ports are sampled or not, and has_sampled_output_ports() to check the current setting. When sampling is disabled, the only state in the context is the kinematic [q, v], so dynamics output ports will always reflect the instantaneous answer (i.e., direct feedthrough). When sampling is enabled (the default), the plant state incorporates a snapshot of the most recent step’s kinematics and dynamics, and the output ports will reflect that sampled state (i.e., not direct feedthrough). For a detailed discussion, see mbp_discrete_dynamics “Discrete system dynamics”.
For a discrete-time plant, the sampled outputs are generally much faster to calculate than the feedthrough outputs when any inputs ports are changing values faster than the discrete time step, e.g., during a simulation. When input ports are fixed, or change at the time step rate (e.g., during motion planning), sampled vs feedthrough will have similar computational performance.
Direct plant API function calls (e.g., EvalBodySpatialAccelerationInWorld()) that depend on forces always use the instantaneous (not sampled) accelerations.
Here are some practical tips that might help inform your particular situation:
(1) If you need a minimal-state representation for motion planning, mathematical optimization, or similar, then you can either use a continuous-time plant or set the config option
use_sampled_output_ports=false
on a discrete-time plant.(2) By default, setting the positions of a discrete-time plant in the Context will not have any effect on the dynamics-related output ports, e.g., the contact results will not change. If you need to see changes to outputs without running the plant in a Simulator, then you can either use a continuous-time plant, set the config option
use_sampled_output_ports=false
, or use ExecuteForcedEvents() to force a dynamics step and then the outputs (and positions) will change.**** Actuation
In a MultibodyPlant model an actuator can be added as a JointActuator, see AddJointActuator(). The plant declares actuation input ports to provide feedforward actuation, both for the MultibodyPlant as a whole (see get_actuation_input_port()) and for each individual model_instances “model instance” in the MultibodyPlant (see get_actuation_input_port(ModelInstanceIndex)const “get_actuation_input_port(ModelInstanceIndex)”). Any actuation input ports not connected are assumed to be zero. Actuation values from the full MultibodyPlant model port (get_actuation_input_port()) and from the per model-instance ports ( get_actuation_input_port(ModelInstanceIndex)const “get_actuation_input_port(ModelInstanceIndex)”) are summed up.
Note
A JointActuator’s index into the vector data supplied to MultibodyPlant’s actuation input port for all actuators (get_actuation_input_port()) is given by JointActuator::input_start(), NOT by its JointActuatorIndex. That is, the vector element data for a JointActuator at index JointActuatorIndex(i) in the full input port vector is found at index: MultibodyPlant::get_joint_actuator(JointActuatorIndex(i)).input_start(). For the get_actuation_input_port(ModelInstanceIndex)const “get_actuation_input_port(ModelInstanceIndex)” specific to a model index, the vector data is ordered by monotonically increasing JointActuatorIndex for the actuators within that model instance: the 0ᵗʰ vector element corresponds to the lowest-numbered JointActuatorIndex of that instance, the 1ˢᵗ vector element corresponds to the second-lowest-numbered JointActuatorIndex of that instance, etc.
Note
The following snippet shows how per model instance actuation can be set:
Click to expand C++ code...
ModelInstanceIndex model_instance_index = ...; VectorX<T> u_instance(plant.num_actuated_dofs(model_instance_index)); int offset = 0; for (JointActuatorIndex joint_actuator_index : plant.GetJointActuatorIndices(model_instance_index)) { const JointActuator<T>& actuator = plant.get_joint_actuator( joint_actuator_index); const Joint<T>& joint = actuator.joint(); VectorX<T> u_joint = ... my_actuation_logic_for(joint) ...; ASSERT(u_joint.size() == joint_actuator.num_inputs()); u_instance.segment(offset, u_joint.size()) = u_joint; offset += u_joint.size(); } plant.get_actuation_input_port(model_instance_index).FixValue( plant_context, u_instance);
Note
To inter-operate between the whole plant actuation vector and sets of per-model instance actuation vectors, see SetActuationInArray() to gather the model instance vectors into a whole plant vector and GetActuationFromArray() to scatter the whole plant vector into per-model instance vectors.
Warning
Effort limits (JointActuator::effort_limit()) are not enforced, unless PD controllers are defined. See pd_controllers “Using PD controlled actuators”.
** Using PD controlled actuators
While PD controllers can be modeled externally and be connected to the MultibodyPlant model via the get_actuation_input_port(), simulation stability at discrete-time steps can be compromised for high controller gains. For such cases, simulation stability and robustness can be improved significantly by moving your PD controller into the plant where the discrete solver can strongly couple controller and model dynamics.
Warning
Currently, this feature is only supported for discrete models (is_discrete() is true) using the SAP solver (get_discrete_contact_solver() returns DiscreteContactSolver::kSap.)
PD controlled joint actuators can be defined by setting PD gains for each joint actuator, see JointActuator::set_controller_gains(). Unless these gains are specified, joint actuators will not be PD controlled and JointActuator::has_controller() will return
False
.Warning
For PD controlled models, all joint actuators in a model instance are required to have PD controllers defined. That is, partially PD controlled model instances are not supported. An exception will be thrown when evaluating the actuation input ports if only a subset of the actuators in a model instance is PD controlled.
For models with PD controllers, the actuation torque per actuator is computed according to:
Click to expand C++ code...
ũ = -Kp⋅(q − qd) - Kd⋅(v − vd) + u_ff u = max(−e, min(e, ũ))
where qd and vd are desired configuration and velocity (see get_desired_state_input_port()) for the actuated joint (see JointActuator::joint()), Kp and Kd are the proportional and derivative gains of the actuator (see JointActuator::get_controller_gains()),
u_ff
is the feed-forward actuation specified with get_actuation_input_port(), ande
corresponds to effort limit (see JointActuator::effort_limit()).Notice that actuation through get_actuation_input_port() and PD control are not mutually exclusive, and they can be used together. This is better explained through examples: 1. PD controlled gripper. In this case, only PD control is used to drive the opening and closing of the fingers. The feed-forward term is assumed to be zero and the actuation input port is not required to be connected. 2. Robot arm. A typical configuration consists on applying gravity compensation in the feed-forward term plus PD control to drive the robot to a given desired state.
** Actuation input ports requirements
The following table specifies whether actuation ports are required to be connected or not:
Port | without PD control | with PD control | |- ——————————
- :——————-: |
- ————-
- | get_actuation_input_port() | yes | no¹ | |
get_desired_state_input_port() | no² | yes |
¹ Feed-forward actuation is not required for models with PD controlled actuators. This simplifies the diagram wiring for models that only rely on PD controllers.
² This port is always declared, though it will be zero sized for model instances with no PD controllers.
** Net actuation
The total joint actuation applied via the actuation input port (get_actuation_input_port()) and applied by the PD controllers is reported by the net actuation port (get_net_actuation_output_port()). That is, the net actuation port reports the total actuation applied by a given actuator.
Note
PD controllers are ignored when a joint is locked (see Joint::Lock()), and thus they have no effect on the actuation output.
**** Loading models from SDFormat files
Drake has the capability to load multibody models from SDFormat and URDF files. Consider the example below which loads an acrobot model:
Click to expand C++ code...
MultibodyPlant<T> acrobot; SceneGraph<T> scene_graph; Parser parser(&acrobot, &scene_graph); const std::string url = "package://drake/multibody/benchmarks/acrobot/acrobot.sdf"; parser.AddModelsFromUrl(url);
As in the example above, for models including visual geometry, collision geometry or both, the user must specify a SceneGraph for geometry handling. You can find a full example of the LQR controlled acrobot in examples/multibody/acrobot/run_lqr.cc.
AddModelFromFile() can be invoked multiple times on the same plant in order to load multiple model instances. Other methods are available on Parser such as AddModels() which allows creating model instances per each
<model>
tag found in the file. Please refer to each of these methods’ documentation for further details.**** Working with SceneGraph
** Adding a MultibodyPlant connected to a SceneGraph to your Diagram
Probably the simplest way to add and wire up a MultibodyPlant with a SceneGraph in your Diagram is using AddMultibodyPlantSceneGraph().
Recommended usages:
Assign to a MultibodyPlant reference (ignoring the SceneGraph):
Click to expand C++ code...
MultibodyPlant<double>& plant = AddMultibodyPlantSceneGraph(&builder, 0.0 /+ time_step +/); plant.DoFoo(...);
This flavor is the simplest, when the SceneGraph is not explicitly needed. (It can always be retrieved later via GetSubsystemByName(“scene_graph”).)
Assign to auto, and use the named public fields:
Click to expand C++ code...
auto items = AddMultibodyPlantSceneGraph(&builder, 0.0 /+ time_step +/); items.plant.DoFoo(...); items.scene_graph.DoBar(...);
or taking advantage of C++’s structured binding:
Click to expand C++ code...
auto [plant, scene_graph] = AddMultibodyPlantSceneGraph(&builder, 0.0); ... plant.DoFoo(...); scene_graph.DoBar(...);
This is the easiest way to use both the plant and scene_graph.
Assign to already-declared pointer variables:
Click to expand C++ code...
MultibodyPlant<double>* plant{}; SceneGraph<double>* scene_graph{}; std::tie(plant, scene_graph) = AddMultibodyPlantSceneGraph(&builder, 0.0 /+ time_step +/); plant->DoFoo(...); scene_graph->DoBar(...);
This flavor is most useful when the pointers are class member fields (and so perhaps cannot be references).
** Registering geometry with a SceneGraph
MultibodyPlant users can register geometry with a SceneGraph for essentially two purposes; a) visualization and, b) contact modeling.
Before any geometry registration takes place, a user must first make a call to RegisterAsSourceForSceneGraph() in order to register the MultibodyPlant as a client of a SceneGraph instance, point at which the plant will have assigned a valid geometry::SourceId. At Finalize(), MultibodyPlant will declare input/output ports as appropriate to communicate with the SceneGraph instance on which registrations took place. All geometry registration must be performed pre-finalize.
Multibodyplant declares an input port for geometric queries, see get_geometry_query_input_port(). If MultibodyPlant registers geometry with a SceneGraph via calls to RegisterCollisionGeometry(), users may use this port for geometric queries. The port must be connected to the same SceneGraph used for registration. The preferred mechanism is to use AddMultibodyPlantSceneGraph() as documented above.
In extraordinary circumstances, this can be done by hand and the setup process will include:
Call to RegisterAsSourceForSceneGraph().
Calls to RegisterCollisionGeometry(), as many as needed.
Call to Finalize(), user is done specifying the model.
4. Connect geometry::SceneGraph::get_query_output_port() to get_geometry_query_input_port(). 5. Connect get_geometry_pose_output_port() to geometry::SceneGraph::get_source_pose_port()
Refer to the documentation provided in each of the methods above for further details.
** Accessing point contact parameters MultibodyPlant’s point contact model looks for model parameters stored as geometry::ProximityProperties by geometry::SceneGraph. These properties can be obtained before or after context creation through geometry::SceneGraphInspector APIs as outlined below. MultibodyPlant expects the following properties for point contact modeling:
|Group name|Property Name|Required|Property Type|Property Description| |:--------:|:———–:|:------:|:—————-:|:-------------------| |material|coulomb_friction|yes¹|CoulombFriction<T>|Static and Dynamic friction.| |material|point_contact_stiffness|no²|T| Compliant point contact stiffness.| |material|hunt_crossley_dissipation |no²⁴|T| Compliant contact dissipation.| |material|relaxation_time|yes³⁴|T|Linear Kelvin–Voigt model parameter.|
¹ Collision geometry is required to be registered with a geometry::ProximityProperties object that contains the (“material”, “coulomb_friction”) property. If the property is missing, MultibodyPlant will throw an exception.
² If the property is missing, MultibodyPlant will use a heuristic value as the default. Refer to the section point_contact_defaults “Point Contact Default Parameters” for further details.
³ When using a linear Kelvin–Voigt model of dissipation (for instance when selecting the SAP solver), collision geometry is required to be registered with a geometry::ProximityProperties object that contains the (“material”, “relaxation_time”) property. If the property is missing, an exception will be thrown.
⁴ We allow to specify both hunt_crossley_dissipation and relaxation_time for a given geometry. However only one of these will get used, depending on the configuration of the MultibodyPlant. As an example, if the SAP contact approximation is specified (see set_discrete_contact_approximation()) only the relaxation_time is used while hunt_crossley_dissipation is ignored. Conversely, if the TAMSI, Similar or Lagged approximation is used (see set_discrete_contact_approximation()) only hunt_crossley_dissipation is used while relaxation_time is ignored. Currently, a continuous MultibodyPlant model will always use the Hunt & Crossley model and relaxation_time will be ignored.
Accessing and modifying contact properties requires interfacing with geometry::SceneGraph’s model inspector. Interfacing with a model inspector obtained from geometry::SceneGraph will provide the default registered values for a given parameter. These are the values that will initially appear in a systems::Context created by CreateDefaultContext(). Subsequently, true system parameters can be accessed and changed through a systems::Context once available. For both of the above cases, proximity properties are accessed through geometry::SceneGraphInspector APIs.
Before context creation an inspector can be retrieved directly from SceneGraph as:
Click to expand C++ code...
// For a SceneGraph<T> instance called scene_graph. const geometry::SceneGraphInspector<T>& inspector = scene_graph.model_inspector();
After context creation, an inspector can be retrieved from the state stored in the context:
Click to expand C++ code...
// For a MultibodyPlant<T> instance called mbp and a Context<T> called // context. const geometry::SceneGraphInspector<T>& inspector = mbp.EvalSceneGraphInspector(context);
Once an inspector is available, proximity properties can be retrieved as:
Click to expand C++ code...
// For a body with GeometryId called geometry_id const geometry::ProximityProperties* props = inspector.GetProximityProperties(geometry_id); const CoulombFriction<T>& geometry_friction = props->GetProperty<CoulombFriction<T>>("material", "coulomb_friction");
**** Working with MultibodyElement parameters Several MultibodyElements expose parameters, allowing the user flexible modification of some aspects of the plant’s model, post systems::Context creation. For details, refer to the documentation for the MultibodyElement whose parameters you are trying to modify/access (e.g. RigidBody, FixedOffsetFrame, etc.)
As an example, here is how to access and modify rigid body mass parameters:
Click to expand C++ code...
MultibodyPlant<double> plant; // ... Code to add bodies, finalize plant, and to obtain a context. const RigidBody<double>& body = plant.GetRigidBodyByName("BodyName"); const SpatialInertia<double> M_BBo_B = body.GetSpatialInertiaInBodyFrame(context); // .. logic to determine a new SpatialInertia parameter for body. const SpatialInertia<double>& M_BBo_B_new = .... // Modify the body parameter for spatial inertia. body.SetSpatialInertiaInBodyFrame(&context, M_BBo_B_new);
Another example, working with automatic differentiation in order to take derivatives with respect to one of the bodies’ masses:
Click to expand C++ code...
MultibodyPlant<double> plant; // ... Code to add bodies, finalize plant, and to obtain a // context and a body's spatial inertia M_BBo_B. // Scalar convert the plant. unique_ptr<MultibodyPlant<AutoDiffXd>> plant_autodiff = systems::System<double>::ToAutoDiffXd(plant); unique_ptr<Context<AutoDiffXd>> context_autodiff = plant_autodiff->CreateDefaultContext(); context_autodiff->SetTimeStateAndParametersFrom(context); const RigidBody<AutoDiffXd>& body = plant_autodiff->GetRigidBodyByName("BodyName"); // Modify the body parameter for mass. const AutoDiffXd mass_autodiff(mass, Vector1d(1)); body.SetMass(context_autodiff.get(), mass_autodiff); // M_autodiff(i, j).derivatives()(0), contains the derivatives of // M(i, j) with respect to the body's mass. MatrixX<AutoDiffXd> M_autodiff(plant_autodiff->num_velocities(), plant_autodiff->num_velocities()); plant_autodiff->CalcMassMatrix(*context_autodiff, &M_autodiff);
**** Adding modeling elements
Add multibody elements to a MultibodyPlant with methods like:
Bodies: AddRigidBody()
Joints: AddJoint()
see mbp_construction “Construction” for more.
All modeling elements must be added before Finalize() is called. See mbp_finalize_stage “Finalize stage” for a discussion.
**** Modeling contact
Please refer to drake_contacts “Contact Modeling in Drake” for details on the available approximations, setup, and considerations for a multibody simulation with frictional contact.
**** Energy and Power
MultibodyPlant implements the System energy and power methods, with some limitations. - Kinetic energy: fully implemented. - Potential energy and conservative power: currently include only gravity and contributions from ForceElement objects; potential energy from compliant contact and joint limits are not included. - Nonconservative power: currently includes only contributions from ForceElement objects; actuation and input port forces, joint damping, and dissipation from joint limits, friction, and contact dissipation are not included.
See Drake issue #12942 for more discussion.
**** Finalize() stage
Once the user is done adding modeling elements and registering geometry, a call to Finalize() must be performed. This call will: - Build the underlying tree structure of the multibody model, - declare the plant’s state, - declare the plant’s input and output ports, - declare collision filters to ignore collisions among rigid bodies: - between rigid bodies connected by a joint, - within subgraphs of welded rigid bodies. Note that MultibodyPlant will not introduce any collision filters on deformable bodies.
**** References
[Featherstone 2008] Featherstone, R., 2008.
Rigid body dynamics algorithms. Springer. - [Jain 2010] Jain, A., 2010. Robot and multibody dynamics: analysis and algorithms. Springer Science & Business Media. - [Seth 2010] Seth, A., Sherman, M., Eastman, P. and Delp, S., 2010. Minimal formulation of joint motion for biomechanisms. Nonlinear dynamics, 62(1), pp.291-303.
- __init__(self: pydrake.multibody.plant.MultibodyPlant_[Expression], time_step: float) None
This constructor creates a plant with a single “world” body. Therefore, right after creation, num_bodies() returns one.
MultibodyPlant offers two different modalities to model mechanical systems in time. These are: 1. As a discrete system with periodic updates,
time_step
is strictly greater than zero. 2. As a continuous system,time_step
equals exactly zero.Currently the discrete model is preferred for simulation given its robustness and speed in problems with frictional contact. However this might change as we work towards developing better strategies to model contact. See multibody_simulation for further details.
Warning
Users should be aware of current limitations in either modeling modality. While the discrete model is often the preferred option for problems with frictional contact given its robustness and speed, it might become unstable when using large feedback gains, high damping or large external forcing. MultibodyPlant will throw an exception whenever the discrete solver is detected to fail. Conversely, the continuous modality has the potential to leverage the robustness and accuracy control provide by Drake’s integrators. However thus far this has proved difficult in practice and especially due to poor performance.
- Parameter
time_step
: Indicates whether
this
plant is modeled as a continuous system (time_step = 0
) or as a discrete system with periodic updates of periodtime_step > 0
. See multibody_simulation for further details.
Warning
Currently the continuous modality with
time_step = 0
does not support joint limits for simulation, these are ignored. MultibodyPlant prints a warning to console if joint limits are provided. If your simulation requires joint limits currently you must use a discrete MultibodyPlant model.- Raises
RuntimeError if time_step is negative. –
- Parameter
- AddBallConstraint(self: pydrake.multibody.plant.MultibodyPlant_[Expression], body_A: pydrake.multibody.tree.RigidBody_[Expression], p_AP: numpy.ndarray[numpy.float64[3, 1]], body_B: pydrake.multibody.tree.RigidBody_[Expression], p_BQ: Optional[numpy.ndarray[numpy.float64[3, 1]]] = None) pydrake.multibody.tree.MultibodyConstraintId
Defines a constraint such that point P affixed to body A is coincident at all times with point Q affixed to body B, effectively modeling a ball-and-socket joint.
- Parameter
body_A
: RigidBody to which point P is rigidly attached.
- Parameter
p_AP
: Position of point P in body A’s frame.
- Parameter
body_B
: RigidBody to which point Q is rigidly attached.
- Parameter
p_BQ
: (optional) Position of point Q in body B’s frame. If p_BQ is std::nullopt, then p_BQ will be computed so that the constraint is satisfied for the default configuration at Finalize() time; subsequent changes to the default configuration will not change the computed p_BQ.
- Returns
the id of the newly added constraint.
- Raises
RuntimeError if bodies A and B are the same body. –
RuntimeError if the MultibodyPlant has already been finalized. –
RuntimeError if this MultibodyPlant is not a discrete model –
(is_discrete() == false) –
RuntimeError if this MultibodyPlant's underlying contact –
solver is not SAP. (i.e. get_discrete_contact_solver() != –
DiscreteContactSolver::kSap) –
- Parameter
- AddCouplerConstraint(self: pydrake.multibody.plant.MultibodyPlant_[Expression], joint0: pydrake.multibody.tree.Joint_[Expression], joint1: pydrake.multibody.tree.Joint_[Expression], gear_ratio: float, offset: float = 0.0) pydrake.multibody.tree.MultibodyConstraintId
Defines a holonomic constraint between two single-dof joints
joint0
andjoint1
with positions q₀ and q₁, respectively, such that q₀ = ρ⋅q₁ + Δq, where ρ is the gear ratio and Δq is a fixed offset. The gear ratio can have units if the units of q₀ and q₁ are different. For instance, between a prismatic and a revolute joint the gear ratio will specify the “pitch” of the resulting mechanism. As defined,offset
has units ofq₀
.Note
joint0 and/or joint1 can still be actuated, regardless of whether we have coupler constraint among them. That is, one or both of these joints can have external actuation applied to them.
Note
Generally, to couple (q0, q1, q2), the user would define a coupler between (q0, q1) and a second coupler between (q1, q2), or any combination therein.
- Raises
if joint0 and joint1 are not both single-dof joints. –
RuntimeError if the MultibodyPlant has already been finalized. –
RuntimeError if this MultibodyPlant is not a discrete model –
(is_discrete() == false) –
RuntimeError if this MultibodyPlant's underlying contact –
solver is not SAP. (i.e. get_discrete_contact_solver() != –
DiscreteContactSolver::kSap) –
- AddDistanceConstraint(self: pydrake.multibody.plant.MultibodyPlant_[Expression], body_A: pydrake.multibody.tree.RigidBody_[Expression], p_AP: numpy.ndarray[numpy.float64[3, 1]], body_B: pydrake.multibody.tree.RigidBody_[Expression], p_BQ: numpy.ndarray[numpy.float64[3, 1]], distance: float, stiffness: float = inf, damping: float = 0.0) pydrake.multibody.tree.MultibodyConstraintId
Defines a distance constraint between a point P on a body A and a point Q on a body B.
This constraint can be compliant, modeling a spring with free length
distance
and givenstiffness
anddamping
parameters between points P and Q. For d = ‖p_PQ‖, then a compliant distance constraint models a spring with force along p_PQ given by:f = −stiffness ⋅ d − damping ⋅ ḋ
- Parameter
body_A
: RigidBody to which point P is rigidly attached.
- Parameter
p_AP
: Position of point P in body A’s frame.
- Parameter
body_B
: RigidBody to which point Q is rigidly attached.
- Parameter
p_BQ
: Position of point Q in body B’s frame.
- Parameter
distance
: Fixed length of the distance constraint, in meters. It must be strictly positive.
- Parameter
stiffness
: For modeling a spring with free length equal to
distance
, the stiffness parameter in N/m. Optional, with its default value being infinite to model a rigid massless rod of lengthdistance
connecting points A and B.- Parameter
damping
: For modeling a spring with free length equal to
distance
, damping parameter in N⋅s/m. Optional, with its default value being zero for a non-dissipative constraint.
- Returns
the id of the newly added constraint.
Warning
Currently, it is the user’s responsibility to initialize the model’s context in a configuration compatible with the newly added constraint.
Warning
A distance constraint is the wrong modeling choice if the distance needs to go through zero. To constrain two points to be coincident we need a 3-dof ball constraint, the 1-dof distance constraint is singular in this case. Therefore we require the distance parameter to be strictly positive.
- Raises
RuntimeError if bodies A and B are the same body. –
RuntimeError if distance is not strictly positive. –
RuntimeError if stiffness is not positive or zero. –
RuntimeError if damping is not positive or zero. –
RuntimeError if the MultibodyPlant has already been finalized. –
RuntimeError if this MultibodyPlant is not a discrete model –
(is_discrete() == false) –
RuntimeError if this MultibodyPlant's underlying contact –
solver is not SAP. (i.e. get_discrete_contact_solver() != –
DiscreteContactSolver::kSap) –
- Parameter
- AddForceElement(self: pydrake.multibody.plant.MultibodyPlant_[Expression], force_element: pydrake.multibody.tree.ForceElement_[Expression]) pydrake.multibody.tree.ForceElement_[Expression]
Adds a new force element model of type
ForceElementType
tothis
MultibodyPlant. The arguments to this methodargs
are forwarded to ``ForceElementType`’s constructor.- Parameter
args
: Zero or more parameters provided to the constructor of the new force element. It must be the case that ForceElementType<T>(args)` is a valid constructor.
- Template parameter
ForceElementType
: The type of the ForceElement to add. As there is always a UniformGravityFieldElement present (accessible through gravity_field()), an exception will be thrown if this function is called to add another UniformGravityFieldElement.
- Returns
A constant reference to the new ForceElement just added, of type
ForceElementType<T>
specialized on the scalar type T ofthis
MultibodyPlant. It will remain valid for the lifetime ofthis
MultibodyPlant.
See also
The ForceElement class’s documentation for further details on how a force element is defined.
- Parameter
- AddFrame(self: pydrake.multibody.plant.MultibodyPlant_[Expression], frame: pydrake.multibody.tree.Frame_[Expression]) pydrake.multibody.tree.Frame_[Expression]
This method adds a Frame of type
FrameType<T>
. For more information, please see the corresponding constructor ofFrameType
.- Template parameter
FrameType
: Template which will be instantiated on
T
.- Parameter
frame
: Unique pointer frame instance.
- Returns
A constant reference to the new Frame just added, which will remain valid for the lifetime of
this
MultibodyPlant.
- Template parameter
- AddJoint(self: pydrake.multibody.plant.MultibodyPlant_[Expression], joint: pydrake.multibody.tree.Joint_[Expression]) pydrake.multibody.tree.Joint_[Expression]
This method adds a Joint of type
JointType
between two bodies. For more information, see the below overload ofAddJoint<>
.
- AddJointActuator(self: pydrake.multibody.plant.MultibodyPlant_[Expression], name: str, joint: pydrake.multibody.tree.Joint_[Expression], effort_limit: float = inf) pydrake.multibody.tree.JointActuator_[Expression]
Creates and adds a JointActuator model for an actuator acting on a given
joint
. This method returns a constant reference to the actuator just added, which will remain valid for the lifetime ofthis
plant.- Parameter
name
: A string that uniquely identifies the new actuator to be added to
this
model. A RuntimeError is thrown if an actuator with the same name already exists in the model. See HasJointActuatorNamed().- Parameter
joint
: The Joint to be actuated by the new JointActuator.
- Parameter
effort_limit
: The maximum effort for the actuator. It must be strictly positive, otherwise an RuntimeError is thrown. If +∞, the actuator has no limit, which is the default. The effort limit has physical units in accordance to the joint type it actuates. For instance, it will have units of N⋅m (torque) for revolute joints while it will have units of N (force) for prismatic joints.
Note
The effort limit is unused by MultibodyPlant and is simply provided here for bookkeeping purposes. It will not, for instance, saturate external actuation inputs based on this value. If, for example, a user intends to saturate the force/torque that is applied to the MultibodyPlant via this actuator, the user-level code (e.g., a controller) should query this effort limit and impose the saturation there.
- Returns
A constant reference to the new JointActuator just added, which will remain valid for the lifetime of
this
plant or until the JointActuator has been removed from the plant with RemoveJointActuator().- Raises
RuntimeError if joint.num_velocities() > 1 since for now we –
only support actuators for single dof joints. –
See also
RemoveJointActuator()
- Parameter
- AddModelInstance(self: pydrake.multibody.plant.MultibodyPlant_[Expression], name: str) pydrake.multibody.tree.ModelInstanceIndex
Creates a new model instance. Returns the index for the model instance.
- Parameter
name
: A string that uniquely identifies the new instance to be added to
this
model. An exception is thrown if an instance with the same name already exists in the model. See HasModelInstanceNamed().
- Parameter
- AddRigidBody(*args, **kwargs)
Overloaded function.
AddRigidBody(self: pydrake.multibody.plant.MultibodyPlant_[Expression], name: str, M_BBo_B: pydrake.multibody.tree.SpatialInertia = SpatialInertia.Zero()) -> pydrake.multibody.tree.RigidBody_[Expression]
Creates a rigid body with the provided name and spatial inertia. This method returns a constant reference to the body just added, which will remain valid for the lifetime of
this
MultibodyPlant. The body will use the default model instance (model_instance “more on model instances”).Example of usage:
Click to expand C++ code...
MultibodyPlant<T> plant; // ... Code to define spatial_inertia, a SpatialInertia<T> object ... const RigidBody<T>& body = plant.AddRigidBody("BodyName", spatial_inertia);
- Parameter
name
: A string that identifies the new body to be added to
this
model. A RuntimeError is thrown if a body namedname
already is part of the model in the default model instance. See HasBodyNamed(), RigidBody::name().- Parameter
M_BBo_B
: The SpatialInertia of the new rigid body to be added to
this
MultibodyPlant, computed about the body frame originBo
and expressed in the body frame B. When not provided, defaults to zero.
- Returns
A constant reference to the new RigidBody just added, which will remain valid for the lifetime of
this
MultibodyPlant.- Raises
RuntimeError if additional model instances have been created –
beyond the world and default instances. –
AddRigidBody(self: pydrake.multibody.plant.MultibodyPlant_[Expression], name: str, model_instance: pydrake.multibody.tree.ModelInstanceIndex, M_BBo_B: pydrake.multibody.tree.SpatialInertia = SpatialInertia.Zero()) -> pydrake.multibody.tree.RigidBody_[Expression]
Creates a rigid body with the provided name and spatial inertia. This method returns a constant reference to the body just added, which will remain valid for the lifetime of
this
MultibodyPlant.Example of usage:
Click to expand C++ code...
MultibodyPlant<T> plant; // ... Code to define spatial_inertia, a SpatialInertia<T> object ... ModelInstanceIndex model_instance = plant.AddModelInstance("instance"); const RigidBody<T>& body = plant.AddRigidBody("BodyName", model_instance, spatial_inertia);
- Parameter
name
: A string that identifies the new body to be added to
this
model. A RuntimeError is thrown if a body namedname
already is part ofmodel_instance
. See HasBodyNamed(), RigidBody::name().- Parameter
model_instance
: A model instance index which this body is part of.
- Parameter
M_BBo_B
: The SpatialInertia of the new rigid body to be added to
this
MultibodyPlant, computed about the body frame originBo
and expressed in the body frame B. When not provided, defaults to zero.
- Returns
A constant reference to the new RigidBody just added, which will remain valid for the lifetime of
this
MultibodyPlant.
- AddWeldConstraint(self: pydrake.multibody.plant.MultibodyPlant_[Expression], body_A: pydrake.multibody.tree.RigidBody_[Expression], X_AP: pydrake.math.RigidTransform, body_B: pydrake.multibody.tree.RigidBody_[Expression], X_BQ: pydrake.math.RigidTransform) pydrake.multibody.tree.MultibodyConstraintId
Defines a constraint such that frame P affixed to body A is coincident at all times with frame Q affixed to body B, effectively modeling a weld joint.
- Parameter
body_A
: RigidBody to which frame P is rigidly attached.
- Parameter
X_AP
: Pose of frame P in body A’s frame.
- Parameter
body_B
: RigidBody to which frame Q is rigidly attached.
- Parameter
X_BQ
: Pose of frame Q in body B’s frame.
- Returns
the id of the newly added constraint.
- Raises
RuntimeError if bodies A and B are the same body. –
RuntimeError if the MultibodyPlant has already been finalized. –
RuntimeError if this MultibodyPlant is not a discrete model –
(is_discrete() == false) –
RuntimeError if this MultibodyPlant's underlying contact –
solver is not SAP. (i.e. get_discrete_contact_solver() != –
DiscreteContactSolver::kSap) –
- Parameter
- CalcBiasCenterOfMassTranslationalAcceleration(*args, **kwargs)
Overloaded function.
CalcBiasCenterOfMassTranslationalAcceleration(self: pydrake.multibody.plant.MultibodyPlant_[Expression], context: pydrake.systems.framework.Context_[Expression], with_respect_to: pydrake.multibody.tree.JacobianWrtVariable, frame_A: pydrake.multibody.tree.Frame_[Expression], frame_E: pydrake.multibody.tree.Frame_[Expression]) -> numpy.ndarray[object[3, 1]]
For the system S of all bodies other than the world body, calculates a𝑠Bias_AScm_E, Scm’s translational acceleration bias in frame A with respect to “speeds” 𝑠, expressed in frame E, where Scm is the center of mass of S and speeds 𝑠 is either q̇ or v.
- Parameter
context
: Contains the state of the multibody system.
- Parameter
with_respect_to
: Enum equal to JacobianWrtVariable::kQDot or JacobianWrtVariable::kV, indicating whether the accceleration bias is with respect to 𝑠 = q̇ or 𝑠 = v. Currently, an exception is thrown if with_respect_to is JacobianWrtVariable::kQDot.
- Parameter
frame_A
: The frame in which a𝑠Bias_AScm is measured.
- Parameter
frame_E
: The frame in which a𝑠Bias_AScm is expressed on output.
- Returns
a𝑠Bias_AScm_E Point Scm’s translational acceleration bias in frame A with respect to speeds 𝑠 (𝑠 = q̇ or 𝑠 = v), expressed in frame E.
- Raises
RuntimeError if this has no body except world_body() –
RuntimeError if mₛ ≤ 0, where mₛ is the mass of system S. –
RuntimeError if with_respect_to is JacobianWrtVariable::kQDot. –
See also
CalcJacobianCenterOfMassTranslationalVelocity() to compute J𝑠_v_Scm, point Scm’s translational velocity Jacobian in frame A with respect to 𝑠.
Note
The world_body() is ignored. asBias_AScm_E = ∑ (mᵢ aᵢ) / mₛ, where mₛ = ∑ mᵢ is the mass of system S, mᵢ is the mass of the iᵗʰ body, and aᵢ is the translational bias acceleration of Bᵢcm in frame A expressed in frame E for speeds 𝑠 (Bᵢcm is the center of mass of the iᵗʰ body).
Note
See bias_acceleration_functions “Bias acceleration functions” for theory and details.
CalcBiasCenterOfMassTranslationalAcceleration(self: pydrake.multibody.plant.MultibodyPlant_[Expression], context: pydrake.systems.framework.Context_[Expression], model_instances: list[pydrake.multibody.tree.ModelInstanceIndex], with_respect_to: pydrake.multibody.tree.JacobianWrtVariable, frame_A: pydrake.multibody.tree.Frame_[Expression], frame_E: pydrake.multibody.tree.Frame_[Expression]) -> numpy.ndarray[object[3, 1]]
For the system S containing the selected model instances, calculates a𝑠Bias_AScm_E, Scm’s translational acceleration bias in frame A with respect to “speeds” 𝑠, expressed in frame E, where Scm is the center of mass of S and speeds 𝑠 is either q̇ or v.
- Parameter
context
: Contains the state of the multibody system.
- Parameter
model_instances
: Vector of selected model instances. If a model instance is repeated in the vector (unusual), it is only counted once.
- Parameter
with_respect_to
: Enum equal to JacobianWrtVariable::kQDot or JacobianWrtVariable::kV, indicating whether the accceleration bias is with respect to 𝑠 = q̇ or 𝑠 = v. Currently, an exception is thrown if with_respect_to is JacobianWrtVariable::kQDot.
- Parameter
frame_A
: The frame in which a𝑠Bias_AScm is measured.
- Parameter
frame_E
: The frame in which a𝑠Bias_AScm is expressed on output.
- Returns
a𝑠Bias_AScm_E Point Scm’s translational acceleration bias in frame A with respect to speeds 𝑠 (𝑠 = q̇ or 𝑠 = v), expressed in frame E.
- Raises
RuntimeError if this has no body except world_body() –
RuntimeError if mₛ ≤ 0, where mₛ is the mass of system S. –
RuntimeError if with_respect_to is JacobianWrtVariable::kQDot. –
See also
CalcJacobianCenterOfMassTranslationalVelocity() to compute J𝑠_v_Scm, point Scm’s translational velocity Jacobian in frame A with respect to 𝑠.
Note
The world_body() is ignored. asBias_AScm_E = ∑ (mᵢ aᵢ) / mₛ, where mₛ = ∑ mᵢ is the mass of system S, mᵢ is the mass of the iᵗʰ body, and aᵢ is the translational bias acceleration of Bᵢcm in frame A expressed in frame E for speeds 𝑠 (Bᵢcm is the center of mass of the iᵗʰ body).
Note
See bias_acceleration_functions “Bias acceleration functions” for theory and details.
- CalcBiasSpatialAcceleration(self: pydrake.multibody.plant.MultibodyPlant_[Expression], context: pydrake.systems.framework.Context_[Expression], with_respect_to: pydrake.multibody.tree.JacobianWrtVariable, frame_B: pydrake.multibody.tree.Frame_[Expression], p_BoBp_B: numpy.ndarray[object[3, 1]], frame_A: pydrake.multibody.tree.Frame_[Expression], frame_E: pydrake.multibody.tree.Frame_[Expression]) pydrake.multibody.math.SpatialAcceleration_[Expression]
For one point Bp affixed/welded to a frame B, calculates A𝑠Bias_ABp, Bp’s spatial acceleration bias in frame A with respect to “speeds” 𝑠, expressed in frame E, where speeds 𝑠 is either q̇ or v.
- Parameter
context
: Contains the state of the multibody system.
- Parameter
with_respect_to
: Enum equal to JacobianWrtVariable::kQDot or JacobianWrtVariable::kV, indicating whether the spatial accceleration bias is with respect to 𝑠 = q̇ or 𝑠 = v. Currently, an exception is thrown if with_respect_to is JacobianWrtVariable::kQDot.
- Parameter
frame_B
: The frame on which point Bp is affixed/welded.
- Parameter
p_BoBp_B
: Position vector from Bo (frame_B’s origin) to point Bp (regarded as affixed/welded to B), expressed in frame_B.
- Parameter
frame_A
: The frame in which A𝑠Bias_ABp is measured.
- Parameter
frame_E
: The frame in which A𝑠Bias_ABp is expressed on output.
- Returns
A𝑠Bias_ABp_E Point Bp’s spatial acceleration bias in frame A with respect to speeds 𝑠 (𝑠 = q̇ or 𝑠 = v), expressed in frame E.
See also
CalcJacobianSpatialVelocity() to compute J𝑠_V_ABp, point Bp’s spatial velocity Jacobian in frame A with respect to 𝑠.
- Raises
RuntimeError if with_respect_to is JacobianWrtVariable::kQDot. –
Note
Use CalcBiasTranslationalAcceleration() to efficiently calculate bias translational accelerations for a list of points (each fixed to frame B). This function returns only one bias spatial acceleration, which contains both frame B’s bias angular acceleration and point Bp’s bias translational acceleration.
Note
See bias_acceleration_functions “Bias acceleration functions” for theory and details.
- Parameter
- CalcBiasTerm(self: pydrake.multibody.plant.MultibodyPlant_[Expression], context: pydrake.systems.framework.Context_[Expression]) numpy.ndarray[object[m, 1]]
Computes the bias term
C(q, v) v
containing Coriolis, centripetal, and gyroscopic effects in the multibody equations of motion:Click to expand C++ code...
M(q) v̇ + C(q, v) v = tau_app + ∑ (Jv_V_WBᵀ(q) ⋅ Fapp_Bo_W)
where
M(q)
is the multibody model’s mass matrix (including rigid body mass properties and reflected_inertia “reflected inertias”) andtau_app
is a vector of applied generalized forces. The last term is a summation over all bodies of the dot-product ofFapp_Bo_W
(applied spatial force on body B at Bo) withJv_V_WB(q)
(B’s spatial Jacobian in world W with respect to generalized velocities v). Note: B’s spatial velocity in W can be writtenV_WB = Jv_V_WB * v
.- Parameter
context
: Contains the state of the multibody system, including the generalized positions q and the generalized velocities v.
- Parameter
Cv
: On output,
Cv
will contain the productC(q, v)v
. It must be a valid (non-null) pointer to a column vector inℛⁿ
with n the number of generalized velocities (num_velocities()) of the model. This method aborts if Cv is nullptr or if it does not have the proper size.
- Parameter
- CalcBiasTranslationalAcceleration(self: pydrake.multibody.plant.MultibodyPlant_[Expression], context: pydrake.systems.framework.Context_[Expression], with_respect_to: pydrake.multibody.tree.JacobianWrtVariable, frame_B: pydrake.multibody.tree.Frame_[Expression], p_BoBi_B: numpy.ndarray[object[3, n], flags.f_contiguous], frame_A: pydrake.multibody.tree.Frame_[Expression], frame_E: pydrake.multibody.tree.Frame_[Expression]) numpy.ndarray[object[3, n]]
For each point Bi affixed/welded to a frame B, calculates a𝑠Bias_ABi, Bi’s translational acceleration bias in frame A with respect to “speeds” 𝑠, expressed in frame E, where speeds 𝑠 is either q̇ or v.
- Parameter
context
: Contains the state of the multibody system.
- Parameter
with_respect_to
: Enum equal to JacobianWrtVariable::kQDot or JacobianWrtVariable::kV, indicating whether the translational acceleration bias is with respect to 𝑠 = q̇ or 𝑠 = v. Currently, an exception is thrown if with_respect_to is JacobianWrtVariable::kQDot.
- Parameter
frame_B
: The frame on which points Bi are affixed/welded.
- Parameter
p_BoBi_B
: A position vector or list of p position vectors from Bo (frame_B’s origin) to points Bi (regarded as affixed to B), where each position vector is expressed in frame_B. Each column in the
3 x p
matrix p_BoBi_B corresponds to a position vector.- Parameter
frame_A
: The frame in which a𝑠Bias_ABi is measured.
- Parameter
frame_E
: The frame in which a𝑠Bias_ABi is expressed on output.
- Returns
a𝑠Bias_ABi_E Point Bi’s translational acceleration bias in frame A with respect to speeds 𝑠 (𝑠 = q̇ or 𝑠 = v), expressed in frame E. a𝑠Bias_ABi_E is a
3 x p
matrix, where p is the number of points Bi.
See also
CalcJacobianTranslationalVelocity() to compute J𝑠_v_ABi, point Bi’s translational velocity Jacobian in frame A with respect to 𝑠.
- Precondition:
p_BoBi_B must have 3 rows.
- Raises
RuntimeError if with_respect_to is JacobianWrtVariable::kQDot. –
Note
See bias_acceleration_functions “Bias acceleration functions” for theory and details.
- Parameter
- CalcCenterOfMassPositionInWorld(*args, **kwargs)
Overloaded function.
CalcCenterOfMassPositionInWorld(self: pydrake.multibody.plant.MultibodyPlant_[Expression], context: pydrake.systems.framework.Context_[Expression]) -> numpy.ndarray[object[3, 1]]
Calculates the position vector from the world origin Wo to the center of mass of all bodies in this MultibodyPlant, expressed in the world frame W.
- Parameter
context
: Contains the state of the model.
- Returns
p_WoScm_W
: position vector from Wo to Scm expressed in world frame W, where Scm is the center of mass of the system S stored by
this
plant.
- Raises
RuntimeError if this has no body except world_body() –
RuntimeError if mₛ ≤ 0 (where mₛ is the mass of system S) –
Note
The world_body() is ignored. p_WoScm_W = ∑ (mᵢ pᵢ) / mₛ, where mₛ = ∑ mᵢ, mᵢ is the mass of the iᵗʰ body, and pᵢ is Bᵢcm’s position from Wo expressed in frame W (Bᵢcm is the center of mass of the iᵗʰ body).
CalcCenterOfMassPositionInWorld(self: pydrake.multibody.plant.MultibodyPlant_[Expression], context: pydrake.systems.framework.Context_[Expression], model_instances: list[pydrake.multibody.tree.ModelInstanceIndex]) -> numpy.ndarray[object[3, 1]]
Calculates the position vector from the world origin Wo to the center of mass of all non-world bodies contained in model_instances, expressed in the world frame W.
- Parameter
context
: Contains the state of the model.
- Parameter
model_instances
: Vector of selected model instances. If a model instance is repeated in the vector (unusual), it is only counted once.
- Returns
p_WoScm_W
: position vector from world origin Wo to Scm expressed in the world frame W, where Scm is the center of mass of the system S of non-world bodies contained in model_instances.
- Raises
RuntimeError if model_instances is empty or only has world body. –
RuntimeError if mₛ ≤ 0 (where mₛ is the mass of system S) –
Note
The world_body() is ignored. p_WoScm_W = ∑ (mᵢ pᵢ) / mₛ, where mₛ = ∑ mᵢ, mᵢ is the mass of the iᵗʰ body contained in model_instances, and pᵢ is Bᵢcm’s position vector from Wo expressed in frame W (Bᵢcm is the center of mass of the iᵗʰ body).
- CalcCenterOfMassTranslationalAccelerationInWorld(*args, **kwargs)
Overloaded function.
CalcCenterOfMassTranslationalAccelerationInWorld(self: pydrake.multibody.plant.MultibodyPlant_[Expression], context: pydrake.systems.framework.Context_[Expression]) -> numpy.ndarray[object[3, 1]]
For the system S contained in this MultibodyPlant, calculates Scm’s translational acceleration in the world frame W expressed in W, where Scm is the center of mass of S.
- Parameter
context
: The context contains the state of the model.
- Returns
a_WScm_W
: Scm’s translational acceleration in the world frame W expressed in the world frame W.
- Raises
RuntimeError if this has no body except world_body() –
RuntimeError if mₛ ≤ 0, where mₛ is the mass of system S. –
Note
The world_body() is ignored. a_WScm_W = ∑ (mᵢ aᵢ) / mₛ, where mₛ = ∑ mᵢ is the mass of system S, mᵢ is the mass of the iᵗʰ body, and aᵢ is the translational acceleration of Bᵢcm in world W expressed in W (Bᵢcm is the center of mass of the iᵗʰ body).
Note
When cached values are out of sync with the state stored in context, this method performs an expensive forward dynamics computation, whereas once evaluated, successive calls to this method are inexpensive.
CalcCenterOfMassTranslationalAccelerationInWorld(self: pydrake.multibody.plant.MultibodyPlant_[Expression], context: pydrake.systems.framework.Context_[Expression], model_instances: list[pydrake.multibody.tree.ModelInstanceIndex]) -> numpy.ndarray[object[3, 1]]
For the system S containing the selected model instances, calculates Scm’s translational acceleration in the world frame W expressed in W, where Scm is the center of mass of S.
- Parameter
context
: The context contains the state of the model.
- Parameter
model_instances
: Vector of selected model instances. If a model instance is repeated in the vector (unusual), it is only counted once.
- Returns
a_WScm_W
: Scm’s translational acceleration in the world frame W expressed in the world frame W.
- Raises
RuntimeError if model_instances is empty or only has world body. –
RuntimeError if mₛ ≤ 0, where mₛ is the mass of system S. –
Note
The world_body() is ignored. a_WScm_W = ∑ (mᵢ aᵢ) / mₛ, where mₛ = ∑ mᵢ is the mass of system S, mᵢ is the mass of the iᵗʰ body in model_instances, and aᵢ is the translational acceleration of Bᵢcm in world W expressed in W (Bᵢcm is the center of mass of the iᵗʰ body).
Note
When cached values are out of sync with the state stored in context, this method performs an expensive forward dynamics computation, whereas once evaluated, successive calls to this method are inexpensive.
- CalcCenterOfMassTranslationalVelocityInWorld(*args, **kwargs)
Overloaded function.
CalcCenterOfMassTranslationalVelocityInWorld(self: pydrake.multibody.plant.MultibodyPlant_[Expression], context: pydrake.systems.framework.Context_[Expression]) -> numpy.ndarray[object[3, 1]]
Calculates system center of mass translational velocity in world frame W.
- Parameter
context
: The context contains the state of the model.
- Returns
v_WScm_W
: Scm’s translational velocity in frame W, expressed in W, where Scm is the center of mass of the system S stored by
this
plant.
- Raises
RuntimeError if this has no body except world_body() –
RuntimeError if mₛ ≤ 0 (where mₛ is the mass of system S) –
Note
The world_body() is ignored. v_WScm_W = ∑ (mᵢ vᵢ) / mₛ, where mₛ = ∑ mᵢ, mᵢ is the mass of the iᵗʰ body, and vᵢ is Bᵢcm’s velocity in world W (Bᵢcm is the center of mass of the iᵗʰ body).
CalcCenterOfMassTranslationalVelocityInWorld(self: pydrake.multibody.plant.MultibodyPlant_[Expression], context: pydrake.systems.framework.Context_[Expression], model_instances: list[pydrake.multibody.tree.ModelInstanceIndex]) -> numpy.ndarray[object[3, 1]]
Calculates system center of mass translational velocity in world frame W.
- Parameter
context
: The context contains the state of the model.
- Parameter
model_instances
: Vector of selected model instances. If a model instance is repeated in the vector (unusual), it is only counted once.
- Returns
v_WScm_W
: Scm’s translational velocity in frame W, expressed in W, where Scm is the center of mass of the system S of non-world bodies contained in model_instances.
- Raises
RuntimeError if model_instances is empty or only has world body. –
RuntimeError if mₛ ≤ 0 (where mₛ is the mass of system S) –
Note
The world_body() is ignored. v_WScm_W = ∑ (mᵢ vᵢ) / mₛ, where mₛ = ∑ mᵢ, mᵢ is the mass of the iᵗʰ body contained in model_instances, and vᵢ is Bᵢcm’s velocity in world W expressed in frame W (Bᵢcm is the center of mass of the iᵗʰ body).
- CalcForceElementsContribution(self: pydrake.multibody.plant.MultibodyPlant_[Expression], context: pydrake.systems.framework.Context_[Expression], forces: pydrake.multibody.tree.MultibodyForces_[Expression]) None
Computes the combined force contribution of ForceElement objects in the model. A ForceElement can apply forces as a spatial force per body or as generalized forces, depending on the ForceElement model. ForceElement contributions are a function of the state and time only. The output from this method can immediately be used as input to CalcInverseDynamics() to include the effect of applied forces by force elements.
- Parameter
context
: The context containing the state of this model.
- Parameter
forces
: A pointer to a valid, non nullptr, multibody forces object. On output
forces
will store the forces exerted by all the ForceElement objects in the model.
- Raises
RuntimeError if forces is null or not compatible with this –
model, per MultibodyForces::CheckInvariants() –
- Parameter
- CalcGeneralizedForces(self: pydrake.multibody.plant.MultibodyPlant_[Expression], context: pydrake.systems.framework.Context_[Expression], forces: pydrake.multibody.tree.MultibodyForces_[Expression]) numpy.ndarray[object[m, 1]]
Computes the generalized forces result of a set of MultibodyForces applied to this model.
MultibodyForces stores applied forces as both generalized forces τ and spatial forces F on each body, refer to documentation in MultibodyForces for details. Users of MultibodyForces will use MultibodyForces::mutable_generalized_forces() to mutate the stored generalized forces directly and will use RigidBody::AddInForceInWorld() to append spatial forces.
For a given set of forces stored as MultibodyForces, this method will compute the total generalized forces on this model. More precisely, if J_WBo is the Jacobian (with respect to velocities) for this model, including all bodies, then this method computes:
Click to expand C++ code...
τᵣₑₛᵤₗₜ = τ + J_WBo⋅F
- Parameter
context
: Context that stores the state of the model.
- Parameter
forces
: Set of multibody forces, including both generalized forces and per-body spatial forces.
- Parameter
generalized_forces
: The total generalized forces on the model that would result from applying
forces
. In other words,forces
can be replaced by the equivalentgeneralized_forces
. On output,generalized_forces
is resized to num_velocities().
- Raises
RuntimeError if forces is null or not compatible with this –
model. –
RuntimeError if generalized_forces is not a valid non-null –
pointer. –
- Parameter
- CalcGravityGeneralizedForces(self: pydrake.multibody.plant.MultibodyPlant_[Expression], context: pydrake.systems.framework.Context_[Expression]) numpy.ndarray[object[m, 1]]
Computes the generalized forces
tau_g(q)
due to gravity as a function of the generalized positionsq
stored in the inputcontext
. The vector of generalized forces due to gravitytau_g(q)
is defined such that it appears on the right hand side of the equations of motion together with any other generalized forces, like so:Click to expand C++ code...
Mv̇ + C(q, v)v = tau_g(q) + tau_app
where
tau_app
includes any other generalized forces applied on the system.- Parameter
context
: The context storing the state of the model.
- Returns
tau_g A vector containing the generalized forces due to gravity. The generalized forces are consistent with the vector of generalized velocities
v
forthis
so that the inner productv⋅tau_g
corresponds to the power applied by the gravity forces on the mechanical system. That is,v⋅tau_g > 0
corresponds to potential energy going into the system, as either mechanical kinetic energy, some other potential energy, or heat, and therefore to a decrease of the gravitational potential energy.
- Parameter
- CalcInverseDynamics(self: pydrake.multibody.plant.MultibodyPlant_[Expression], context: pydrake.systems.framework.Context_[Expression], known_vdot: numpy.ndarray[object[m, 1]], external_forces: pydrake.multibody.tree.MultibodyForces_[Expression]) numpy.ndarray[object[m, 1]]
Given the state of this model in
context
and a known vector of generalized accelerationsvdot
, this method computes the set of generalized forcestau
that would need to be applied in order to attain the specified generalized accelerations. Mathematically, this method computes:Click to expand C++ code...
tau = M(q)v̇ + C(q, v)v - tau_app - ∑ J_WBᵀ(q) Fapp_Bo_W
where
M(q)
is the model’s mass matrix (including rigid body mass properties and reflected_inertia “reflected inertias”),C(q, v)v
is the bias term for Coriolis and gyroscopic effects andtau_app
consists of a vector applied generalized forces. The last term is a summation over all bodies in the model whereFapp_Bo_W
is an applied spatial force on body B atBo
which gets projected into the space of generalized forces with the transpose ofJv_V_WB(q)
(whereJv_V_WB
is B’s spatial velocity Jacobian in W with respect to generalized velocities v). Note: B’s spatial velocity in W can be written asV_WB = Jv_V_WB * v
.This method does not compute explicit expressions for the mass matrix nor for the bias term, which would be of at least
O(n²)
complexity, but it implements anO(n)
Newton-Euler recursive algorithm, where n is the number of bodies in the model. The explicit formation of the mass matrixM(q)
would require the calculation ofO(n²)
entries while explicitly forming the productC(q, v) * v
could require up toO(n³)
operations (see [Featherstone 1987, §4]), depending on the implementation. The recursive Newton-Euler algorithm is the most efficient currently known general method for solving inverse dynamics [Featherstone 2008].- Parameter
context
: The context containing the state of the model.
- Parameter
known_vdot
: A vector with the known generalized accelerations
vdot
for the full model. Use the provided Joint APIs in order to access entries into this array.- Parameter
external_forces
: A set of forces to be applied to the system either as body spatial forces
Fapp_Bo_W
or generalized forcestau_app
, see MultibodyForces for details.
- Returns
the vector of generalized forces that would need to be applied to the mechanical system in order to achieve the desired acceleration given by
known_vdot
.
- Parameter
- CalcJacobianAngularVelocity(self: pydrake.multibody.plant.MultibodyPlant_[Expression], context: pydrake.systems.framework.Context_[Expression], with_respect_to: pydrake.multibody.tree.JacobianWrtVariable, frame_B: pydrake.multibody.tree.Frame_[Expression], frame_A: pydrake.multibody.tree.Frame_[Expression], frame_E: pydrake.multibody.tree.Frame_[Expression]) numpy.ndarray[object[3, n]]
Calculates J𝑠_w_AB, a frame B’s angular velocity Jacobian in a frame A with respect to “speeds” 𝑠.
Click to expand C++ code...
J𝑠_w_AB ≜ [ ∂(w_AB)/∂𝑠₁, ... ∂(w_AB)/∂𝑠ₙ ] (n is j or k) w_AB = J𝑠_w_AB ⋅ 𝑠 w_AB is linear in 𝑠 ≜ [𝑠₁ ... 𝑠ₙ]ᵀ
w_AB
is B’s angular velocity in frame A and “speeds” 𝑠 is either q̇ ≜ [q̇₁ … q̇ⱼ]ᵀ (time-derivatives of j generalized positions) or v ≜ [v₁ … vₖ]ᵀ (k generalized velocities).- Parameter
context
: The state of the multibody system.
- Parameter
with_respect_to
: Enum equal to JacobianWrtVariable::kQDot or JacobianWrtVariable::kV, indicating whether the Jacobian
J𝑠_w_AB
is partial derivatives with respect to 𝑠 = q̇ (time-derivatives of generalized positions) or with respect to 𝑠 = v (generalized velocities).- Parameter
frame_B
: The frame B in
w_AB
(B’s angular velocity in A).- Parameter
frame_A
: The frame A in
w_AB
(B’s angular velocity in A).- Parameter
frame_E
: The frame in which
w_AB
is expressed on input and the frame in which the JacobianJ𝑠_w_AB
is expressed on output.- Parameter
J𝑠_w_AB_E
: Frame B’s angular velocity Jacobian in frame A with respect to speeds 𝑠 (which is either q̇ or v), expressed in frame E. The Jacobian is a function of only generalized positions q (which are pulled from the context). The previous definition shows
J𝑠_w_AB_E
is a matrix of size3 x n
, where n is the number of elements in 𝑠.
See also
See Jacobian_functions “Jacobian functions” for related functions.
- Raises
RuntimeError if J𝑠_w_AB_E is nullptr or not of size 3 x n. –
- Parameter
- CalcJacobianCenterOfMassTranslationalVelocity(*args, **kwargs)
Overloaded function.
CalcJacobianCenterOfMassTranslationalVelocity(self: pydrake.multibody.plant.MultibodyPlant_[Expression], context: pydrake.systems.framework.Context_[Expression], with_respect_to: pydrake.multibody.tree.JacobianWrtVariable, frame_A: pydrake.multibody.tree.Frame_[Expression], frame_E: pydrake.multibody.tree.Frame_[Expression]) -> numpy.ndarray[object[3, n]]
Calculates J𝑠_v_ACcm_E, point Ccm’s translational velocity Jacobian in frame A with respect to “speeds” 𝑠, expressed in frame E, where point CCm is the center of mass of the system of all non-world bodies contained in
this
MultibodyPlant.- Parameter
context
: contains the state of the model.
- Parameter
with_respect_to
: Enum equal to JacobianWrtVariable::kQDot or JacobianWrtVariable::kV, indicating whether the Jacobian
J𝑠_v_ACcm_E
is partial derivatives with respect to 𝑠 = q̇ (time-derivatives of generalized positions) or with respect to 𝑠 = v (generalized velocities).- Parameter
frame_A
: The frame in which the translational velocity v_ACcm and its Jacobian J𝑠_v_ACcm are measured.
- Parameter
frame_E
: The frame in which the Jacobian J𝑠_v_ACcm is expressed on output.
- Parameter
J𝑠_v_ACcm_E
: Point Ccm’s translational velocity Jacobian in frame A with respect to speeds 𝑠 (𝑠 = q̇ or 𝑠 = v), expressed in frame E. J𝑠_v_ACcm_E is a 3 x n matrix, where n is the number of elements in 𝑠. The Jacobian is a function of only generalized positions q (which are pulled from the context).
- Raises
RuntimeError if CCm does not exist, which occurs if there are no –
massive bodies in MultibodyPlant (except world_body()) –
RuntimeError if mₛ ≤ 0 (where mₛ is the mass of all non-world –
bodies contained in this MultibodyPlant) –
See also
See Jacobian_functions “Jacobian functions” for related functions.
CalcJacobianCenterOfMassTranslationalVelocity(self: pydrake.multibody.plant.MultibodyPlant_[Expression], context: pydrake.systems.framework.Context_[Expression], model_instances: list[pydrake.multibody.tree.ModelInstanceIndex], with_respect_to: pydrake.multibody.tree.JacobianWrtVariable, frame_A: pydrake.multibody.tree.Frame_[Expression], frame_E: pydrake.multibody.tree.Frame_[Expression]) -> numpy.ndarray[object[3, n]]
Calculates J𝑠_v_ACcm_E, point Ccm’s translational velocity Jacobian in frame A with respect to “speeds” 𝑠, expressed in frame E, where point CCm is the center of mass of the system of all non-world bodies contained in model_instances.
- Parameter
context
: contains the state of the model.
- Parameter
model_instances
: Vector of selected model instances. If a model instance is repeated in the vector (unusual), it is only counted once.
- Parameter
with_respect_to
: Enum equal to JacobianWrtVariable::kQDot or JacobianWrtVariable::kV, indicating whether the Jacobian
J𝑠_v_ACcm_E
is partial derivatives with respect to 𝑠 = q̇ (time-derivatives of generalized positions) or with respect to 𝑠 = v (generalized velocities).- Parameter
frame_A
: The frame in which the translational velocity v_ACcm and its Jacobian J𝑠_v_ACcm are measured.
- Parameter
frame_E
: The frame in which the Jacobian J𝑠_v_ACcm is expressed on output.
- Parameter
J𝑠_v_ACcm_E
: Point Ccm’s translational velocity Jacobian in frame A with respect to speeds 𝑠 (𝑠 = q̇ or 𝑠 = v), expressed in frame E. J𝑠_v_ACcm_E is a 3 x n matrix, where n is the number of elements in 𝑠. The Jacobian is a function of only generalized positions q (which are pulled from the context).
- Raises
RuntimeError if mₛ ≤ 0 (where mₛ is the mass of all non-world –
bodies contained in model_instances) –
RuntimeError if model_instances is empty or only has world body. –
Note
The world_body() is ignored. J𝑠_v_ACcm_ = ∑ (mᵢ Jᵢ) / mₛ, where mₛ = ∑ mᵢ, mᵢ is the mass of the iᵗʰ body contained in model_instances, and Jᵢ is Bᵢcm’s translational velocity Jacobian in frame A, expressed in frame E (Bᵢcm is the center of mass of the iᵗʰ body).
See also
See Jacobian_functions “Jacobian functions” for related functions.
- CalcJacobianPositionVector(self: pydrake.multibody.plant.MultibodyPlant_[Expression], context: pydrake.systems.framework.Context_[Expression], frame_B: pydrake.multibody.tree.Frame_[Expression], p_BoBi_B: numpy.ndarray[object[3, n], flags.f_contiguous], frame_A: pydrake.multibody.tree.Frame_[Expression], frame_E: pydrake.multibody.tree.Frame_[Expression]) numpy.ndarray[object[m, n]]
For each point Bi affixed/welded to a frame B, calculates Jq_p_AoBi, Bi’s position vector Jacobian in frame A with respect to the generalized positions q ≜ [q₁ … qₙ]ᵀ as
Click to expand C++ code...
Jq_p_AoBi ≜ [ ᴬ∂(p_AoBi)/∂q₁, ... ᴬ∂(p_AoBi)/∂qₙ ]
where p_AoBi is Bi’s position vector from point Ao (frame A’s origin) and ᴬ∂(p_AoBi)/∂qᵣ denotes the partial derivative in frame A of p_AoBi with respect to the generalized position qᵣ, where qᵣ is one of q₁ … qₙ.
- Parameter
context
: The state of the multibody system.
- Parameter
frame_B
: The frame on which point Bi is affixed/welded.
- Parameter
p_BoBi_B
: A position vector or list of k position vectors from Bo (frame_B’s origin) to points Bi (Bi is regarded as affixed to B), where each position vector is expressed in frame_B.
- Parameter
frame_A
: The frame in which partial derivatives are calculated and the frame in which point Ao is affixed.
- Parameter
frame_E
: The frame in which the Jacobian Jq_p_AoBi is expressed on output.
- Parameter
Jq_p_AoBi_E
: Point Bi’s position vector Jacobian in frame A with generalized positions q, expressed in frame E. Jq_p_AoBi_E is a
3*k x n
matrix, where k is the number of points Bi and n is the number of elements in q. The Jacobian is a function of only generalized positions q (which are pulled from the context).
- Raises
RuntimeError if Jq_p_AoBi_E is nullptr or not sized 3*k x n. –
Note
Jq̇_v_ABi = Jq_p_AoBi. In other words, point Bi’s velocity Jacobian in frame A with respect to q̇ is equal to point Bi’s position vector Jacobian in frame A with respect to q.
Click to expand C++ code...
[∂(v_ABi)/∂q̇₁, ... ∂(v_ABi)/∂q̇ₙ] = [ᴬ∂(p_AoBi)/∂q₁, ... ᴬ∂(p_AoBi)/∂qₙ]
See also
CalcJacobianTranslationalVelocity() for details on Jq̇_v_ABi. Note: Jq_p_AaBi = Jq_p_AoBi, where point Aa is any point fixed/welded to frame A, i.e., this calculation’s result is the same if point Ao is replaced with any point fixed on frame A.
See also
See Jacobian_functions “Jacobian functions” for related functions.
- Parameter
- CalcJacobianSpatialVelocity(self: pydrake.multibody.plant.MultibodyPlant_[Expression], context: pydrake.systems.framework.Context_[Expression], with_respect_to: pydrake.multibody.tree.JacobianWrtVariable, frame_B: pydrake.multibody.tree.Frame_[Expression], p_BoBp_B: numpy.ndarray[object[3, 1]], frame_A: pydrake.multibody.tree.Frame_[Expression], frame_E: pydrake.multibody.tree.Frame_[Expression]) numpy.ndarray[object[m, n]]
For one point Bp fixed/welded to a frame B, calculates J𝑠_V_ABp, Bp’s spatial velocity Jacobian in frame A with respect to “speeds” 𝑠.
Click to expand C++ code...
J𝑠_V_ABp ≜ [ ∂(V_ABp)/∂𝑠₁, ... ∂(V_ABp)/∂𝑠ₙ ] (n is j or k) V_ABp = J𝑠_V_ABp ⋅ 𝑠 V_ABp is linear in 𝑠 ≜ [𝑠₁ ... 𝑠ₙ]ᵀ
V_ABp
is Bp’s spatial velocity in frame A and “speeds” 𝑠 is either q̇ ≜ [q̇₁ … q̇ⱼ]ᵀ (time-derivatives of j generalized positions) or v ≜ [v₁ … vₖ]ᵀ (k generalized velocities).- Parameter
context
: The state of the multibody system.
- Parameter
with_respect_to
: Enum equal to JacobianWrtVariable::kQDot or JacobianWrtVariable::kV, indicating whether the Jacobian
J𝑠_V_ABp
is partial derivatives with respect to 𝑠 = q̇ (time-derivatives of generalized positions) or with respect to 𝑠 = v (generalized velocities).- Parameter
frame_B
: The frame on which point Bp is fixed/welded.
- Parameter
p_BoBp_B
: A position vector from Bo (frame_B’s origin) to point Bp (regarded as fixed/welded to B), expressed in frame_B.
- Parameter
frame_A
: The frame that measures
v_ABp
(Bp’s velocity in A). Note: It is natural to wonder why there is no parameter p_AoAp_A (similar to the parameter p_BoBp_B for frame_B). There is no need for p_AoAp_A because Bp’s velocity in A is defined as the derivative in frame A of Bp’s position vector from any point fixed to A.- Parameter
frame_E
: The frame in which
v_ABp
is expressed on input and the frame in which the JacobianJ𝑠_V_ABp
is expressed on output.- Parameter
J𝑠_V_ABp_E
: Point Bp’s spatial velocity Jacobian in frame A with respect to speeds 𝑠 (which is either q̇ or v), expressed in frame E.
J𝑠_V_ABp_E
is a6 x n
matrix, where n is the number of elements in 𝑠. The Jacobian is a function of only generalized positions q (which are pulled from the context).
Note
The returned
6 x n
matrix stores frame B’s angular velocity Jacobian in A in rows 1-3 and stores point Bp’s translational velocity Jacobian in A in rows 4-6, i.e.,Click to expand C++ code...
J𝑠_w_AB_E = J𝑠_V_ABp_E.topRows<3>(); J𝑠_v_ABp_E = J𝑠_V_ABp_E.bottomRows<3>();
Note
Consider CalcJacobianTranslationalVelocity() for multiple points fixed to frame B and consider CalcJacobianAngularVelocity() to calculate frame B’s angular velocity Jacobian.
See also
See Jacobian_functions “Jacobian functions” for related functions.
- Raises
RuntimeError if J𝑠_V_ABp_E is nullptr or not sized 6 x n. –
- Parameter
- CalcJacobianTranslationalVelocity(self: pydrake.multibody.plant.MultibodyPlant_[Expression], context: pydrake.systems.framework.Context_[Expression], with_respect_to: pydrake.multibody.tree.JacobianWrtVariable, frame_B: pydrake.multibody.tree.Frame_[Expression], p_BoBi_B: numpy.ndarray[object[3, n], flags.f_contiguous], frame_A: pydrake.multibody.tree.Frame_[Expression], frame_E: pydrake.multibody.tree.Frame_[Expression]) numpy.ndarray[object[m, n]]
For each point Bi affixed/welded to a frame B, calculates J𝑠_v_ABi, Bi’s translational velocity Jacobian in frame A with respect to “speeds” 𝑠.
Click to expand C++ code...
J𝑠_v_ABi ≜ [ ∂(v_ABi)/∂𝑠₁, ... ∂(v_ABi)/∂𝑠ₙ ] (n is j or k) v_ABi = J𝑠_v_ABi ⋅ 𝑠 v_ABi is linear in 𝑠 ≜ [𝑠₁ ... 𝑠ₙ]ᵀ
v_ABi
is Bi’s translational velocity in frame A and “speeds” 𝑠 is either q̇ ≜ [q̇₁ … q̇ⱼ]ᵀ (time-derivatives of j generalized positions) or v ≜ [v₁ … vₖ]ᵀ (k generalized velocities).- Parameter
context
: The state of the multibody system.
- Parameter
with_respect_to
: Enum equal to JacobianWrtVariable::kQDot or JacobianWrtVariable::kV, indicating whether the Jacobian
J𝑠_v_ABi
is partial derivatives with respect to 𝑠 = q̇ (time-derivatives of generalized positions) or with respect to 𝑠 = v (generalized velocities).- Parameter
frame_B
: The frame on which point Bi is affixed/welded.
- Parameter
p_BoBi_B
: A position vector or list of p position vectors from Bo (frame_B’s origin) to points Bi (regarded as affixed to B), where each position vector is expressed in frame_B.
- Parameter
frame_A
: The frame that measures
v_ABi
(Bi’s velocity in A). Note: It is natural to wonder why there is no parameter p_AoAi_A (similar to the parameter p_BoBi_B for frame_B). There is no need for p_AoAi_A because Bi’s velocity in A is defined as the derivative in frame A of Bi’s position vector from any point affixed to A.- Parameter
frame_E
: The frame in which
v_ABi
is expressed on input and the frame in which the JacobianJ𝑠_v_ABi
is expressed on output.- Parameter
J𝑠_v_ABi_E
: Point Bi’s velocity Jacobian in frame A with respect to speeds 𝑠 (which is either q̇ or v), expressed in frame E.
J𝑠_v_ABi_E
is a3*p x n
matrix, where p is the number of points Bi and n is the number of elements in 𝑠. The Jacobian is a function of only generalized positions q (which are pulled from the context).
- Raises
RuntimeError if J𝑠_v_ABi_E is nullptr or not sized ``3*p x –
n``. –
Note
When 𝑠 = q̇,
Jq̇_v_ABi = Jq_p_AoBi
. In other words, point Bi’s velocity Jacobian in frame A with respect to q̇ is equal to point Bi’s position Jacobian from Ao (A’s origin) in frame A with respect to q.Click to expand C++ code...
[∂(v_ABi)/∂q̇₁, ... ∂(v_ABi)/∂q̇ⱼ] = [∂(p_AoBi)/∂q₁, ... ∂(p_AoBi)/∂qⱼ]
Note: Each partial derivative of p_AoBi is taken in frame A.
See also
CalcJacobianPositionVector() for details on Jq_p_AoBi.
See also
See Jacobian_functions “Jacobian functions” for related functions.
- Parameter
- CalcMassMatrix(self: pydrake.multibody.plant.MultibodyPlant_[Expression], context: pydrake.systems.framework.Context_[Expression]) numpy.ndarray[object[m, n]]
Efficiently computes the mass matrix
M(q)
of the model. The generalized positions q are taken from the givencontext
. M includes the mass properties of rigid bodies and reflected_inertia “reflected inertias” as provided with JointActuator specifications.This method employs the Composite Body Algorithm, which we believe to be the fastest O(n²) algorithm to compute the mass matrix of a multibody system.
- Parameter
context
: The Context containing the state of the model from which generalized coordinates q are extracted.
- Parameter
M
: A pointer to a square matrix in
ℛⁿˣⁿ
with n the number of generalized velocities (num_velocities()) of the model. Although symmetric, the matrix is filled in completely on return.- Precondition:
M is non-null and has the right size.
Warning
This is an O(n²) algorithm. Avoid the explicit computation of the mass matrix whenever possible.
See also
CalcMassMatrixViaInverseDynamics() (slower)
- Parameter
- CalcMassMatrixViaInverseDynamics(self: pydrake.multibody.plant.MultibodyPlant_[Expression], context: pydrake.systems.framework.Context_[Expression]) numpy.ndarray[object[m, n]]
Computes the mass matrix
M(q)
of the model using a slow method (inverse dynamics). The generalized positions q are taken from the givencontext
. M includes the mass properties of rigid bodies and reflected_inertia “reflected inertias” as provided with JointActuator specifications.Use CalcMassMatrix() for a faster implementation using the Composite Body Algorithm.
- Parameter
context
: The Context containing the state of the model from which generalized coordinates q are extracted.
- Parameter
M
: A pointer to a square matrix in
ℛⁿˣⁿ
with n the number of generalized velocities (num_velocities()) of the model. Although symmetric, the matrix is filled in completely on return.- Precondition:
M is non-null and has the right size.
The algorithm used to build
M(q)
consists in computing one column ofM(q)
at a time using inverse dynamics. The result from inverse dynamics, with no applied forces, is the vector of generalized forces:Click to expand C++ code...
tau = M(q)v̇ + C(q, v)v
where q and v are the generalized positions and velocities, respectively. When
v = 0
the Coriolis and gyroscopic forces termC(q, v)v
is zero. Therefore thei-th
column ofM(q)
can be obtained performing inverse dynamics with an acceleration vectorv̇ = eᵢ
, witheᵢ
the standard (or natural) basis ofℛⁿ
with n the number of generalized velocities. We write this as:Click to expand C++ code...
M.ᵢ(q) = M(q) * e_i
where
M.ᵢ(q)
(notice the dot for the rows index) denotes thei-th
column in M(q).Warning
This is an O(n²) algorithm. Avoid the explicit computation of the mass matrix whenever possible.
See also
CalcMassMatrix(), CalcInverseDynamics()
- Parameter
- CalcPointsPositions(self: pydrake.multibody.plant.MultibodyPlant_[Expression], context: pydrake.systems.framework.Context_[Expression], frame_B: pydrake.multibody.tree.Frame_[Expression], p_BQi: numpy.ndarray[object[m, n], flags.f_contiguous], frame_A: pydrake.multibody.tree.Frame_[Expression]) numpy.ndarray[object[m, n]]
Given the positions
p_BQi
for a set of pointsQi
measured and expressed in a frame B, this method computes the positionsp_AQi(q)
of each pointQi
in the set as measured and expressed in another frame A, as a function of the generalized positions q of the model.- Parameter
context
: The context containing the state of the model. It stores the generalized positions q of the model.
- Parameter
frame_B
: The frame B in which the positions
p_BQi
of a set of pointsQi
are given.- Parameter
p_BQi
: The input positions of each point
Qi
in frame B.p_BQi ∈ ℝ³ˣⁿᵖ
withnp
the number of points in the set. Each column ofp_BQi
corresponds to a vector in ℝ³ holding the position of one of the points in the set as measured and expressed in frame B.- Parameter
frame_A
: The frame A in which it is desired to compute the positions
p_AQi
of each pointQi
in the set.- Parameter
p_AQi
: The output positions of each point
Qi
now computed as measured and expressed in frame A. The outputp_AQi
must have the same size as the inputp_BQi
or otherwise this method aborts. That isp_AQi
must be inℝ³ˣⁿᵖ
.
Note
Both
p_BQi
andp_AQi
must have three rows. Otherwise this method will throw a RuntimeError. This method also throws a RuntimeError ifp_BQi
andp_AQi
differ in the number of columns.- Parameter
- CalcRelativeRotationMatrix(self: pydrake.multibody.plant.MultibodyPlant_[Expression], context: pydrake.systems.framework.Context_[Expression], frame_A: pydrake.multibody.tree.Frame_[Expression], frame_B: pydrake.multibody.tree.Frame_[Expression]) pydrake.math.RotationMatrix_[Expression]
Calculates the rotation matrix
R_AB
relating frame A and frame B.- Parameter
context
: The state of the multibody system, which includes the system’s generalized positions q. Note:
R_AB
is a function of q.- Parameter
frame_A
: The frame A designated in the rigid transform
R_AB
.- Parameter
frame_B
: The frame G designated in the rigid transform
R_AB
.- Returns
R_AB
: The RigidTransform relating frame A and frame B.
- Parameter
- CalcRelativeTransform(self: pydrake.multibody.plant.MultibodyPlant_[Expression], context: pydrake.systems.framework.Context_[Expression], frame_A: pydrake.multibody.tree.Frame_[Expression], frame_B: pydrake.multibody.tree.Frame_[Expression]) pydrake.math.RigidTransform_[Expression]
Calculates the rigid transform (pose)
X_AB
relating frame A and frame B.- Parameter
context
: The state of the multibody system, which includes the system’s generalized positions q. Note:
X_AB
is a function of q.- Parameter
frame_A
: The frame A designated in the rigid transform
X_AB
.- Parameter
frame_B
: The frame G designated in the rigid transform
X_AB
.- Returns
X_AB
: The RigidTransform relating frame A and frame B.
- Parameter
- CalcSpatialAccelerationsFromVdot(self: pydrake.multibody.plant.MultibodyPlant_[Expression], context: pydrake.systems.framework.Context_[Expression], known_vdot: numpy.ndarray[object[m, 1]]) list[pydrake.multibody.math.SpatialAcceleration_[Expression]]
Given the state of this model in
context
and a known vector of generalized accelerationsknown_vdot
, this method computes the spatial accelerationA_WB
for each body as measured and expressed in the world frame W.- Parameter
context
: The context containing the state of this model.
- Parameter
known_vdot
: A vector with the generalized accelerations for the full model.
- Parameter
A_WB_array
: A pointer to a valid, non nullptr, vector of spatial accelerations containing the spatial acceleration
A_WB
for each body. It must be of size equal to the number of bodies in the model. On output, entries will be ordered by BodyIndex.
- Raises
RuntimeError if A_WB_array is not of size num_bodies() –
- Parameter
- CalcSpatialInertia(self: pydrake.multibody.plant.MultibodyPlant_[Expression], context: pydrake.systems.framework.Context_[Expression], frame_F: pydrake.multibody.tree.Frame_[Expression], body_indexes: list[pydrake.multibody.tree.BodyIndex]) pydrake.multibody.tree.SpatialInertia_[Expression]
Returns M_SFo_F, the spatial inertia of a set S of bodies about point Fo (the origin of a frame F), expressed in frame F. You may regard M_SFo_F as measuring spatial inertia as if the set S of bodies were welded into a single composite body at the configuration specified in the
context
.- Parameter
context
: Contains the configuration of the set S of bodies.
- Parameter
frame_F
: specifies the about-point Fo (frame_F’s origin) and the expressed-in frame for the returned spatial inertia.
- Parameter
body_indexes
: Array of selected bodies. This method does not distinguish between welded bodies, joint-connected bodies, etc.
- Raises
RuntimeError if body_indexes contains an invalid BodyIndex or if –
there is a repeated BodyIndex. –
Note
The mass and inertia of the world_body() does not contribute to the the returned spatial inertia.
- Parameter
- CalcSpatialMomentumInWorldAboutPoint(*args, **kwargs)
Overloaded function.
CalcSpatialMomentumInWorldAboutPoint(self: pydrake.multibody.plant.MultibodyPlant_[Expression], context: pydrake.systems.framework.Context_[Expression], p_WoP_W: numpy.ndarray[object[3, 1]]) -> pydrake.multibody.math.SpatialMomentum_[Expression]
This method returns the spatial momentum of
this
MultibodyPlant in the world frame W, about a designated point P, expressed in the world frame W.- Parameter
context
: Contains the state of the model.
- Parameter
p_WoP_W
: Position from Wo (origin of the world frame W) to an arbitrary point P, expressed in the world frame W.
- Returns
L_WSP_W
: , spatial momentum of the system S represented by
this
plant, measured in the world frame W, about point P, expressed in W.
Note
To calculate the spatial momentum of this system S in W about Scm (the system’s center of mass), use something like:
Click to expand C++ code...
MultibodyPlant<T> plant; // ... code to load a model .... const Vector3<T> p_WoScm_W = plant.CalcCenterOfMassPositionInWorld(context); const SpatialMomentum<T> L_WScm_W = plant.CalcSpatialMomentumInWorldAboutPoint(context, p_WoScm_W);
CalcSpatialMomentumInWorldAboutPoint(self: pydrake.multibody.plant.MultibodyPlant_[Expression], context: pydrake.systems.framework.Context_[Expression], model_instances: list[pydrake.multibody.tree.ModelInstanceIndex], p_WoP_W: numpy.ndarray[object[3, 1]]) -> pydrake.multibody.math.SpatialMomentum_[Expression]
This method returns the spatial momentum of a set of model instances in the world frame W, about a designated point P, expressed in frame W.
- Parameter
context
: Contains the state of the model.
- Parameter
model_instances
: Set of selected model instances.
- Parameter
p_WoP_W
: Position from Wo (origin of the world frame W) to an arbitrary point P, expressed in the world frame W.
- Returns
L_WSP_W
: , spatial momentum of the system S represented by the model_instances, measured in world frame W, about point P, expressed in W.
Note
To calculate the spatial momentum of this system S in W about Scm (the system’s center of mass), use something like:
Click to expand C++ code...
MultibodyPlant<T> plant; // ... code to create a set of selected model instances, e.g., ... const ModelInstanceIndex gripper_model_instance = plant.GetModelInstanceByName("gripper"); const ModelInstanceIndex robot_model_instance = plant.GetBodyByName("end_effector").model_instance(); const std::vector<ModelInstanceIndex> model_instances{ gripper_model_instance, robot_model_instance}; const Vector3<T> p_WoScm_W = plant.CalcCenterOfMassPositionInWorld(context, model_instances); SpatialMomentum<T> L_WScm_W = plant.CalcSpatialMomentumInWorldAboutPoint(context, model_instances, p_WoScm_W);
- Raises
RuntimeError if model_instances contains an invalid –
ModelInstanceIndex. –
- CalcTotalMass(*args, **kwargs)
Overloaded function.
CalcTotalMass(self: pydrake.multibody.plant.MultibodyPlant_[Expression], context: pydrake.systems.framework.Context_[Expression]) -> pydrake.symbolic.Expression
Calculates the total mass of all bodies in this MultibodyPlant.
- Parameter
context
: Contains the state of the model.
- Returns
The
: total mass of all bodies or 0 if there are none.
Note
The mass of the world_body() does not contribute to the total mass.
CalcTotalMass(self: pydrake.multibody.plant.MultibodyPlant_[Expression], context: pydrake.systems.framework.Context_[Expression], model_instances: list[pydrake.multibody.tree.ModelInstanceIndex]) -> pydrake.symbolic.Expression
Calculates the total mass of all bodies contained in model_instances.
- Parameter
context
: Contains the state of the model.
- Parameter
model_instances
: Vector of selected model instances. This method does not distinguish between welded, joint connected, or floating bodies.
- Returns
The
: total mass of all bodies belonging to a model instance in model_instances or 0 if model_instances is empty.
Note
The mass of the world_body() does not contribute to the total mass and each body only contributes to the total mass once, even if the body has repeated occurrence (instance) in model_instances.
- CollectRegisteredGeometries(self: pydrake.multibody.plant.MultibodyPlant_[Expression], bodies: list[pydrake.multibody.tree.RigidBody_[Expression]]) pydrake.geometry.GeometrySet
For each of the provided
bodies
, collects up all geometries that have been registered to that body. Intended to be used in conjunction with CollisionFilterDeclaration and CollisionFilterManager::Apply() to filter collisions between the geometries registered to the bodies.For example:
Click to expand C++ code...
// Don't report on collisions between geometries affixed to `body1`, // `body2`, or `body3`. std::vector<const RigidBody<T>*> bodies{&body1, &body2, &body3}; geometry::GeometrySet set = plant.CollectRegisteredGeometries(bodies); scene_graph.collision_filter_manager().Apply( CollisionFilterDeclaration().ExcludeWithin(set));
Note
There is a very specific order of operations:
Bodies and geometries must be added to the MultibodyPlant.
Create GeometrySet instances from bodies (via this method).
Invoke SceneGraph::ExcludeCollisions*() to filter collisions.
Allocate context.
Changing the order will cause exceptions to be thrown.
- Raises
RuntimeError if this MultibodyPlant was not registered with a –
SceneGraph. –
- deformable_model(self: pydrake.multibody.plant.MultibodyPlant_[Expression]) drake::multibody::DeformableModel<drake::symbolic::Expression>
Returns the DeformableModel owned by this plant.
- Raises
RuntimeError if this plant doesn't own a DeformableModel. –
Warning
This feature is considered to be experimental and may change or be removed at any time, without any deprecation notice ahead of time.
- EvalBodyPoseInWorld(self: pydrake.multibody.plant.MultibodyPlant_[Expression], context: pydrake.systems.framework.Context_[Expression], body: pydrake.multibody.tree.RigidBody_[Expression]) pydrake.math.RigidTransform_[Expression]
Evaluate the pose
X_WB
of a body B in the world frame W.- Parameter
context
: The context storing the state of the model.
- Parameter
body_B
: The body B for which the pose is requested.
- Returns
X_WB
: The pose of body frame B in the world frame W.
- Raises
RuntimeError if Finalize() was not called on this model or if –
body_B` does not belong to this model –
- Parameter
- EvalBodySpatialAccelerationInWorld(self: pydrake.multibody.plant.MultibodyPlant_[Expression], context: pydrake.systems.framework.Context_[Expression], body: pydrake.multibody.tree.RigidBody_[Expression]) pydrake.multibody.math.SpatialAcceleration_[Expression]
Evaluates A_WB, body B’s spatial acceleration in the world frame W.
- Parameter
context
: The context storing the state of the model.
- Parameter
body_B
: The body for which spatial acceleration is requested.
- Returns
A_WB_W
: RigidBody B’s spatial acceleration in the world frame W, expressed in W (for point Bo, the body’s origin).
- Raises
RuntimeError if Finalize() was not called on this model or if –
body_B` does not belong to this model –
Note
When cached values are out of sync with the state stored in context, this method performs an expensive forward dynamics computation, whereas once evaluated, successive calls to this method are inexpensive.
- Parameter
- EvalBodySpatialVelocityInWorld(self: pydrake.multibody.plant.MultibodyPlant_[Expression], context: pydrake.systems.framework.Context_[Expression], body: pydrake.multibody.tree.RigidBody_[Expression]) pydrake.multibody.math.SpatialVelocity_[Expression]
Evaluates V_WB, body B’s spatial velocity in the world frame W.
- Parameter
context
: The context storing the state of the model.
- Parameter
body_B
: The body B for which the spatial velocity is requested.
- Returns
V_WB_W
: RigidBody B’s spatial velocity in the world frame W, expressed in W (for point Bo, the body’s origin).
- Raises
RuntimeError if Finalize() was not called on this model or if –
body_B` does not belong to this model –
- Parameter
- EvalSceneGraphInspector(self: pydrake.multibody.plant.MultibodyPlant_[Expression], context: pydrake.systems.framework.Context_[Expression]) pydrake.geometry.SceneGraphInspector_[Expression]
Returns the inspector from the
context
for the SceneGraph associated with this plant, via this plant’s “geometry_query” input port. (In the future, the inspector might come from a different context source that is more efficient than the “geometry_query” input port.)
- Finalize(self: pydrake.multibody.plant.MultibodyPlant_[Expression]) None
This method must be called after all elements in the model (joints, bodies, force elements, constraints, etc.) are added and before any computations are performed. It essentially compiles all the necessary “topological information”, i.e. how bodies, joints and, any other elements connect with each other, and performs all the required pre-processing to enable computations at a later stage.
If the finalize stage is successful, the topology of this MultibodyPlant is valid, meaning that the topology is up-to-date after this call. No more multibody elements can be added after a call to Finalize().
At Finalize(), state and input/output ports for
this
plant are declared.For a full account of the effects of Finalize(), see mbp_finalize_stage “Finalize() stage”.
See also
is_finalized(), mbp_finalize_stage “Finalize() stage”.
- Raises
RuntimeError if the MultibodyPlant has already been finalized. –
- geometry_source_is_registered(self: pydrake.multibody.plant.MultibodyPlant_[Expression]) bool
Returns
True
ifthis
MultibodyPlant was registered with a SceneGraph. This method can be called at any time during the lifetime ofthis
plant to query ifthis
plant has been registered with a SceneGraph, either pre- or post-finalize, see Finalize().
- get_actuation_input_port(*args, **kwargs)
Overloaded function.
get_actuation_input_port(self: pydrake.multibody.plant.MultibodyPlant_[Expression]) -> pydrake.systems.framework.InputPort_[Expression]
Returns a constant reference to the input port for external actuation for all actuated dofs. This input port is a vector valued port and can be set with JointActuator::set_actuation_vector(). The actuation value for a particular actuator can be found at offset JointActuator::input_start() in this vector. Refer to mbp_actuation “Actuation” for further details.
- Precondition:
Finalize() was already called on
this
plant.
- Raises
RuntimeError if called before Finalize() –
get_actuation_input_port(self: pydrake.multibody.plant.MultibodyPlant_[Expression], model_instance: pydrake.multibody.tree.ModelInstanceIndex) -> pydrake.systems.framework.InputPort_[Expression]
Returns a constant reference to the input port for external actuation for a specific model instance. This is a vector valued port with entries ordered by monotonically increasing JointActuatorIndex within
model_instance
. Refer to mbp_actuation “Actuation” for further details.Every model instance in
this
plant model has an actuation input port, even if zero sized (for model instance with no actuators).See also
GetJointActuatorIndices(), GetActuatedJointIndices().
- Precondition:
Finalize() was already called on
this
plant.
- Raises
RuntimeError if called before Finalize() –
RuntimeError if the model instance does not exist. –
- get_adjacent_bodies_collision_filters(self: pydrake.multibody.plant.MultibodyPlant_[Expression]) bool
Returns whether to apply collision filters to topologically adjacent bodies at Finalize() time.
- get_applied_generalized_force_input_port(self: pydrake.multibody.plant.MultibodyPlant_[Expression]) pydrake.systems.framework.InputPort_[Expression]
Returns a constant reference to the vector-valued input port for applied generalized forces, and the vector will be added directly into
tau
(see mbp_equations_of_motion “System dynamics”). This vector is ordered using the same convention as the plant velocities: you can set the generalized forces that will be applied to model instance i using, e.g.,SetVelocitiesInArray(i, model_forces, &force_array)
.- Raises
RuntimeError if called before Finalize() –
- get_applied_spatial_force_input_port(self: pydrake.multibody.plant.MultibodyPlant_[Expression]) pydrake.systems.framework.InputPort_[Expression]
Returns a constant reference to the input port for applying spatial forces to bodies in the plant. The data type for the port is an std::vector of ExternallyAppliedSpatialForce; any number of spatial forces can be applied to any number of bodies in the plant.
- get_body(self: pydrake.multibody.plant.MultibodyPlant_[Expression], body_index: pydrake.multibody.tree.BodyIndex) pydrake.multibody.tree.RigidBody_[Expression]
Returns a constant reference to the body with unique index
body_index
.- Raises
RuntimeError if body_index does not correspond to a body in –
this model. –
- get_body_poses_output_port(self: pydrake.multibody.plant.MultibodyPlant_[Expression]) pydrake.systems.framework.OutputPort_[Expression]
Returns the output port of all body poses in the world frame. You can obtain the pose
X_WB
of a body B in the world frame W with:Click to expand C++ code...
const auto& X_WB_all = plant.get_body_poses_output_port(). .Eval<std::vector<math::RigidTransform<double>>>(plant_context); const BodyIndex arm_body_index = plant.GetBodyByName("arm").index(); const math::RigidTransform<double>& X_WArm = X_WB_all[arm_body_index];
As shown in the example above, the resulting
std::vector
of body poses is indexed by BodyIndex, and it has size num_bodies(). BodyIndex “zero” (0) always corresponds to the world body, with pose equal to the identity at all times.- Raises
RuntimeError if called pre-finalize. –
- get_body_spatial_accelerations_output_port(self: pydrake.multibody.plant.MultibodyPlant_[Expression]) pydrake.systems.framework.OutputPort_[Expression]
Returns the output port of all body spatial accelerations in the world frame. You can obtain the spatial acceleration
A_WB
of a body B (for point Bo, the body’s origin) in the world frame W with:Click to expand C++ code...
const auto& A_WB_all = plant.get_body_spatial_accelerations_output_port(). .Eval<std::vector<SpatialAcceleration<double>>>(plant_context); const BodyIndex arm_body_index = plant.GetBodyByName("arm").index(); const SpatialVelocity<double>& A_WArm = A_WB_all[arm_body_index];
As shown in the example above, the resulting
std::vector
of body spatial accelerations is indexed by BodyIndex, and it has size num_bodies(). BodyIndex “zero” (0) always corresponds to the world body, with zero spatial acceleration at all times.In a discrete-time plant, the use_sampled_output_ports setting affects the output of this port. See output_port_sampling “Output port sampling” for details. When sampling is enabled and the plant has not yet taken a step, the output value will be all zeros.
- Raises
RuntimeError if called pre-finalize. –
- get_body_spatial_velocities_output_port(self: pydrake.multibody.plant.MultibodyPlant_[Expression]) pydrake.systems.framework.OutputPort_[Expression]
Returns the output port of all body spatial velocities in the world frame. You can obtain the spatial velocity
V_WB
of a body B in the world frame W with:Click to expand C++ code...
const auto& V_WB_all = plant.get_body_spatial_velocities_output_port(). .Eval<std::vector<SpatialVelocity<double>>>(plant_context); const BodyIndex arm_body_index = plant.GetBodyByName("arm").index(); const SpatialVelocity<double>& V_WArm = V_WB_all[arm_body_index];
As shown in the example above, the resulting
std::vector
of body spatial velocities is indexed by BodyIndex, and it has size num_bodies(). BodyIndex “zero” (0) always corresponds to the world body, with zero spatial velocity at all times.- Raises
RuntimeError if called pre-finalize. –
- get_contact_model(self: pydrake.multibody.plant.MultibodyPlant_[Expression]) pydrake.multibody.plant.ContactModel
Returns the model used for contact. See documentation for ContactModel.
- get_contact_penalty_method_time_scale(self: pydrake.multibody.plant.MultibodyPlant_[Expression]) float
Returns a time-scale estimate
tc
based on the requested penetration allowance δ set with set_penetration_allowance(). For the compliant contact model to enforce non-penetration, this time scale relates to the time it takes the relative normal velocity between two bodies to go to zero. This time scaletc
is a global estimate of the dynamics introduced by the compliant contact model and goes to zero in the limit to ideal rigid contact. Since numerical integration methods for continuum systems must be able to resolve a system’s dynamics, the time step used by an integrator must in general be much smaller than the time scaletc
. How much smaller will depend on the details of the problem and the convergence characteristics of the integrator and should be tuned appropriately. Another factor to take into account for setting up the simulation’s time step is the speed of the objects in your simulation. Ifvn
represents a reference velocity scale for the normal relative velocity between bodies, the new time scaletn = δ / vn
represents the time it would take for the distance between two bodies approaching with relative normal velocityvn
to decrease by the penetration_allowance δ. In this case a user should choose a time step for simulation that can resolve the smallest of the two time scalestc
andtn
.
- get_contact_results_output_port(self: pydrake.multibody.plant.MultibodyPlant_[Expression]) pydrake.systems.framework.OutputPort_[Expression]
Returns a constant reference to the port that outputs ContactResults.
In a discrete-time plant, the use_sampled_output_ports setting affects the output of this port. See output_port_sampling “Output port sampling” for details. When sampling is enabled and the plant has not yet taken a step, the output value will be empty (no contacts).
- Raises
RuntimeError if called pre-finalize, see Finalize() –
- get_contact_surface_representation(self: pydrake.multibody.plant.MultibodyPlant_[Expression]) pydrake.geometry.HydroelasticContactRepresentation
Gets the current representation of contact surfaces used by
this
MultibodyPlant.
- get_deformable_body_configuration_output_port(self: pydrake.multibody.plant.MultibodyPlant_[Expression]) pydrake.systems.framework.OutputPort_[Expression]
Returns the output port for vertex positions (configurations), measured and expressed in the World frame, of the deformable bodies in
this
plant as a GeometryConfigurationVector.
- get_desired_state_input_port(self: pydrake.multibody.plant.MultibodyPlant_[Expression], model_instance: pydrake.multibody.tree.ModelInstanceIndex) pydrake.systems.framework.InputPort_[Expression]
For models with PD controlled joint actuators, returns the port to provide the desired state for the full
model_instance
. Refer to mbp_actuation “Actuation” for further details.For consistency with get_actuation_input_port(), each model instance in
this
plant model has a desired states input port, even if zero sized (for model instance with no actuators.)Note
This is a vector valued port of size 2*num_actuators(model_instance), where we assumed 1-DOF actuated joints. This is true even for unactuated models, for which this port is zero sized. This port must provide one desired position and one desired velocity per joint actuator. Desired state is assumed to be packed as xd = [qd, vd] that is, configurations first followed by velocities. The actuation value for a particular actuator can be found at offset JointActuator::input_start() in both qd and vd. For example:
Click to expand C++ code...
const double qd_actuator = xd[actuator.input_start()]; const double vd_actuator = xd[actuator.input_start() + plant.num_actuated_dofs()];
Warning
If a user specifies a PD controller for an actuator from a given model instance, then all actuators of that model instance are required to be PD controlled.
Warning
It is required to connect this port for PD controlled model instances.
- get_discrete_contact_approximation(self: pydrake.multibody.plant.MultibodyPlant_[Expression]) pydrake.multibody.plant.DiscreteContactApproximation
- Returns
the discrete contact solver approximation.
- get_discrete_contact_solver(self: pydrake.multibody.plant.MultibodyPlant_[Expression]) pydrake.multibody.plant.DiscreteContactSolver
Returns the contact solver type used for discrete MultibodyPlant models.
- get_force_element(self: pydrake.multibody.plant.MultibodyPlant_[Expression], force_element_index: pydrake.multibody.tree.ForceElementIndex) pydrake.multibody.tree.ForceElement_[Expression]
Returns a constant reference to the force element with unique index
force_element_index
.- Raises
RuntimeError when force_element_index does not correspond to a –
force element in this model. –
- get_frame(self: pydrake.multibody.plant.MultibodyPlant_[Expression], frame_index: pydrake.multibody.tree.FrameIndex) pydrake.multibody.tree.Frame_[Expression]
Returns a constant reference to the frame with unique index
frame_index
.- Raises
RuntimeError if frame_index does not correspond to a frame in –
this plant. –
- get_generalized_acceleration_output_port(*args, **kwargs)
Overloaded function.
get_generalized_acceleration_output_port(self: pydrake.multibody.plant.MultibodyPlant_[Expression]) -> pydrake.systems.framework.OutputPort_[Expression]
Returns a constant reference to the output port for generalized accelerations v̇ of the model.
In a discrete-time plant, the use_sampled_output_ports setting affects the output of this port. See output_port_sampling “Output port sampling” for details. When sampling is enabled and the plant has not yet taken a step, the output value will be all zeros.
- Precondition:
Finalize() was already called on
this
plant.
- Raises
RuntimeError if called before Finalize() –
get_generalized_acceleration_output_port(self: pydrake.multibody.plant.MultibodyPlant_[Expression], model_instance: pydrake.multibody.tree.ModelInstanceIndex) -> pydrake.systems.framework.OutputPort_[Expression]
Returns a constant reference to the output port for the generalized accelerations v̇ᵢ ⊆ v̇ for model instance i.
In a discrete-time plant, the use_sampled_output_ports setting affects the output of this port. See output_port_sampling “Output port sampling” for details. When sampling is enabled and the plant has not yet taken a step, the output value will be all zeros.
- Precondition:
Finalize() was already called on
this
plant.
- Raises
RuntimeError if called before Finalize() –
RuntimeError if the model instance does not exist. –
- get_generalized_contact_forces_output_port(self: pydrake.multibody.plant.MultibodyPlant_[Expression], model_instance: pydrake.multibody.tree.ModelInstanceIndex) pydrake.systems.framework.OutputPort_[Expression]
Returns a constant reference to the output port of generalized contact forces for a specific model instance.
In a discrete-time plant, the use_sampled_output_ports setting affects the output of this port. See output_port_sampling “Output port sampling” for details. When sampling is enabled and the plant has not yet taken a step, the output value will be all zeros.
- Precondition:
Finalize() was already called on
this
plant.
- Raises
RuntimeError if called before Finalize() –
RuntimeError if the model instance does not exist. –
- get_geometry_pose_output_port(self: pydrake.multibody.plant.MultibodyPlant_[Expression]) pydrake.systems.framework.OutputPort_[Expression]
Returns the output port of frames’ poses to communicate with a SceneGraph.
- get_geometry_query_input_port(self: pydrake.multibody.plant.MultibodyPlant_[Expression]) pydrake.systems.framework.InputPort_[Expression]
Returns a constant reference to the input port used to perform geometric queries on a SceneGraph. See SceneGraph::get_query_output_port(). Refer to section mbp_geometry “Geometry” of this class’s documentation for further details on collision geometry registration and connection with a SceneGraph.
- get_joint(self: pydrake.multibody.plant.MultibodyPlant_[Expression], joint_index: pydrake.multibody.tree.JointIndex) pydrake.multibody.tree.Joint_[Expression]
Returns a constant reference to the joint with unique index
joint_index
.- Raises
RuntimeError when joint_index does not correspond to a joint –
in this model. –
- get_joint_actuator(self: pydrake.multibody.plant.MultibodyPlant_[Expression], actuator_index: pydrake.multibody.tree.JointActuatorIndex) pydrake.multibody.tree.JointActuator_[Expression]
Returns a constant reference to the joint actuator with unique index
actuator_index
.- Raises
RuntimeError if actuator_index does not correspond to a joint –
actuator in this tree. –
- get_mutable_joint(self: pydrake.multibody.plant.MultibodyPlant_[Expression], joint_index: pydrake.multibody.tree.JointIndex) pydrake.multibody.tree.Joint_[Expression]
Returns a mutable reference to the joint with unique index
joint_index
.- Raises
RuntimeError when joint_index does not correspond to a joint –
in this model. –
- get_mutable_joint_actuator(self: pydrake.multibody.plant.MultibodyPlant_[Expression], actuator_index: pydrake.multibody.tree.JointActuatorIndex) pydrake.multibody.tree.JointActuator_[Expression]
Returns a mutable reference to the joint actuator with unique index
actuator_index
.- Raises
RuntimeError if actuator_index does not correspond to a joint –
actuator in this tree. –
- get_net_actuation_output_port(*args, **kwargs)
Overloaded function.
get_net_actuation_output_port(self: pydrake.multibody.plant.MultibodyPlant_[Expression]) -> pydrake.systems.framework.OutputPort_[Expression]
Returns a constant reference to the output port that reports actuation values applied through joint actuators. This output port is a vector valued port. The actuation value for a particular actuator can be found at offset JointActuator::input_start() in this vector. Models that include PD controllers will include their contribution in this port, refer to mbp_actuation “Actuation” for further details.
In a discrete-time plant, the use_sampled_output_ports setting affects the output of this port. See output_port_sampling “Output port sampling” for details. When sampling is enabled and the plant has not yet taken a step, the output value will be all zeros.
Note
PD controllers are not considered for actuators on locked joints, see Joint::Lock(). Therefore they do not contribute to this port.
- Precondition:
Finalize() was already called on
this
plant.
- Raises
RuntimeError if called before Finalize() –
get_net_actuation_output_port(self: pydrake.multibody.plant.MultibodyPlant_[Expression], model_instance: pydrake.multibody.tree.ModelInstanceIndex) -> pydrake.systems.framework.OutputPort_[Expression]
Returns a constant reference to the output port that reports actuation values applied through joint actuators, for a specific model instance. Models that include PD controllers will include their contribution in this port, refer to mbp_actuation “Actuation” for further details. This is a vector valued port with entries ordered by monotonically increasing JointActuatorIndex within
model_instance
.Every model instance in
this
plant model has a net actuation output port, even if zero sized (for model instance with no actuators).In a discrete-time plant, the use_sampled_output_ports setting affects the output of this port. See output_port_sampling “Output port sampling” for details. When sampling is enabled and the plant has not yet taken a step, the output value will be all zeros.
Note
PD controllers are not considered for actuators on locked joints, see Joint::Lock(). Therefore they do not contribute to this port.
- Precondition:
Finalize() was already called on
this
plant.
- Raises
RuntimeError if called before Finalize() –
- get_reaction_forces_output_port(self: pydrake.multibody.plant.MultibodyPlant_[Expression]) pydrake.systems.framework.OutputPort_[Expression]
Returns the port for joint reaction forces. A Joint models the kinematical relationship which characterizes the possible relative motion between two bodies. In Drake, a joint connects a frame
Jp
on parent body P with a frameJc
on a child body C. This usage of the terms parent and child is just a convention and implies nothing about the inboard-outboard relationship between the bodies. Since a Joint imposes a kinematical relationship which characterizes the possible relative motion between frames Jp and Jc, reaction forces on each body are established. That is, we could cut the model at the joint and replace it with equivalent forces equal to these reaction forces in order to attain the same motions of the mechanical system.This output port allows to evaluate the reaction force
F_CJc_Jc
on the child body C, atJc
, and expressed in Jc for all joints in the model. This port evaluates to a vector of type std::vector<SpatialForce<T>> and size num_joints() indexed by JointIndex, see Joint::index(). Each entry corresponds to the spatial forceF_CJc_Jc
applied on the joint’s child body C (Joint::child_body()), at the joint’s child frameJc
(Joint::frame_on_child()) and expressed in frameJc
.In a discrete-time plant, the use_sampled_output_ports setting affects the output of this port. See output_port_sampling “Output port sampling” for details. When sampling is enabled and the plant has not yet taken a step, the output value will be all zeros.
- Raises
RuntimeError if called pre-finalize. –
- get_sap_near_rigid_threshold(self: pydrake.multibody.plant.MultibodyPlant_[Expression]) float
- Returns
the SAP near rigid regime threshold.
See also
See set_sap_near_rigid_threshold().
- get_source_id(self: pydrake.multibody.plant.MultibodyPlant_[Expression]) Optional[pydrake.geometry.SourceId]
Returns the unique id identifying
this
plant as a source for a SceneGraph. Returnsnullopt
ifthis
plant did not register any geometry. This method can be called at any time during the lifetime ofthis
plant to query ifthis
plant has been registered with a SceneGraph, either pre- or post-finalize, see Finalize(). However, a geometry::SourceId is only assigned once at the first call of any of this plant’s geometry registration methods, and it does not change after that. Post-finalize calls will always return the same value.
- get_state_output_port(*args, **kwargs)
Overloaded function.
get_state_output_port(self: pydrake.multibody.plant.MultibodyPlant_[Expression]) -> pydrake.systems.framework.OutputPort_[Expression]
Returns a constant reference to the output port for the multibody state x = [q, v] of the model.
- Precondition:
Finalize() was already called on
this
plant.
- Raises
RuntimeError if called before Finalize() –
get_state_output_port(self: pydrake.multibody.plant.MultibodyPlant_[Expression], model_instance: pydrake.multibody.tree.ModelInstanceIndex) -> pydrake.systems.framework.OutputPort_[Expression]
Returns a constant reference to the output port for the state xᵢ = [qᵢ vᵢ] of model instance i. (Here qᵢ ⊆ q and vᵢ ⊆ v.)
- Precondition:
Finalize() was already called on
this
plant.
- Raises
RuntimeError if called before Finalize() –
RuntimeError if the model instance does not exist. –
- GetAccelerationLowerLimits(self: pydrake.multibody.plant.MultibodyPlant_[Expression]) numpy.ndarray[numpy.float64[m, 1]]
Returns a vector of size
num_velocities()
containing the lower acceleration limits for every generalized velocity coordinate. These include joint and free body coordinates. Any unbounded or unspecified limits will be -infinity.- Raises
RuntimeError if called pre-finalize. –
- GetAccelerationUpperLimits(self: pydrake.multibody.plant.MultibodyPlant_[Expression]) numpy.ndarray[numpy.float64[m, 1]]
Upper limit analog of GetAccelerationsLowerLimits(), where any unbounded or unspecified limits will be +infinity.
See also
GetAccelerationLowerLimits() for more information.
- GetActuatedJointIndices(self: pydrake.multibody.plant.MultibodyPlant_[Expression], model_instance: pydrake.multibody.tree.ModelInstanceIndex) list[pydrake.multibody.tree.JointIndex]
Returns a list of actuated joint indices associated with
model_instance
.- Raises
RuntimeError if called pre-finalize. –
- GetActuatorNames(*args, **kwargs)
Overloaded function.
GetActuatorNames(self: pydrake.multibody.plant.MultibodyPlant_[Expression], add_model_instance_prefix: bool = True) -> list[str]
Returns a list of string names corresponding to each element of the actuation vector. These strings take the form
{model_instance_name}_{joint_actuator_name}
, but the prefix may optionally be withheld usingadd_model_instance_prefix
.The returned names are guaranteed to be unique if
add_model_instance_prefix
isTrue
(the default).- Raises
RuntimeError if the plant is not finalized. –
GetActuatorNames(self: pydrake.multibody.plant.MultibodyPlant_[Expression], model_instance: pydrake.multibody.tree.ModelInstanceIndex, add_model_instance_prefix: bool = False) -> list[str]
Returns a list of string names corresponding to each element of the actuation vector. These strings take the form
{model_instance_name}_{joint_actuator_name}
, but the prefix may optionally be withheld usingadd_model_instance_prefix
.The returned names are guaranteed to be unique.
- Raises
RuntimeError if the plant is not finalized or if the –
model_instance` is invalid –
- GetBodiesKinematicallyAffectedBy(self: pydrake.multibody.plant.MultibodyPlant_[Expression], joint_indexes: list[pydrake.multibody.tree.JointIndex]) list[pydrake.multibody.tree.BodyIndex]
Returns all bodies whose kinematics are transitively affected by the given vector of Joints. The affected bodies are returned in increasing order of body indexes. Note that this is a kinematic relationship rather than a dynamic one. For example, if one of the inboard joints is a free (6dof) joint, the kinematic influence is still felt even though dynamically there would be no influence on the outboard body. This function can be only be called post-finalize, see Finalize().
- Raises
RuntimeError if any of the given joint has an invalid index, –
doesn't correspond to a mobilizer, or is welded. –
- GetBodiesWeldedTo(self: pydrake.multibody.plant.MultibodyPlant_[Expression], body: pydrake.multibody.tree.RigidBody_[Expression]) list[pydrake.multibody.tree.RigidBody_[Expression]]
Returns all bodies that are transitively welded, or rigidly affixed, to
body
, per these two definitions:A body is always considered welded to itself.
2. Two unique bodies are considered welded together exclusively by the presence of a weld joint, not by other constructs that prevent mobility (e.g. constraints).
This method can be called at any time during the lifetime of
this
plant, either pre- or post-finalize, see Finalize().Meant to be used with
CollectRegisteredGeometries
.The following example demonstrates filtering collisions between all bodies rigidly affixed to a door (which could be moving) and all bodies rigidly affixed to the world:
Click to expand C++ code...
GeometrySet g_world = plant.CollectRegisteredGeometries( plant.GetBodiesWeldedTo(plant.world_body())); GeometrySet g_door = plant.CollectRegisteredGeometries( plant.GetBodiesWeldedTo(plant.GetBodyByName("door"))); scene_graph.ExcludeCollisionsBetweeen(g_world, g_door);
Note
Usages akin to this example may introduce redundant collision filtering; this will not have a functional impact, but may have a minor performance impact.
- Returns
all bodies rigidly fixed to
body
. This does not return the bodies in any prescribed order.- Raises
RuntimeError if body is not part of this plant. –
- GetBodyByName(*args, **kwargs)
Overloaded function.
GetBodyByName(self: pydrake.multibody.plant.MultibodyPlant_[Expression], name: str) -> pydrake.multibody.tree.RigidBody_[Expression]
Returns a constant reference to a body that is identified by the string
name
inthis
MultibodyPlant.- Raises
RuntimeError if there is no body with the requested name. –
RuntimeError if the body name occurs in multiple model instances. –
See also
HasBodyNamed() to query if there exists a body in
this
MultibodyPlant with a given specified name.GetBodyByName(self: pydrake.multibody.plant.MultibodyPlant_[Expression], name: str, model_instance: pydrake.multibody.tree.ModelInstanceIndex) -> pydrake.multibody.tree.RigidBody_[Expression]
Returns a constant reference to the body that is uniquely identified by the string
name
andmodel_instance
inthis
MultibodyPlant.- Raises
RuntimeError if there is no body with the requested name. –
See also
HasBodyNamed() to query if there exists a body in
this
MultibodyPlant with a given specified name.
- GetBodyFrameIdIfExists(self: pydrake.multibody.plant.MultibodyPlant_[Expression], body_index: pydrake.multibody.tree.BodyIndex) Optional[pydrake.geometry.FrameId]
If the body with
body_index
belongs to the called plant, it returns the geometry::FrameId associated with it. Otherwise, it returns nullopt.
- GetBodyFrameIdOrThrow(self: pydrake.multibody.plant.MultibodyPlant_[Expression], body_index: pydrake.multibody.tree.BodyIndex) pydrake.geometry.FrameId
If the body with
body_index
belongs to the called plant, it returns the geometry::FrameId associated with it. Otherwise this method throws an exception.- Raises
RuntimeError if the called plant does not have the body indicated –
by body_index. –
- GetBodyFromFrameId(self: pydrake.multibody.plant.MultibodyPlant_[Expression], arg0: pydrake.geometry.FrameId) pydrake.multibody.tree.RigidBody_[Expression]
Given a geometry frame identifier, returns a pointer to the body associated with that id (nullptr if there is no such body).
- GetBodyIndices(self: pydrake.multibody.plant.MultibodyPlant_[Expression], model_instance: pydrake.multibody.tree.ModelInstanceIndex) list[pydrake.multibody.tree.BodyIndex]
Returns a list of body indices associated with
model_instance
.
- GetCollisionGeometriesForBody(self: pydrake.multibody.plant.MultibodyPlant_[Expression], body: pydrake.multibody.tree.RigidBody_[Expression]) list[pydrake.geometry.GeometryId]
Returns an array of GeometryId’s identifying the different contact geometries for
body
previously registered with a SceneGraph.Note
This method can be called at any time during the lifetime of
this
plant, either pre- or post-finalize, see Finalize(). Post-finalize calls will always return the same value.See also
RegisterCollisionGeometry(), Finalize()
- GetConstraintActiveStatus(self: pydrake.multibody.plant.MultibodyPlant_[Expression], context: pydrake.systems.framework.Context_[Expression], id: pydrake.multibody.tree.MultibodyConstraintId) bool
Returns the active status of the constraint given by
id
incontext
.- Raises
RuntimeError if the MultibodyPlant has not been finalized. –
RuntimeError if id does not belong to any multibody constraint –
in context. –
- GetConstraintIds(self: pydrake.multibody.plant.MultibodyPlant_[Expression]) list[pydrake.multibody.tree.MultibodyConstraintId]
Returns a list of all constraint identifiers. The returned vector becomes invalid after any calls to Add*Constraint() or RemoveConstraint().
- static GetDefaultContactSurfaceRepresentation(time_step: float) pydrake.geometry.HydroelasticContactRepresentation
Return the default value for contact representation, given the desired time step. Discrete systems default to use polygons; continuous systems default to use triangles.
- GetDefaultFreeBodyPose(self: pydrake.multibody.plant.MultibodyPlant_[Expression], body: pydrake.multibody.tree.RigidBody_[Expression]) pydrake.math.RigidTransform
Gets the default pose of
body
as set by SetDefaultFreeBodyPose(). If no pose is specified for the body, returns the identity pose.- Parameter
body
: RigidBody whose default pose will be retrieved.
- Returns
X_PB
: The pose of the free body relative to its parent frame.
Note
The parent frame is not necessarily the world frame. See mbp_working_with_free_bodies “above for details”.
- Parameter
- GetDefaultPositions(*args, **kwargs)
Overloaded function.
GetDefaultPositions(self: pydrake.multibody.plant.MultibodyPlant_[Expression]) -> numpy.ndarray[object[m, 1]]
Gets the default positions for the plant, which can be changed via SetDefaultPositions().
- Raises
RuntimeError if the plant is not finalized. –
GetDefaultPositions(self: pydrake.multibody.plant.MultibodyPlant_[Expression], model_instance: pydrake.multibody.tree.ModelInstanceIndex) -> numpy.ndarray[object[m, 1]]
Gets the default positions for the plant for a given model instance, which can be changed via SetDefaultPositions().
- Raises
RuntimeError if the plant is not finalized, or if the –
model_instance is invalid, –
- GetEffortLowerLimits(self: pydrake.multibody.plant.MultibodyPlant_[Expression]) numpy.ndarray[numpy.float64[m, 1]]
Returns a vector of size
num_actuated_dofs()
containing the lower effort limits for every actuator. Any unbounded or unspecified limits will be -∞. The returned vector is indexed by JointActuatorIndex, see JointActuator::index().See also
GetEffortUpperLimits()
- Raises
RuntimeError if called pre-finalize. –
- GetEffortUpperLimits(self: pydrake.multibody.plant.MultibodyPlant_[Expression]) numpy.ndarray[numpy.float64[m, 1]]
Returns a vector of size
num_actuated_dofs()
containing the upper effort limits for every actuator. Any unbounded or unspecified limits will be +∞. The returned vector is indexed by JointActuatorIndex, see JointActuator::index().See also
GetEffortLowerLimits()
- Raises
RuntimeError if called pre-finalize. –
- GetFloatingBaseBodies(self: pydrake.multibody.plant.MultibodyPlant_[Expression]) set[pydrake.multibody.tree.BodyIndex]
Returns the set of body indices corresponding to the floating base bodies in the model, in no particular order.
- Raises
RuntimeError if called pre-finalize, see Finalize() –
- GetFrameByName(*args, **kwargs)
Overloaded function.
GetFrameByName(self: pydrake.multibody.plant.MultibodyPlant_[Expression], name: str) -> pydrake.multibody.tree.Frame_[Expression]
Returns a constant reference to a frame that is identified by the string
name
inthis
model.- Raises
RuntimeError if there is no frame with the requested name. –
RuntimeError if the frame name occurs in multiple model instances. –
See also
HasFrameNamed() to query if there exists a frame in
this
model with a given specified name.GetFrameByName(self: pydrake.multibody.plant.MultibodyPlant_[Expression], name: str, model_instance: pydrake.multibody.tree.ModelInstanceIndex) -> pydrake.multibody.tree.Frame_[Expression]
Returns a constant reference to the frame that is uniquely identified by the string
name
inmodel_instance
.- Raises
RuntimeError if there is no frame with the requested name. –
RuntimeError if model_instance is not valid for this model. –
See also
HasFrameNamed() to query if there exists a frame in
this
model with a given specified name.
- GetFrameIndices(self: pydrake.multibody.plant.MultibodyPlant_[Expression], model_instance: pydrake.multibody.tree.ModelInstanceIndex) list[pydrake.multibody.tree.FrameIndex]
Returns a list of frame indices associated with
model_instance
.
- GetFreeBodyPose(self: pydrake.multibody.plant.MultibodyPlant_[Expression], context: pydrake.systems.framework.Context_[Expression], body: pydrake.multibody.tree.RigidBody_[Expression]) pydrake.math.RigidTransform_[Expression]
Gets the pose of a given
body
in the parent frame P.Note
The parent frame is not necessarily the world frame. See mbp_working_with_free_bodies “above for details”. To acquire X_WB, regardless of what P is, kinematics need to be evaluated by calling EvalBodyPoseInWorld().
- Raises
RuntimeError if body is not a free body in the model. –
RuntimeError if called pre-finalize. –
- GetJointActuatorByName(*args, **kwargs)
Overloaded function.
GetJointActuatorByName(self: pydrake.multibody.plant.MultibodyPlant_[Expression], name: str) -> pydrake.multibody.tree.JointActuator_[Expression]
Returns a constant reference to an actuator that is identified by the string
name
inthis
MultibodyPlant.- Raises
RuntimeError if there is no actuator with the requested name. –
RuntimeError if the actuator name occurs in multiple model –
instances. –
See also
HasJointActuatorNamed() to query if there exists an actuator in
this
MultibodyPlant with a given specified name.GetJointActuatorByName(self: pydrake.multibody.plant.MultibodyPlant_[Expression], name: str, model_instance: pydrake.multibody.tree.ModelInstanceIndex) -> pydrake.multibody.tree.JointActuator_[Expression]
Returns a constant reference to the actuator that is uniquely identified by the string
name
andmodel_instance
inthis
MultibodyPlant.- Raises
RuntimeError if there is no actuator with the requested name. –
RuntimeError if model_instance is not valid for this model. –
See also
HasJointActuatorNamed() to query if there exists an actuator in
this
MultibodyPlant with a given specified name.
- GetJointActuatorIndices(*args, **kwargs)
Overloaded function.
GetJointActuatorIndices(self: pydrake.multibody.plant.MultibodyPlant_[Expression]) -> list[pydrake.multibody.tree.JointActuatorIndex]
Returns a list of all joint actuator indices. The vector is ordered by monotonically increasing JointActuatorIndex, but the indices will in general not be consecutive due to actuators that were removed.
GetJointActuatorIndices(self: pydrake.multibody.plant.MultibodyPlant_[Expression], model_instance: pydrake.multibody.tree.ModelInstanceIndex) -> list[pydrake.multibody.tree.JointActuatorIndex]
Returns a list of joint actuator indices associated with
model_instance
. The vector is ordered by monotonically increasing JointActuatorIndex.- Raises
RuntimeError if called pre-finalize. –
- GetJointByName(self: pydrake.multibody.plant.MultibodyPlant_[Expression], name: str, model_instance: Optional[pydrake.multibody.tree.ModelInstanceIndex] = None) pydrake.multibody.tree.Joint_[Expression]
Returns a constant reference to a joint that is identified by the string
name
inthis
MultibodyPlant. If the optional template argument is supplied, then the returned value is downcast to the specifiedJointType
.- Template parameter
JointType
: The specific type of the Joint to be retrieved. It must be a subclass of Joint.
- Raises
RuntimeError if the named joint is not of type JointType or if –
there is no Joint with that name. –
RuntimeError if model_instance is not valid for this model. –
See also
HasJointNamed() to query if there exists a joint in
this
MultibodyPlant with a given specified name.- Template parameter
- GetJointIndices(*args, **kwargs)
Overloaded function.
GetJointIndices(self: pydrake.multibody.plant.MultibodyPlant_[Expression]) -> list[pydrake.multibody.tree.JointIndex]
Returns a list of all joint indices. The vector is ordered by monotonically increasing JointIndex, but the indices will in general not be consecutive due to joints that were removed.
GetJointIndices(self: pydrake.multibody.plant.MultibodyPlant_[Expression], model_instance: pydrake.multibody.tree.ModelInstanceIndex) -> list[pydrake.multibody.tree.JointIndex]
Returns a list of joint indices associated with
model_instance
.
- GetModelInstanceByName(self: pydrake.multibody.plant.MultibodyPlant_[Expression], name: str) pydrake.multibody.tree.ModelInstanceIndex
Returns the index to the model instance that is uniquely identified by the string
name
inthis
MultibodyPlant.- Raises
RuntimeError if there is no instance with the requested name. –
See also
HasModelInstanceNamed() to query if there exists an instance in
this
MultibodyPlant with a given specified name.
- GetModelInstanceName(self: pydrake.multibody.plant.MultibodyPlant_[Expression], model_instance: pydrake.multibody.tree.ModelInstanceIndex) str
Returns the name of a
model_instance
.- Raises
RuntimeError when model_instance does not correspond to a –
model in this model. –
- GetMutableJointByName(self: pydrake.multibody.plant.MultibodyPlant_[Expression], name: str, model_instance: Optional[pydrake.multibody.tree.ModelInstanceIndex] = None) pydrake.multibody.tree.Joint_[Expression]
Returns a constant reference to a joint that is identified by the string
name
inthis
MultibodyPlant. If the optional template argument is supplied, then the returned value is downcast to the specifiedJointType
.- Template parameter
JointType
: The specific type of the Joint to be retrieved. It must be a subclass of Joint.
- Raises
RuntimeError if the named joint is not of type JointType or if –
there is no Joint with that name. –
RuntimeError if model_instance is not valid for this model. –
See also
HasJointNamed() to query if there exists a joint in
this
MultibodyPlant with a given specified name.- Template parameter
- GetPositionLowerLimits(self: pydrake.multibody.plant.MultibodyPlant_[Expression]) numpy.ndarray[numpy.float64[m, 1]]
Returns a vector of size
num_positions()
containing the lower position limits for every generalized position coordinate. These include joint and free body coordinates. Any unbounded or unspecified limits will be -infinity.- Raises
RuntimeError if called pre-finalize. –
- GetPositionNames(*args, **kwargs)
Overloaded function.
GetPositionNames(self: pydrake.multibody.plant.MultibodyPlant_[Expression], add_model_instance_prefix: bool = True, always_add_suffix: bool = True) -> list[str]
Returns a list of string names corresponding to each element of the position vector. These strings take the form
{model_instance_name}_{joint_name}_{joint_position_suffix}
, but the prefix and suffix may optionally be withheld usingadd_model_instance_prefix
andalways_add_suffix
.- Parameter
always_add_suffix
: (optional). If true, then the suffix is always added. If false, then the suffix is only added for joints that have more than one position (in this case, not adding would lead to ambiguity).
The returned names are guaranteed to be unique if
add_model_instance_prefix
isTrue
(the default).- Raises
RuntimeError if the plant is not finalized. –
GetPositionNames(self: pydrake.multibody.plant.MultibodyPlant_[Expression], model_instance: pydrake.multibody.tree.ModelInstanceIndex, add_model_instance_prefix: bool = False, always_add_suffix: bool = True) -> list[str]
Returns a list of string names corresponding to each element of the position vector. These strings take the form
{model_instance_name}_{joint_name}_{joint_position_suffix}
, but the prefix and suffix may optionally be withheld usingadd_model_instance_prefix
andalways_add_suffix
.- Parameter
always_add_suffix
: (optional). If true, then the suffix is always added. If false, then the suffix is only added for joints that have more than one position (in this case, not adding would lead to ambiguity).
The returned names are guaranteed to be unique.
- Raises
RuntimeError if the plant is not finalized or if the –
model_instance` is invalid –
- GetPositions(*args, **kwargs)
Overloaded function.
GetPositions(self: pydrake.multibody.plant.MultibodyPlant_[Expression], context: pydrake.systems.framework.Context_[Expression]) -> numpy.ndarray[object[m, 1]]
Returns a const vector reference to the vector of generalized positions q in a given Context.
Note
This method returns a reference to existing data, exhibits constant i.e., O(1) time complexity, and runs very quickly.
- Raises
RuntimeError if context does not correspond to the Context for –
a multibody model. –
GetPositions(self: pydrake.multibody.plant.MultibodyPlant_[Expression], context: pydrake.systems.framework.Context_[Expression], model_instance: pydrake.multibody.tree.ModelInstanceIndex) -> numpy.ndarray[object[m, 1]]
Returns a vector containing the generalized positions q of a specified model instance in a given Context.
Note
Returns a dense vector of dimension
num_positions(model_instance)
associated withmodel_instance
by copying fromcontext
.- Raises
RuntimeError if context does not correspond to the Context for –
a multibody model or model_instance is invalid. –
GetPositions(self: pydrake.multibody.plant.MultibodyPlant_[Expression], context: pydrake.systems.framework.Context_[Expression]) -> numpy.ndarray[object[m, 1]]
Returns a const vector reference to the vector of generalized positions q in a given Context.
Note
This method returns a reference to existing data, exhibits constant i.e., O(1) time complexity, and runs very quickly.
- Raises
RuntimeError if context does not correspond to the Context for –
a multibody model. –
GetPositions(self: pydrake.multibody.plant.MultibodyPlant_[Expression], context: pydrake.systems.framework.Context_[Expression], model_instance: pydrake.multibody.tree.ModelInstanceIndex) -> numpy.ndarray[object[m, 1]]
Returns a vector containing the generalized positions q of a specified model instance in a given Context.
Note
Returns a dense vector of dimension
num_positions(model_instance)
associated withmodel_instance
by copying fromcontext
.- Raises
RuntimeError if context does not correspond to the Context for –
a multibody model or model_instance is invalid. –
- GetPositionsAndVelocities(*args, **kwargs)
Overloaded function.
GetPositionsAndVelocities(self: pydrake.multibody.plant.MultibodyPlant_[Expression], context: pydrake.systems.framework.Context_[Expression]) -> numpy.ndarray[object[m, 1]]
Returns a const vector reference
[q; v]
to the generalized positions q and generalized velocities v in a given Context.Note
This method returns a reference to existing data, exhibits constant i.e., O(1) time complexity, and runs very quickly.
- Raises
RuntimeError if context does not correspond to the Context for –
a multibody model. –
GetPositionsAndVelocities(self: pydrake.multibody.plant.MultibodyPlant_[Expression], context: pydrake.systems.framework.Context_[Expression], model_instance: pydrake.multibody.tree.ModelInstanceIndex) -> numpy.ndarray[object[m, 1]]
Returns a vector
[q; v]
containing the generalized positions q and generalized velocities v of a specified model instance in a given Context.Note
Returns a dense vector of dimension
num_positions(model_instance) + num_velocities(model_instance)
associated withmodel_instance
by copying fromcontext
.- Raises
RuntimeError if context does not correspond to the Context for –
a multibody model or model_instance is invalid. –
- GetPositionsFromArray(self: pydrake.multibody.plant.MultibodyPlant_[Expression], model_instance: pydrake.multibody.tree.ModelInstanceIndex, q: numpy.ndarray[object[m, 1]]) numpy.ndarray[object[m, 1]]
Returns a vector of generalized positions for
model_instance
from a vectorq_array
of generalized positions for the entire model model. This method throws an exception ifq
is not of size MultibodyPlant::num_positions().
- GetPositionUpperLimits(self: pydrake.multibody.plant.MultibodyPlant_[Expression]) numpy.ndarray[numpy.float64[m, 1]]
Upper limit analog of GetPositionLowerLimits(), where any unbounded or unspecified limits will be +infinity.
See also
GetPositionLowerLimits() for more information.
- GetRigidBodyByName(*args, **kwargs)
Overloaded function.
GetRigidBodyByName(self: pydrake.multibody.plant.MultibodyPlant_[Expression], name: str) -> pydrake.multibody.tree.RigidBody_[Expression]
Returns a constant reference to a rigid body that is identified by the string
name
inthis
model.- Raises
RuntimeError if there is no body with the requested name. –
RuntimeError if the body name occurs in multiple model instances. –
RuntimeError if the requested body is not a RigidBody. –
See also
HasBodyNamed() to query if there exists a body in
this
model with a given specified name.GetRigidBodyByName(self: pydrake.multibody.plant.MultibodyPlant_[Expression], name: str, model_instance: pydrake.multibody.tree.ModelInstanceIndex) -> pydrake.multibody.tree.RigidBody_[Expression]
Returns a constant reference to the rigid body that is uniquely identified by the string
name
inmodel_instance
.- Raises
RuntimeError if there is no body with the requested name. –
RuntimeError if the requested body is not a RigidBody. –
RuntimeError if model_instance is not valid for this model. –
See also
HasBodyNamed() to query if there exists a body in
this
model with a given specified name.
- GetStateNames(*args, **kwargs)
Overloaded function.
GetStateNames(self: pydrake.multibody.plant.MultibodyPlant_[Expression], add_model_instance_prefix: bool = True) -> list[str]
Returns a list of string names corresponding to each element of the multibody state vector. These strings take the form
{model_instance_name}_{joint_name}_{joint_position_suffix | joint_velocity_suffix}
, but the prefix may optionally be withheld usingadd_model_instance_prefix
.The returned names are guaranteed to be unique if
add_model_instance_prefix
isTrue
(the default).- Raises
RuntimeError if the plant is not finalized. –
GetStateNames(self: pydrake.multibody.plant.MultibodyPlant_[Expression], model_instance: pydrake.multibody.tree.ModelInstanceIndex, add_model_instance_prefix: bool = False) -> list[str]
Returns a list of string names corresponding to each element of the multibody state vector. These strings take the form
{model_instance_name}_{joint_name}_{joint_position_suffix | joint_velocity_suffix}
, but the prefix may optionally be withheld usingadd_model_instance_prefix
.The returned names are guaranteed to be unique.
- Raises
RuntimeError if the plant is not finalized or if the –
model_instance` is invalid –
- GetTopologyGraphvizString(self: pydrake.multibody.plant.MultibodyPlant_[Expression]) str
Returns a Graphviz string describing the topology of this plant. To render the string, use the Graphviz tool,
dot
. http://www.graphviz.org/Note: this method can be called either before or after
Finalize()
.
- GetUniqueFreeBaseBodyOrThrow(self: pydrake.multibody.plant.MultibodyPlant_[Expression], model_instance: pydrake.multibody.tree.ModelInstanceIndex) pydrake.multibody.tree.RigidBody_[Expression]
If there exists a unique base body that belongs to the model given by
model_instance
and that unique base body is free (see HasUniqueBaseBody()), return that free body. Throw an exception otherwise.- Raises
RuntimeError if called pre-finalize. –
RuntimeError if model_instance is not valid. –
RuntimeError if HasUniqueFreeBaseBody(model_instance) == false. –
- GetVelocities(*args, **kwargs)
Overloaded function.
GetVelocities(self: pydrake.multibody.plant.MultibodyPlant_[Expression], context: pydrake.systems.framework.Context_[Expression]) -> numpy.ndarray[object[m, 1]]
Returns a const vector reference to the generalized velocities v in a given Context.
Note
This method returns a reference to existing data, exhibits constant i.e., O(1) time complexity, and runs very quickly.
- Raises
RuntimeError if context does not correspond to the Context for –
a multibody model. –
GetVelocities(self: pydrake.multibody.plant.MultibodyPlant_[Expression], context: pydrake.systems.framework.Context_[Expression], model_instance: pydrake.multibody.tree.ModelInstanceIndex) -> numpy.ndarray[object[m, 1]]
Returns a vector containing the generalized velocities v of a specified model instance in a given Context.
Note
returns a dense vector of dimension
num_velocities(model_instance)
associated withmodel_instance
by copying fromcontext
.- Raises
RuntimeError if context does not correspond to the Context for –
a multibody model or model_instance is invalid. –
GetVelocities(self: pydrake.multibody.plant.MultibodyPlant_[Expression], context: pydrake.systems.framework.Context_[Expression]) -> numpy.ndarray[object[m, 1]]
Returns a const vector reference to the generalized velocities v in a given Context.
Note
This method returns a reference to existing data, exhibits constant i.e., O(1) time complexity, and runs very quickly.
- Raises
RuntimeError if context does not correspond to the Context for –
a multibody model. –
GetVelocities(self: pydrake.multibody.plant.MultibodyPlant_[Expression], context: pydrake.systems.framework.Context_[Expression], model_instance: pydrake.multibody.tree.ModelInstanceIndex) -> numpy.ndarray[object[m, 1]]
Returns a vector containing the generalized velocities v of a specified model instance in a given Context.
Note
returns a dense vector of dimension
num_velocities(model_instance)
associated withmodel_instance
by copying fromcontext
.- Raises
RuntimeError if context does not correspond to the Context for –
a multibody model or model_instance is invalid. –
- GetVelocitiesFromArray(self: pydrake.multibody.plant.MultibodyPlant_[Expression], model_instance: pydrake.multibody.tree.ModelInstanceIndex, v: numpy.ndarray[object[m, 1]]) numpy.ndarray[object[m, 1]]
Returns a vector of generalized velocities for
model_instance
from a vectorv
of generalized velocities for the entire MultibodyPlant model. This method throws an exception if the input array is not of size MultibodyPlant::num_velocities().
- GetVelocityLowerLimits(self: pydrake.multibody.plant.MultibodyPlant_[Expression]) numpy.ndarray[numpy.float64[m, 1]]
Returns a vector of size
num_velocities()
containing the lower velocity limits for every generalized velocity coordinate. These include joint and free body coordinates. Any unbounded or unspecified limits will be -infinity.- Raises
RuntimeError if called pre-finalize. –
- GetVelocityNames(*args, **kwargs)
Overloaded function.
GetVelocityNames(self: pydrake.multibody.plant.MultibodyPlant_[Expression], add_model_instance_prefix: bool = True, always_add_suffix: bool = True) -> list[str]
Returns a list of string names corresponding to each element of the velocity vector. These strings take the form
{model_instance_name}_{joint_name}_{joint_velocity_suffix}
, but the prefix and suffix may optionally be withheld usingadd_model_instance_prefix
andalways_add_suffix
.- Parameter
always_add_suffix
: (optional). If true, then the suffix is always added. If false, then the suffix is only added for joints that have more than one position (in this case, not adding would lead to ambiguity).
The returned names are guaranteed to be unique if
add_model_instance_prefix
isTrue
(the default).- Raises
RuntimeError if the plant is not finalized. –
GetVelocityNames(self: pydrake.multibody.plant.MultibodyPlant_[Expression], model_instance: pydrake.multibody.tree.ModelInstanceIndex, add_model_instance_prefix: bool = False, always_add_suffix: bool = True) -> list[str]
Returns a list of string names corresponding to each element of the velocity vector. These strings take the form
{model_instance_name}_{joint_name}_{joint_velocity_suffix}
, but the prefix and suffix may optionally be withheld usingadd_model_instance_prefix
andalways_add_suffix
.- Parameter
always_add_suffix
: (optional). If true, then the suffix is always added. If false, then the suffix is only added for joints that have more than one position (in this case, not adding would lead to ambiguity).
The returned names are guaranteed to be unique.
- Raises
RuntimeError if the plant is not finalized or if the –
model_instance` is invalid –
- GetVelocityUpperLimits(self: pydrake.multibody.plant.MultibodyPlant_[Expression]) numpy.ndarray[numpy.float64[m, 1]]
Upper limit analog of GetVelocitysLowerLimits(), where any unbounded or unspecified limits will be +infinity.
See also
GetVelocityLowerLimits() for more information.
- GetVisualGeometriesForBody(self: pydrake.multibody.plant.MultibodyPlant_[Expression], body: pydrake.multibody.tree.RigidBody_[Expression]) list[pydrake.geometry.GeometryId]
Returns an array of GeometryId’s identifying the different visual geometries for
body
previously registered with a SceneGraph.Note
This method can be called at any time during the lifetime of
this
plant, either pre- or post-finalize, see Finalize(). Post-finalize calls will always return the same value.See also
RegisterVisualGeometry(), Finalize()
- gravity_field(self: pydrake.multibody.plant.MultibodyPlant_[Expression]) pydrake.multibody.tree.UniformGravityFieldElement_[Expression]
An accessor to the current gravity field.
- has_joint(self: pydrake.multibody.plant.MultibodyPlant_[Expression], joint_index: pydrake.multibody.tree.JointIndex) bool
Returns true if plant has a joint with unique index
joint_index
. The value could be false if the joint was removed using RemoveJoint().
- has_joint_actuator(self: pydrake.multibody.plant.MultibodyPlant_[Expression], actuator_index: pydrake.multibody.tree.JointActuatorIndex) bool
Returns true if plant has a joint actuator with unique index
actuator_index
. The value could be false if the actuator was removed using RemoveJointActuator().
- has_sampled_output_ports(self: pydrake.multibody.plant.MultibodyPlant_[Expression]) bool
(Advanced) If
this
plant is continuous (i.e., is_discrete() isFalse
), returns false. Ifthis
plant is discrete, returns whether or not the output ports are sampled (change only at a time step boundary) or live (instantaneously reflect changes to the input ports). See output_port_sampling “Output port sampling” for details.
- HasBodyNamed(*args, **kwargs)
Overloaded function.
HasBodyNamed(self: pydrake.multibody.plant.MultibodyPlant_[Expression], name: str) -> bool
- Returns
True
if a body namedname
was added to the MultibodyPlant.
See also
AddRigidBody().
- Raises
RuntimeError if the body name occurs in multiple model instances. –
HasBodyNamed(self: pydrake.multibody.plant.MultibodyPlant_[Expression], name: str, model_instance: pydrake.multibody.tree.ModelInstanceIndex) -> bool
- Returns
True
if a body namedname
was added to the MultibodyPlant inmodel_instance
.
See also
AddRigidBody().
- Raises
RuntimeError if model_instance is not valid for this model. –
- HasFrameNamed(*args, **kwargs)
Overloaded function.
HasFrameNamed(self: pydrake.multibody.plant.MultibodyPlant_[Expression], name: str) -> bool
- Returns
True
if a frame namedname
was added to the model.
See also
AddFrame().
- Raises
RuntimeError if the frame name occurs in multiple model instances. –
HasFrameNamed(self: pydrake.multibody.plant.MultibodyPlant_[Expression], name: str, model_instance: pydrake.multibody.tree.ModelInstanceIndex) -> bool
- Returns
True
if a frame namedname
was added tomodel_instance
.
See also
AddFrame().
- Raises
RuntimeError if model_instance is not valid for this model. –
- HasJointActuatorNamed(*args, **kwargs)
Overloaded function.
HasJointActuatorNamed(self: pydrake.multibody.plant.MultibodyPlant_[Expression], name: str) -> bool
- Returns
True
if an actuator namedname
was added to this model.
See also
AddJointActuator().
- Raises
RuntimeError if the actuator name occurs in multiple model –
instances. –
HasJointActuatorNamed(self: pydrake.multibody.plant.MultibodyPlant_[Expression], name: str, model_instance: pydrake.multibody.tree.ModelInstanceIndex) -> bool
- Returns
True
if an actuator namedname
was added tomodel_instance
.
See also
AddJointActuator().
- Raises
RuntimeError if model_instance is not valid for this model. –
- HasJointNamed(*args, **kwargs)
Overloaded function.
HasJointNamed(self: pydrake.multibody.plant.MultibodyPlant_[Expression], name: str) -> bool
- Returns
True
if a joint namedname
was added to this model.
See also
AddJoint().
- Raises
RuntimeError if the joint name occurs in multiple model instances. –
HasJointNamed(self: pydrake.multibody.plant.MultibodyPlant_[Expression], name: str, model_instance: pydrake.multibody.tree.ModelInstanceIndex) -> bool
- Returns
True
if a joint namedname
was added tomodel_instance
.
See also
AddJoint().
- Raises
RuntimeError if model_instance is not valid for this model. –
- HasModelInstanceNamed(self: pydrake.multibody.plant.MultibodyPlant_[Expression], name: str) bool
- Returns
True
if a model instance namedname
was added to this model.
See also
AddModelInstance().
- HasUniqueFreeBaseBody(self: pydrake.multibody.plant.MultibodyPlant_[Expression], model_instance: pydrake.multibody.tree.ModelInstanceIndex) bool
Return true if there exists a unique base body in the model given by
model_instance
and that unique base body is free.- Raises
RuntimeError if called pre-finalize. –
RuntimeError if model_instance is not valid. –
- is_finalized(self: pydrake.multibody.plant.MultibodyPlant_[Expression]) bool
Returns
True
if this MultibodyPlant was finalized with a call to Finalize().See also
Finalize().
- is_gravity_enabled(self: pydrake.multibody.plant.MultibodyPlant_[Expression], model_instance: pydrake.multibody.tree.ModelInstanceIndex) bool
- Returns
True
iff gravity is enabled formodel_instance
.
See also
set_gravity_enabled().
- Raises
RuntimeError if the model instance is invalid. –
- IsAnchored(self: pydrake.multibody.plant.MultibodyPlant_[Expression], body: pydrake.multibody.tree.RigidBody_[Expression]) bool
Returns
True
ifbody
is anchored (i.e. the kinematic path betweenbody
and the world only contains weld joints.)- Raises
RuntimeError if called pre-finalize. –
- IsVelocityEqualToQDot(self: pydrake.multibody.plant.MultibodyPlant_[Expression]) bool
Returns true iff the generalized velocity v is exactly the time derivative q̇ of the generalized coordinates q. In this case MapQDotToVelocity() and MapVelocityToQDot() implement the identity map. This method is, in the worst case, O(n), where n is the number of joints.
- MakeActuationMatrix(self: pydrake.multibody.plant.MultibodyPlant_[Expression]) numpy.ndarray[object[m, n]]
This method creates an actuation matrix B mapping a vector of actuation values u into generalized forces
tau_u = B * u
, where B is a matrix of sizenv x nu
withnu
equal to num_actuated_dofs() andnv
equal to num_velocities(). The vector u of actuation values is of size num_actuated_dofs(). For a given JointActuator,u[JointActuator::input_start()]
stores the value for the external actuation corresponding to that actuator.tau_u
on the other hand is indexed by generalized velocity indices according toJoint::velocity_start()
.Warning
B is a permutation matrix. While making a permutation has
O(n)
complexity, making a full B matrix hasO(n²)
complexity. For most applications this cost can be neglected but it could become significant for very large systems.
- MakeActuationMatrixPseudoinverse(self: pydrake.multibody.plant.MultibodyPlant_[Expression]) scipy.sparse.csc_matrix[numpy.float64]
Creates the pseudoinverse of the actuation matrix B directly (without requiring an explicit inverse calculation). See MakeActuationMatrix().
Notably, when B is full row rank (the system is fully actuated), then the pseudoinverse is a true inverse.
- MakeActuatorSelectorMatrix(*args, **kwargs)
Overloaded function.
MakeActuatorSelectorMatrix(self: pydrake.multibody.plant.MultibodyPlant_[Expression], user_to_actuator_index_map: list[pydrake.multibody.tree.JointActuatorIndex]) -> numpy.ndarray[numpy.float64[m, n]]
This method allows user to map a vector
uₛ
containing the actuation for a set of selected actuators into the vector u containing the actuation values forthis
full model. The mapping, or selection, is returned in the form of a selector matrix Su such thatu = Su⋅uₛ
. The size nₛ of uₛ is always smaller or equal than the size of the full vector of actuation values u. That is, a user might be interested in only a given subset of actuators in the model.This selection matrix is particularly useful when adding PID control on a portion of the state, see systems::controllers::PidController.
A user specifies the preferred order in uₛ via
user_to_actuator_index_map
. The actuation values in uₛ are a concatenation of the values for each actuator in the order they appear inuser_to_actuator_index_map
. The actuation value in the full vector of actuation valuesu
for a particular actuator can be found at offset JointActuator::input_start().MakeActuatorSelectorMatrix(self: pydrake.multibody.plant.MultibodyPlant_[Expression], user_to_joint_index_map: list[pydrake.multibody.tree.JointIndex]) -> numpy.ndarray[numpy.float64[m, n]]
Alternative signature to build an actuation selector matrix
Su
such thatu = Su⋅uₛ
, where u is the vector of actuation values for the full model (see get_actuation_input_port()) and uₛ is a vector of actuation values for the actuators acting on the joints listed byuser_to_joint_index_map
. It is assumed that all joints referenced byuser_to_joint_index_map
are actuated. See MakeActuatorSelectorMatrix(const std::vector<JointActuatorIndex>&) for details.- Raises
RuntimeError if any of the joints in user_to_joint_index_map –
does not have an actuator. –
- MakeStateSelectorMatrix(self: pydrake.multibody.plant.MultibodyPlant_[Expression], user_to_joint_index_map: list[pydrake.multibody.tree.JointIndex]) numpy.ndarray[numpy.float64[m, n]]
This method allows users to map the state of
this
model, x, into a vector of selected state xₛ with a given preferred ordering. The mapping, or selection, is returned in the form of a selector matrix Sx such thatxₛ = Sx⋅x
. The size nₛ of xₛ is always smaller or equal than the size of the full state x. That is, a user might be interested in only a given portion of the full state x.This selection matrix is particularly useful when adding PID control on a portion of the state, see systems::controllers::PidController.
A user specifies the preferred order in xₛ via
user_to_joint_index_map
. The selected state is built such that selected positions are followed by selected velocities, as inxₛ = [qₛ, vₛ]
. The positions in qₛ are a concatenation of the positions for each joint in the order they appear inuser_to_joint_index_map
. That is, the positions foruser_to_joint_index_map[0]
are first, followed by the positions foruser_to_joint_index_map[1]
, etc. Similarly for the selected velocities vₛ.- Raises
RuntimeError if there are repeated indices in –
user_to_joint_index_map` –
- MapQDotToVelocity(self: pydrake.multibody.plant.MultibodyPlant_[Expression], context: pydrake.systems.framework.Context_[Expression], qdot: numpy.ndarray[object[m, 1]]) numpy.ndarray[object[m, 1]]
Transforms the time derivative
qdot
of the generalized positions vectorq
(stored incontext
) to generalized velocitiesv
. v andq̇
are related linearly byq̇ = N(q)⋅v
. AlthoughN(q)
is not necessarily square, its left pseudo-inverseN⁺(q)
can be used to invert that relationship without residual error, provided thatqdot
is in the range space ofN(q)
(that is, if it could have been produced asq̇ = N(q)⋅v
for somev
). Using the configurationq
stored in the givencontext
this method calculatesv = N⁺(q)⋅q̇
.- Parameter
context
: The context containing the state of the model.
- Parameter
qdot
: A vector containing the time derivatives of the generalized positions. This method aborts if
qdot
is not of size num_positions().- Parameter
v
: A valid (non-null) pointer to a vector in
ℛⁿ
with n the number of generalized velocities. This method aborts if v is nullptr or if it is not of size num_velocities().
See also
MapVelocityToQDot()
See also
Mobilizer::MapQDotToVelocity()
- Parameter
- MapVelocityToQDot(self: pydrake.multibody.plant.MultibodyPlant_[Expression], context: pydrake.systems.framework.Context_[Expression], v: numpy.ndarray[object[m, 1]]) numpy.ndarray[object[m, 1]]
Transforms generalized velocities v to time derivatives
qdot
of the generalized positions vectorq
(stored incontext
). v andqdot
are related linearly byq̇ = N(q)⋅v
. Using the configurationq
stored in the givencontext
this method calculatesq̇ = N(q)⋅v
.- Parameter
context
: The context containing the state of the model.
- Parameter
v
: A vector of generalized velocities for this model. This method aborts if v is not of size num_velocities().
- Parameter
qdot
: A valid (non-null) pointer to a vector in
ℝⁿ
with n being the number of generalized positions in this model, given bynum_positions()
. This method aborts ifqdot
is nullptr or if it is not of size num_positions().
See also
MapQDotToVelocity()
See also
Mobilizer::MapVelocityToQDot()
- Parameter
- mutable_deformable_model(self: pydrake.multibody.plant.MultibodyPlant_[Expression]) drake::multibody::DeformableModel<drake::symbolic::Expression>
Returns a mutable reference to the DeformableModel owned by this plant.
- Raises
RuntimeError if the plant is finalized. –
Warning
This feature is considered to be experimental and may change or be removed at any time, without any deprecation notice ahead of time.
- mutable_gravity_field(self: pydrake.multibody.plant.MultibodyPlant_[Expression]) pydrake.multibody.tree.UniformGravityFieldElement_[Expression]
A mutable accessor to the current gravity field.
- num_actuated_dofs(*args, **kwargs)
Overloaded function.
num_actuated_dofs(self: pydrake.multibody.plant.MultibodyPlant_[Expression]) -> int
Returns the total number of actuated degrees of freedom. That is, the vector of actuation values u has this size. See AddJointActuator().
num_actuated_dofs(self: pydrake.multibody.plant.MultibodyPlant_[Expression], model_instance: pydrake.multibody.tree.ModelInstanceIndex) -> int
Returns the total number of actuated degrees of freedom for a specific model instance. That is, the vector of actuation values u has this size. See AddJointActuator().
- Raises
RuntimeError if called pre-finalize. –
- num_actuators(*args, **kwargs)
Overloaded function.
num_actuators(self: pydrake.multibody.plant.MultibodyPlant_[Expression]) -> int
Returns the number of joint actuators in the model.
See also
AddJointActuator().
num_actuators(self: pydrake.multibody.plant.MultibodyPlant_[Expression], model_instance: pydrake.multibody.tree.ModelInstanceIndex) -> int
Returns the number of actuators for a specific model instance.
- Raises
RuntimeError if called pre-finalize. –
- num_bodies(self: pydrake.multibody.plant.MultibodyPlant_[Expression]) int
Returns the number of RigidBody elements in the model, including the “world” RigidBody, which is always part of the model.
See also
AddRigidBody().
- num_collision_geometries(self: pydrake.multibody.plant.MultibodyPlant_[Expression]) int
Returns the number of geometries registered for contact modeling. This method can be called at any time during the lifetime of
this
plant, either pre- or post-finalize, see Finalize(). Post-finalize calls will always return the same value.
- num_constraints(self: pydrake.multibody.plant.MultibodyPlant_[Expression]) int
Returns the total number of constraints specified by the user.
- num_force_elements(self: pydrake.multibody.plant.MultibodyPlant_[Expression]) int
Returns the number of ForceElement objects.
See also
AddForceElement().
- num_frames(self: pydrake.multibody.plant.MultibodyPlant_[Expression]) int
Returns the number of Frame objects in this model. Frames include body frames associated with each of the bodies, including the world body. This means the minimum number of frames is one.
- num_joints(self: pydrake.multibody.plant.MultibodyPlant_[Expression]) int
Returns the number of joints in the model.
See also
AddJoint().
- num_model_instances(self: pydrake.multibody.plant.MultibodyPlant_[Expression]) int
Returns the number of model instances in the model.
See also
AddModelInstance().
- num_multibody_states(*args, **kwargs)
Overloaded function.
num_multibody_states(self: pydrake.multibody.plant.MultibodyPlant_[Expression]) -> int
Returns the size of the multibody system state vector x = [q v]. This will be
num_positions()
plusnum_velocities()
.- Raises
RuntimeError if called pre-finalize. –
num_multibody_states(self: pydrake.multibody.plant.MultibodyPlant_[Expression], model_instance: pydrake.multibody.tree.ModelInstanceIndex) -> int
Returns the size of the multibody system state vector xᵢ = [qᵢ vᵢ] for model instance i. (Here qᵢ ⊆ q and vᵢ ⊆ v.) will be
num_positions(model_instance)
plusnum_velocities(model_instance)
.- Raises
RuntimeError if called pre-finalize. –
- num_positions(*args, **kwargs)
Overloaded function.
num_positions(self: pydrake.multibody.plant.MultibodyPlant_[Expression]) -> int
Returns the size of the generalized position vector q for this model.
- Raises
RuntimeError if called pre-finalize. –
num_positions(self: pydrake.multibody.plant.MultibodyPlant_[Expression], model_instance: pydrake.multibody.tree.ModelInstanceIndex) -> int
Returns the size of the generalized position vector qᵢ for model instance i.
- Raises
RuntimeError if called pre-finalize. –
- num_velocities(*args, **kwargs)
Overloaded function.
num_velocities(self: pydrake.multibody.plant.MultibodyPlant_[Expression]) -> int
Returns the size of the generalized velocity vector v for this model.
- Raises
RuntimeError if called pre-finalize. –
num_velocities(self: pydrake.multibody.plant.MultibodyPlant_[Expression], model_instance: pydrake.multibody.tree.ModelInstanceIndex) -> int
Returns the size of the generalized velocity vector vᵢ for model instance i.
- Raises
RuntimeError if called pre-finalize. –
- NumBodiesWithName(self: pydrake.multibody.plant.MultibodyPlant_[Expression], name: str) int
- Returns
The total number of bodies (across all model instances) with the given name.
- RegisterAsSourceForSceneGraph(self: pydrake.multibody.plant.MultibodyPlant_[Expression], scene_graph: pydrake.geometry.SceneGraph_[Expression]) pydrake.geometry.SourceId
Registers
this
plant to serve as a source for an instance of SceneGraph. This registration allows MultibodyPlant to register geometry withscene_graph
for visualization and/or collision queries. The string returned bythis->get_name()
is passed to SceneGraph’s RegisterSource, so it is highly recommended that you give the plant a recognizable name before calling this. Successive registration calls with SceneGraph must be performed on the same instance to which the pointer argumentscene_graph
points to. Failure to do so will result in runtime exceptions.- Parameter
scene_graph
: A valid non nullptr to the SceneGraph instance for which
this
plant will sever as a source, see SceneGraph documentation for further details.
- Returns
the SourceId of
this
plant inscene_graph
. It can also later on be retrieved with get_source_id().- Raises
RuntimeError if called post-finalize. –
RuntimeError if scene_graph is the nullptr. –
RuntimeError if called more than once. –
- Parameter
- RegisterCollisionGeometry(*args, **kwargs)
Overloaded function.
RegisterCollisionGeometry(self: pydrake.multibody.plant.MultibodyPlant_[Expression], body: pydrake.multibody.tree.RigidBody_[Expression], X_BG: pydrake.math.RigidTransform, shape: pydrake.geometry.Shape, name: str, properties: pydrake.geometry.ProximityProperties) -> pydrake.geometry.GeometryId
Registers geometry in a SceneGraph with a given geometry::Shape to be used for the contact modeling of a given
body
. More than one geometry can be registered with a body, in which case the body’s contact geometry is the union of all geometries registered to that body.- Parameter
body
: The body for which geometry is being registered.
- Parameter
X_BG
: The fixed pose of the geometry frame G in the body frame B.
- Parameter
shape
: The geometry::Shape used for visualization. E.g.: geometry::Sphere, geometry::Cylinder, etc.
- Parameter
properties
: The proximity properties associated with the collision geometry. They must include the (
material
, coulomb_friction) property of type CoulombFriction<double>.
- Raises
RuntimeError if called post-finalize or if the properties are –
missing the coulomb friction property (or if it is of the wrong –
type) –
RegisterCollisionGeometry(self: pydrake.multibody.plant.MultibodyPlant_[Expression], body: pydrake.multibody.tree.RigidBody_[Expression], X_BG: pydrake.math.RigidTransform, shape: pydrake.geometry.Shape, name: str, coulomb_friction: pydrake.multibody.plant.CoulombFriction) -> pydrake.geometry.GeometryId
Overload which specifies a single property: coulomb_friction.
- RegisterVisualGeometry(*args, **kwargs)
Overloaded function.
RegisterVisualGeometry(self: pydrake.multibody.plant.MultibodyPlant_[Expression], body: pydrake.multibody.tree.RigidBody_[Expression], X_BG: pydrake.math.RigidTransform, shape: pydrake.geometry.Shape, name: str, diffuse_color: numpy.ndarray[numpy.float64[4, 1]]) -> pydrake.geometry.GeometryId
Overload for visual geometry registration. The following properties are set: - (“phong”, “diffuse”) =
diffuse_color
in both sets of properties. - (“label”, “id”) in perception properties as documented above.See mbp_geometry “the overview” for more details.
RegisterVisualGeometry(self: pydrake.multibody.plant.MultibodyPlant_[Expression], body: pydrake.multibody.tree.RigidBody_[Expression], geometry_instance: pydrake.geometry.GeometryInstance) -> pydrake.geometry.GeometryId
Registers the given
geometry_instance
in a SceneGraph to be used for visualization of a givenbody
.The roles that
geometry_instance
gets assigned (illustration/perception) in SceneGraph depend solely on the properties that have already been assigned togeometry_instance
. If any visual roles have been assigned, those will be the only roles used. If no visual roles have been assigned, then both roles will be assigned using the default set of property values.If the registered geometry has the perception role, it will have the (“label”, “id”) property. Possibly assigned as documented above.
See mbp_geometry “the overview” for more details.
- Parameter
body
: The body for which geometry is being registered.
- Parameter
geometry_instance
: The geometry to associate with the visual appearance of
body
.
- Raises
RuntimeError if geometry_instance is null. –
RuntimeError if called post-finalize. –
- Returns
the id for the registered geometry.
- RemoveConstraint(self: pydrake.multibody.plant.MultibodyPlant_[Expression], id: pydrake.multibody.tree.MultibodyConstraintId) None
Removes the constraint
id
from the plant. Note that this will not remove constraints registered directly with DeformableModel.- Raises
RuntimeError if the MultibodyPlant has already been finalized. –
RuntimeError if id does not identify any multibody constraint –
in this plant. –
- RemoveJoint(self: pydrake.multibody.plant.MultibodyPlant_[Expression], joint: pydrake.multibody.tree.Joint_[Expression]) None
Removes and deletes
joint
from this MultibodyPlant. Any existing references tojoint
will become invalid, and future calls toget_joint(joint_index)
will throw an exception. Other elements of the plant may depend onjoint
at the time of removal and should be removed first. For example, a JointActuator that depends onjoint
should be removed with RemoveJointActuator(). Currently, we do not provide joint dependency tracking for force elements or constraints, so this function will throw an exception if there are any user-added force elements or constraints in the plant.- Raises
RuntimeError if the plant is already finalized. –
RuntimeError if the plant contains a non-zero number of user-added –
force elements or user-added constraints. –
RuntimeError if joint has a dependent JointActuator. –
See also
AddJoint()
Note
It is important to note that the JointIndex assigned to a joint is immutable. New joint indices are assigned in increasing order, even if a joint with a lower index has been removed. This has the consequence that when a joint is removed from the plant, the sequence
[0, num_joints())
is not necessarily the correct set of un-removed joint indices in the plant. Thus, it is important NOT to loop over joint indices sequentially from0
tonum_joints() - 1
. Instead users should use the provided GetJointIndices() and GetJointIndices(ModelIndex) functions:Click to expand C++ code...
for (JointIndex index : plant.GetJointIndices()) { const Joint<double>& joint = plant.get_joint(index); ... }
- RemoveJointActuator(self: pydrake.multibody.plant.MultibodyPlant_[Expression], actuator: pydrake.multibody.tree.JointActuator_[Expression]) None
Removes and deletes
actuator
from this MultibodyPlant. Any existing references toactuator
will become invalid, and future calls toget_joint_actuator(actuator_index)
will throw an exception.- Raises
RuntimeError if the plant is already finalized. –
See also
AddJointActuator()
- RenameModelInstance(self: pydrake.multibody.plant.MultibodyPlant_[Expression], model_instance: pydrake.multibody.tree.ModelInstanceIndex, name: str) None
Renames an existing model instance.
- Parameter
model_instance
: The instance to rename.
- Parameter
name
: A string that uniquely identifies the instance within
this
model.
- Raises
RuntimeError if called after Finalize() –
RuntimeError if model_instance is not a valid index. –
RuntimeError if HasModelInstanceNamed(name) is true. –
- Parameter
- set_adjacent_bodies_collision_filters(self: pydrake.multibody.plant.MultibodyPlant_[Expression], value: bool) None
Sets whether to apply collision filters to topologically adjacent bodies at Finalize() time. Filters are applied when there exists a joint between bodies, except in the case of 6-dof joints or joints in which the parent body is
world
.- Raises
RuntimeError iff called post-finalize. –
- set_contact_model(self: pydrake.multibody.plant.MultibodyPlant_[Expression], model: pydrake.multibody.plant.ContactModel) None
Sets the contact model to be used by
this
MultibodyPlant, see ContactModel for available options. The default contact model is ContactModel::kHydroelasticWithFallback.- Raises
RuntimeError iff called post-finalize. –
- set_contact_surface_representation(self: pydrake.multibody.plant.MultibodyPlant_[Expression], surface_representation: pydrake.geometry.HydroelasticContactRepresentation) None
Sets the representation of contact surfaces to be used by
this
MultibodyPlant. See geometry::HydroelasticContactRepresentation for available options. See GetDefaultContactSurfaceRepresentation() for explanation of default values.- Raises
RuntimeError if called post-finalize. –
- set_discrete_contact_approximation(self: pydrake.multibody.plant.MultibodyPlant_[Expression], approximation: pydrake.multibody.plant.DiscreteContactApproximation) None
Sets the discrete contact model approximation.
Note
Calling this method also sets the contact solver type (see set_discrete_contact_solver()) according to: - DiscreteContactApproximation::kTamsi sets the solver to DiscreteContactSolver::kTamsi. - DiscreteContactApproximation::kSap, DiscreteContactApproximation::kSimilar and DiscreteContactApproximation::kLagged set the solver to DiscreteContactSolver::kSap.
- Raises
iff this plant is continuous (i.e. is_discrete() is –
False`. –
RuntimeError iff called post-finalize. –
- set_discrete_contact_solver(self: pydrake.multibody.plant.MultibodyPlant_[Expression], contact_solver: pydrake.multibody.plant.DiscreteContactSolver) None
Sets the contact solver type used for discrete MultibodyPlant models.
Note
Calling this method also sets a default discrete approximation of contact (see set_discrete_contact_approximation()) according to: - DiscreteContactSolver::kTamsi sets the approximation to DiscreteContactApproximation::kTamsi. - DiscreteContactSolver::kSap sets the approximation to DiscreteContactApproximation::kSap.
Warning
This function is a no-op for continuous models (when is_discrete() is false.)
- Raises
RuntimeError iff called post-finalize. (Deprecated.) –
- Deprecated:
Use set_discrete_contact_approximation() to set the contact model approximation. The underlying solver will be inferred automatically. This will be removed from Drake on or after 2024-04-01.
- set_gravity_enabled(self: pydrake.multibody.plant.MultibodyPlant_[Expression], model_instance: pydrake.multibody.tree.ModelInstanceIndex, is_enabled: bool) None
Sets is_gravity_enabled() for
model_instance
tois_enabled
. The effect ofis_enabled = false
is effectively equivalent to disabling (or making zero) gravity for all bodies in the specified model instance. By default is_gravity_enabled() equalsTrue
for all model instances.- Raises
RuntimeError if called post-finalize. –
RuntimeError if the model instance is invalid. –
- set_penetration_allowance(self: pydrake.multibody.plant.MultibodyPlant_[Expression], penetration_allowance: float = 0.001) None
Sets the penetration allowance used to estimate the coefficients in the penalty method used to impose non-penetration among bodies. Refer to the section point_contact_defaults “Point Contact Default Parameters” for further details.
- Raises
RuntimeError if penetration_allowance is not positive. –
- set_sap_near_rigid_threshold(self: pydrake.multibody.plant.MultibodyPlant_[Expression], near_rigid_threshold: float = 1.0) None
Non-negative dimensionless number typically in the range [0.0, 1.0], though larger values are allowed even if uncommon. This parameter controls the “near rigid” regime of the SAP solver, β in section V.B of [Castro et al., 2021]. It essentially controls a threshold value for the maximum amount of stiffness SAP can handle robustly. Beyond this value, stiffness saturates as explained in [Castro et al., 2021]. A value of 1.0 is a conservative choice to avoid ill-conditioning that might lead to softer than expected contact. If this is your case, consider turning off this approximation by setting this parameter to zero. For difficult cases where ill-conditioning is a problem, a small but non-zero number can be used, e.g. 1.0e-3.
- Raises
RuntimeError if near_rigid_threshold is negative. –
RuntimeError if called post-finalize. –
- set_stiction_tolerance(self: pydrake.multibody.plant.MultibodyPlant_[Expression], v_stiction: float = 0.001) None
**** Stribeck model of friction
Currently MultibodyPlant uses the Stribeck approximation to model dry friction. The Stribeck model of friction is an approximation to Coulomb’s law of friction that allows using continuous time integration without the need to specify complementarity constraints. While this results in a simpler model immediately tractable with standard numerical methods for integration of ODE’s, it often leads to stiff dynamics that require an explicit integrator to take very small time steps. It is therefore recommended to use error controlled integrators when using this model or the discrete time stepping (see multibody_simulation). See stribeck_approximation for a detailed discussion of the Stribeck model.
Sets the stiction tolerance
v_stiction
for the Stribeck model, wherev_stiction
must be specified in m/s (meters per second.)v_stiction
defaults to a value of 1 millimeter per second. In selecting a value forv_stiction
, you must ask yourself the question, “When two objects are ostensibly in stiction, how much slip am I willing to allow?” There are two opposing design issues in picking a value for vₛ. On the one hand, small values of vₛ make the problem numerically stiff during stiction, potentially increasing the integration cost. On the other hand, it should be picked to be appropriate for the scale of the problem. For example, a car simulation could allow a “large” value for vₛ of 1 cm/s (1×10⁻² m/s), but reasonable stiction for grasping a 10 cm box might require limiting residual slip to 1×10⁻³ m/s or less. Ultimately, picking the largest viable value will allow your simulation to run faster and more robustly. Note thatv_stiction
is the slip velocity that we’d have when we are at edge of the friction cone. For cases when the friction force is well within the friction cone the slip velocity will always be smaller than this value. See also stribeck_approximation.- Raises
RuntimeError if v_stiction is non-positive. –
- SetActuationInArray(self: pydrake.multibody.plant.MultibodyPlant_[Expression], model_instance: pydrake.multibody.tree.ModelInstanceIndex, u_instance: numpy.ndarray[object[m, 1]], u: Optional[numpy.ndarray[object[m, 1], flags.writeable]]) None
Given actuation values
u_instance
for the actuators inmodel_instance
, this function updates the actuation vector u for the entire plant model to which this actuator belongs to. Refer to mbp_actuation “Actuation” for further details.- Parameter
u_instance
: Actuation values for the model instance. Values are ordered by monotonically increasing JointActuatorIndex within the model instance.
- Parameter
u
: Actuation values for the entire plant model. The actuation value in
u
for a particular actuator must be found at offset JointActuator::input_start(). Only values corresponding tomodel_instance
are changed.
- Raises
RuntimeError if the size of u_instance is not equal to the –
number of actuation inputs for the joints of model_instance. –
- Parameter
- SetConstraintActiveStatus(self: pydrake.multibody.plant.MultibodyPlant_[Expression], context: pydrake.systems.framework.Context_[Expression], id: pydrake.multibody.tree.MultibodyConstraintId, status: bool) None
Sets the active status of the constraint given by
id
incontext
.- Raises
RuntimeError if the MultibodyPlant has not been finalized. –
RuntimeError if context == nullptr –
RuntimeError if id does not belong to any multibody constraint –
in context. –
- SetDefaultFreeBodyPose(*args, **kwargs)
Overloaded function.
SetDefaultFreeBodyPose(self: pydrake.multibody.plant.MultibodyPlant_[Expression], body: pydrake.multibody.tree.RigidBody_[Expression], X_PB: pydrake.math.RigidTransform) -> None
Sets the default pose of
body
. Ifbody.is_floating()
is true, this will affect subsequent calls to SetDefaultState(); otherwise, the only effect of the call is that the value will be echoed back in GetDefaultFreeBodyPose().Note
The parent frame is not necessarily the world frame. See mbp_working_with_free_bodies “above for details”.
- Parameter
body
: RigidBody whose default pose will be set.
- Parameter
X_PB
: Default pose of the body.
SetDefaultFreeBodyPose(self: pydrake.multibody.plant.MultibodyPlant_[Expression], body: pydrake.multibody.tree.RigidBody_[Expression], X_WB: pydrake.math.RigidTransform) -> None
Sets
context
to store the poseX_PB
of a givenbody
B in the parent frame P.Note
The parent frame is not necessarily the world frame. See mbp_working_with_free_bodies “above for details”.
- Raises
RuntimeError if body is not a free body in the model. –
RuntimeError if called pre-finalize. –
- SetDefaultPositions(*args, **kwargs)
Overloaded function.
SetDefaultPositions(self: pydrake.multibody.plant.MultibodyPlant_[Expression], q: numpy.ndarray[numpy.float64[m, 1]]) -> None
Sets the default positions for the plant. Calls to CreateDefaultContext or SetDefaultContext/SetDefaultState will return a Context populated with these position values. They have no other effects on the dynamics of the system.
- Raises
RuntimeError if the plant is not finalized or if q is not of size –
num_positions() –
SetDefaultPositions(self: pydrake.multibody.plant.MultibodyPlant_[Expression], model_instance: pydrake.multibody.tree.ModelInstanceIndex, q_instance: numpy.ndarray[numpy.float64[m, 1]]) -> None
Sets the default positions for the model instance. Calls to CreateDefaultContext or SetDefaultContext/SetDefaultState will return a Context populated with these position values. They have no other effects on the dynamics of the system.
- Raises
RuntimeError if the plant is not finalized, if the model_instance –
is invalid, or if the length of q_instance is not equal to –
num_positions(model_instance)` –
- SetDefaultState(self: pydrake.multibody.plant.MultibodyPlant_[Expression], context: pydrake.systems.framework.Context_[Expression], state: pydrake.systems.framework.State_[Expression]) None
Sets
state
according to defaults set by the user for joints (e.g. RevoluteJoint::set_default_angle()) and free bodies (SetDefaultFreeBodyPose()). If the user does not specify defaults, the state corresponds to zero generalized positions and velocities.- Raises
RuntimeError if called pre-finalize. See Finalize() –
- SetFreeBodyPose(*args, **kwargs)
Overloaded function.
SetFreeBodyPose(self: pydrake.multibody.plant.MultibodyPlant_[Expression], context: pydrake.systems.framework.Context_[Expression], body: pydrake.multibody.tree.RigidBody_[Expression], X_PB: pydrake.math.RigidTransform_[Expression]) -> None
Sets
context
to store the poseX_PB
of a givenbody
B in the parent frame P.Note
The parent frame is not necessarily the world frame. See mbp_working_with_free_bodies “above for details”.
- Raises
RuntimeError if body is not a free body in the model. –
RuntimeError if called pre-finalize. –
SetFreeBodyPose(self: pydrake.multibody.plant.MultibodyPlant_[Expression], context: pydrake.systems.framework.Context_[Expression], body: pydrake.multibody.tree.RigidBody_[Expression], X_WB: pydrake.math.RigidTransform_[Expression]) -> None
Sets
context
to store the poseX_PB
of a givenbody
B in the parent frame P.Note
The parent frame is not necessarily the world frame. See mbp_working_with_free_bodies “above for details”.
- Raises
RuntimeError if body is not a free body in the model. –
RuntimeError if called pre-finalize. –
- SetFreeBodySpatialVelocity(*args, **kwargs)
Overloaded function.
SetFreeBodySpatialVelocity(self: pydrake.multibody.plant.MultibodyPlant_[Expression], body: pydrake.multibody.tree.RigidBody_[Expression], V_PB: pydrake.multibody.math.SpatialVelocity_[Expression], context: pydrake.systems.framework.Context_[Expression]) -> None
Sets
context
to store the spatial velocityV_PB
of a givenbody
B in its parent frame P.Note
The parent frame is not necessarily the world frame. See mbp_working_with_free_bodies “above for details”.
- Raises
RuntimeError if body is not a free body in the model. –
RuntimeError if called pre-finalize. –
SetFreeBodySpatialVelocity(self: pydrake.multibody.plant.MultibodyPlant_[Expression], body: pydrake.multibody.tree.RigidBody_[Expression], V_WB: pydrake.multibody.math.SpatialVelocity_[Expression], context: pydrake.systems.framework.Context_[Expression]) -> None
Sets
context
to store the spatial velocityV_PB
of a givenbody
B in its parent frame P.Note
The parent frame is not necessarily the world frame. See mbp_working_with_free_bodies “above for details”.
- Raises
RuntimeError if body is not a free body in the model. –
RuntimeError if called pre-finalize. –
- SetPositions(*args, **kwargs)
Overloaded function.
SetPositions(self: pydrake.multibody.plant.MultibodyPlant_[Expression], context: pydrake.systems.framework.Context_[Expression], q: numpy.ndarray[object[m, 1]]) -> None
Sets the generalized positions q in a given Context from a given vector. Prefer this method over GetMutablePositions().
- Raises
RuntimeError if context is nullptr, if context does not –
correspond to the Context for a multibody model, or if the length –
of q is not equal to num_positions() –
SetPositions(self: pydrake.multibody.plant.MultibodyPlant_[Expression], context: pydrake.systems.framework.Context_[Expression], model_instance: pydrake.multibody.tree.ModelInstanceIndex, q: numpy.ndarray[object[m, 1]]) -> None
Sets the generalized positions q in a given Context from a given vector. Prefer this method over GetMutablePositions().
- Raises
RuntimeError if context is nullptr, if context does not –
correspond to the Context for a multibody model, or if the length –
of q is not equal to num_positions() –
- SetPositionsAndVelocities(*args, **kwargs)
Overloaded function.
SetPositionsAndVelocities(self: pydrake.multibody.plant.MultibodyPlant_[Expression], context: pydrake.systems.framework.Context_[Expression], q_v: numpy.ndarray[object[m, 1]]) -> None
Sets generalized positions q and generalized velocities v in a given Context from a given vector [q; v]. Prefer this method over GetMutablePositionsAndVelocities().
- Raises
RuntimeError if context is nullptr, if context does not –
correspond to the context for a multibody model, or if the length –
of q_v is not equal to num_positions() + num_velocities() –
SetPositionsAndVelocities(self: pydrake.multibody.plant.MultibodyPlant_[Expression], context: pydrake.systems.framework.Context_[Expression], model_instance: pydrake.multibody.tree.ModelInstanceIndex, q_v: numpy.ndarray[object[m, 1]]) -> None
Sets generalized positions q and generalized velocities v from a given vector [q; v] for a specified model instance in a given Context.
- Raises
RuntimeError if context is nullptr, if context does not –
correspond to the Context for a multibody model, if the model –
instance index is invalid, or if the length of q_v is not –
equal to ``num_positions(model_instance) + –
num_velocities(model_instance)``. –
- SetPositionsInArray(self: pydrake.multibody.plant.MultibodyPlant_[Expression], model_instance: pydrake.multibody.tree.ModelInstanceIndex, q_instance: numpy.ndarray[object[m, 1]], q: Optional[numpy.ndarray[object[m, 1], flags.writeable]]) None
Sets the vector of generalized positions for
model_instance
inq
usingq_instance
, leaving all other elements in the array untouched. This method throws an exception ifq
is not of size MultibodyPlant::num_positions() orq_instance
is not of sizeMultibodyPlant::num_positions(model_instance)
.
- SetUseSampledOutputPorts(self: pydrake.multibody.plant.MultibodyPlant_[Expression], use_sampled_output_ports: bool) None
(Advanced) For a discrete-time plant, configures whether the output ports are sampled (the default) or live (opt-in). See output_port_sampling “Output port sampling” for details.
- Raises
RuntimeError if the plant is already finalized. –
RuntimeError if use_sampled_output_ports is True but –
this` MultibodyPlant is not a discrete model (is_discrete() = –
false) –
- SetVelocities(*args, **kwargs)
Overloaded function.
SetVelocities(self: pydrake.multibody.plant.MultibodyPlant_[Expression], context: pydrake.systems.framework.Context_[Expression], v: numpy.ndarray[object[m, 1]]) -> None
Sets the generalized velocities v in a given Context from a given vector. Prefer this method over GetMutableVelocities().
- Raises
RuntimeError if the context is nullptr, if the context does –
not correspond to the context for a multibody model, or if the –
length of v is not equal to num_velocities() –
SetVelocities(self: pydrake.multibody.plant.MultibodyPlant_[Expression], context: pydrake.systems.framework.Context_[Expression], model_instance: pydrake.multibody.tree.ModelInstanceIndex, v: numpy.ndarray[object[m, 1]]) -> None
Sets the generalized velocities v for a particular model instance in a given Context from a given vector.
- Raises
RuntimeError if the context is nullptr, if context does –
not correspond to the Context for a multibody model, if the model –
instance index is invalid, or if the length of v_instance is –
not equal to num_velocities(model_instance) –
- SetVelocitiesInArray(self: pydrake.multibody.plant.MultibodyPlant_[Expression], model_instance: pydrake.multibody.tree.ModelInstanceIndex, v_instance: numpy.ndarray[object[m, 1]], v: Optional[numpy.ndarray[object[m, 1], flags.writeable]]) None
Sets the vector of generalized velocities for
model_instance
inv
usingv_instance
, leaving all other elements in the array untouched. This method throws an exception ifv
is not of size MultibodyPlant::num_velocities() orv_instance
is not of sizeMultibodyPlant::num_positions(model_instance)
.
- time_step(self: pydrake.multibody.plant.MultibodyPlant_[Expression]) float
The time step (or period) used to model
this
plant as a discrete system with periodic updates. Returns 0 (zero) if the plant is modeled as a continuous system. This property of the plant is specified at construction and therefore this query can be performed either pre- or post-finalize, see Finalize().See also
MultibodyPlant::MultibodyPlant(double)
- WeldFrames(self: pydrake.multibody.plant.MultibodyPlant_[Expression], frame_on_parent_F: pydrake.multibody.tree.Frame_[Expression], frame_on_child_M: pydrake.multibody.tree.Frame_[Expression], X_FM: pydrake.math.RigidTransform = RigidTransform(R=RotationMatrix([[1.0, 0.0, 0.0], [0.0, 1.0, 0.0], [0.0, 0.0, 1.0]]), p=[0.0, 0.0, 0.0])) pydrake.multibody.tree.WeldJoint_[Expression]
Welds
frame_on_parent_F
andframe_on_child_M
with relative poseX_FM
. That is, the pose of frame M in frame F is fixed, with valueX_FM
. IfX_FM
is omitted, the identity transform will be used. The call to this method creates and adds a new WeldJoint to the model. The new WeldJoint is named as: frame_on_parent_F.name() + “_welds_to_” + frame_on_child_M.name().- Returns
a constant reference to the WeldJoint welding frames F and M.
- Raises
RuntimeError if the weld produces a duplicate joint name. –
- world_body(self: pydrake.multibody.plant.MultibodyPlant_[Expression]) pydrake.multibody.tree.RigidBody_[Expression]
Returns a constant reference to the world body.
- world_frame(self: pydrake.multibody.plant.MultibodyPlant_[Expression]) pydrake.multibody.tree.RigidBodyFrame_[Expression]
Returns a constant reference to the world frame.
- class pydrake.multibody.plant.MultibodyPlantConfig
The set of configurable properties on a MultibodyPlant.
The field names and defaults here match MultibodyPlant’s defaults exactly, with the exception of time_step.
- __init__(self: pydrake.multibody.plant.MultibodyPlantConfig, **kwargs) None
- property adjacent_bodies_collision_filters
Configures the MultibodyPlant::set_adjacent_bodies_collision_filters().
- property contact_model
Configures the MultibodyPlant::set_contact_model(). Refer to drake::multibody::ContactModel for details. Valid strings are: - “point” - “hydroelastic” - “hydroelastic_with_fallback”
- property contact_surface_representation
Configures the MultibodyPlant::set_contact_surface_representation(). Refer to drake::geometry::HydroelasticContactRepresentation for details. Valid strings are: - “triangle” - “polygon”
The default value used here is consistent with the default time_step chosen above; keep this consistent with MultibodyPlant::GetDefaultContactSurfaceRepresentation().
- property discrete_contact_approximation
Configures the MultibodyPlant::set_discrete_contact_approximation(). Refer to drake::multibody::DiscreteContactApproximation for details. Valid strings are: - “tamsi” - “sap” - “similar” - “lagged”
Refer to MultibodyPlant::set_discrete_contact_approximation() and the references therein for further details.
Note
If empty, the contact approximation is determined by discrete_contact_solver, see set_discrete_contact_solver(). If both discrete_contact_solver and discrete_contact_approximation are empty, the default model (and solver) is TAMSI.
- property discrete_contact_solver
Configures the MultibodyPlant::set_discrete_contact_solver(). Refer to drake::multibody::DiscreteContactSolver for details. Valid strings are: - “tamsi”, uses the TAMSI model approximation. - “sap” , uses the SAP model approximation.
Note
If empty, the contact solver is determined by discrete_contact_approximation, see MultibodyPlant::set_discrete_contact_approximation(). If both discrete_contact_solver and discrete_contact_approximation are empty, the default model (and solver) is TAMSI.
Warning
discrete_contact_solver is deprecated. Use discrete_contact_approximation to set the contact model approximation. The underlying solver will be inferred automatically. The deprecated code will be removed from Drake on or after 2024-04-01.
- property penetration_allowance
Configures the MultibodyPlant::set_penetration_allowance().
- property sap_near_rigid_threshold
Non-negative dimensionless number typically in the range [0.0, 1.0], though larger values are allowed even if uncommon. This parameter controls the “near rigid” regime of the SAP solver, β in section V.B of [Castro et al., 2021]. It essentially controls a threshold value for the maximum amount of stiffness SAP can handle robustly. Beyond this value, stiffness saturates as explained in [Castro et al., 2021]. A value of 1.0 is a conservative choice to avoid numerical ill-conditioning. However, this might introduce artificial softening of the contact constraints. If this is your case try: 1. Set this parameter to zero. 2. For difficult problems (hundreds of contacts for instance), you might need to use a low value if the solver fails to converge. For instance, set values in the range (1e-3, 1e-2).
- property stiction_tolerance
Configures the MultibodyPlant::set_stiction_tolerance().
- property time_step
Configures the MultibodyPlant::MultibodyPlant() constructor time_step.
There is no default value for this within MultibodyPlant itself, so here we choose a nominal value (a discrete system, with a 1ms periodic update) as a reasonably conservative estimate that works in many cases.
- property use_sampled_output_ports
Configures the MultibodyPlant::SetUseSampledOutputPorts(). Ignored when the time_step is zero.
- class pydrake.multibody.plant.PhysicalModel
(Internal) PhysicalModel provides the functionalities to extend the type of physical model of MultibodyPlant. Developers can derive from this PhysicalModel to incorporate additional model elements coupled with the rigid body dynamics. For instance, simulation of deformable objects requires additional state and ports to interact with externals systems such as visualization.
Similar to the routine of adding multiple model elements in MultibodyPlant, users should add all the model elements they wish to add to a PhysicalModel before the owning MultibodyPlant calls
Finalize()
. WhenFinalize()
is invoked, MultibodyPlant will allocate the system level context resources for each PhysicalModel it owns. After the system resources are allocated, model mutation in the PhysicalModels owned by MultibodyPlant is not allowed.This class is for internal use only. Use derived concrete models (e.g. DeformableModel) instead.
- __init__(*args, **kwargs)
- class pydrake.multibody.plant.PointPairContactInfo
A class containing information regarding contact response between two bodies including:
The pair of bodies that are contacting, referenced by their BodyIndex.
A resultant contact force.
A contact point.
Separation speed.
Slip speed.
Note
This class is templated; see
PointPairContactInfo_
for the list of instantiations.- __init__(self: pydrake.multibody.plant.PointPairContactInfo, bodyA_index: pydrake.multibody.tree.BodyIndex, bodyB_index: pydrake.multibody.tree.BodyIndex, f_Bc_W: numpy.ndarray[numpy.float64[3, 1]], p_WC: numpy.ndarray[numpy.float64[3, 1]], separation_speed: float, slip_speed: float, point_pair: pydrake.geometry.PenetrationAsPointPair) None
Constructs the contact information for a given pair of two colliding bodies.
- Parameter
bodyA_index
: Index that references body A in
this
contact pair.- Parameter
bodyB_index
: Index that references body B in
this
contact pair.- Parameter
f_Bc_W
: Force on body B applied at contact point C, expressed in the world frame W.
- Parameter
p_WC
: Position of the contact point C in the world frame W.
- Parameter
separation_speed
: Separation speed along the normal direction between body A and body B, in meters per second. A positive value indicates bodies are moving apart. A negative value indicates bodies are moving towards each other.
- Parameter
slip_speed
: Slip speed, that is, the magnitude of the relative tangential velocity at the contact point in meters per second. A non-negative value always.
- Parameter
point_pair
: Additional point pair information for
this
contact info. Refer to the documentation for PenetrationAsPointPair for further details. It is expected that the body indexed bybodyA_index
is the same body that contains the geometry indexed bypoint_pair.id_A
. Likewise for the body indexed bybodyB_index
and the body contining geometry with idpoint_pair.id_B
.- Precondition:
The two body indexes must reference bodies from the same MultibodyPlant. Contact values should likewise be generated by the same MultibodyPlant.
- Parameter
- bodyA_index(self: pydrake.multibody.plant.PointPairContactInfo) pydrake.multibody.tree.BodyIndex
Returns the index of body A in the contact pair.
- bodyB_index(self: pydrake.multibody.plant.PointPairContactInfo) pydrake.multibody.tree.BodyIndex
Returns the index of body B in the contact pair.
- contact_force(self: pydrake.multibody.plant.PointPairContactInfo) numpy.ndarray[numpy.float64[3, 1]]
Returns the contact force
f_Bc_W
on B at contact point C expressed in the world frame W.
- contact_point(self: pydrake.multibody.plant.PointPairContactInfo) numpy.ndarray[numpy.float64[3, 1]]
Returns the position
p_WC
of the contact point C in the world frame W.
- point_pair(self: pydrake.multibody.plant.PointPairContactInfo) pydrake.geometry.PenetrationAsPointPair
Returns additional information for the geometric contact query for
this
pair as a PenetrationAsPointPair. The body containingpoint_pair().id_A
is the same body indexed bybodyA_index()
. Likewise, the body containingpoint_pair().id_B
is the same body indexed bybodyB_index()
.
- separation_speed(self: pydrake.multibody.plant.PointPairContactInfo) float
Returns the separation speed between body A and B along the normal direction (see PenetrationAsPointPair::nhat_BA_W) at the contact point. It is defined positive for bodies moving apart in the normal direction.
- slip_speed(self: pydrake.multibody.plant.PointPairContactInfo) float
Returns the slip speed between body A and B at contact point C.
- template pydrake.multibody.plant.PointPairContactInfo_
Instantiations:
PointPairContactInfo_[float]
,PointPairContactInfo_[AutoDiffXd]
,PointPairContactInfo_[Expression]
- class pydrake.multibody.plant.PointPairContactInfo_[AutoDiffXd]
A class containing information regarding contact response between two bodies including:
The pair of bodies that are contacting, referenced by their BodyIndex.
A resultant contact force.
A contact point.
Separation speed.
Slip speed.
- __init__(self: pydrake.multibody.plant.PointPairContactInfo_[AutoDiffXd], bodyA_index: pydrake.multibody.tree.BodyIndex, bodyB_index: pydrake.multibody.tree.BodyIndex, f_Bc_W: numpy.ndarray[object[3, 1]], p_WC: numpy.ndarray[object[3, 1]], separation_speed: pydrake.autodiffutils.AutoDiffXd, slip_speed: pydrake.autodiffutils.AutoDiffXd, point_pair: pydrake.geometry.PenetrationAsPointPair_[AutoDiffXd]) None
Constructs the contact information for a given pair of two colliding bodies.
- Parameter
bodyA_index
: Index that references body A in
this
contact pair.- Parameter
bodyB_index
: Index that references body B in
this
contact pair.- Parameter
f_Bc_W
: Force on body B applied at contact point C, expressed in the world frame W.
- Parameter
p_WC
: Position of the contact point C in the world frame W.
- Parameter
separation_speed
: Separation speed along the normal direction between body A and body B, in meters per second. A positive value indicates bodies are moving apart. A negative value indicates bodies are moving towards each other.
- Parameter
slip_speed
: Slip speed, that is, the magnitude of the relative tangential velocity at the contact point in meters per second. A non-negative value always.
- Parameter
point_pair
: Additional point pair information for
this
contact info. Refer to the documentation for PenetrationAsPointPair for further details. It is expected that the body indexed bybodyA_index
is the same body that contains the geometry indexed bypoint_pair.id_A
. Likewise for the body indexed bybodyB_index
and the body contining geometry with idpoint_pair.id_B
.- Precondition:
The two body indexes must reference bodies from the same MultibodyPlant. Contact values should likewise be generated by the same MultibodyPlant.
- Parameter
- bodyA_index(self: pydrake.multibody.plant.PointPairContactInfo_[AutoDiffXd]) pydrake.multibody.tree.BodyIndex
Returns the index of body A in the contact pair.
- bodyB_index(self: pydrake.multibody.plant.PointPairContactInfo_[AutoDiffXd]) pydrake.multibody.tree.BodyIndex
Returns the index of body B in the contact pair.
- contact_force(self: pydrake.multibody.plant.PointPairContactInfo_[AutoDiffXd]) numpy.ndarray[object[3, 1]]
Returns the contact force
f_Bc_W
on B at contact point C expressed in the world frame W.
- contact_point(self: pydrake.multibody.plant.PointPairContactInfo_[AutoDiffXd]) numpy.ndarray[object[3, 1]]
Returns the position
p_WC
of the contact point C in the world frame W.
- point_pair(self: pydrake.multibody.plant.PointPairContactInfo_[AutoDiffXd]) pydrake.geometry.PenetrationAsPointPair_[AutoDiffXd]
Returns additional information for the geometric contact query for
this
pair as a PenetrationAsPointPair. The body containingpoint_pair().id_A
is the same body indexed bybodyA_index()
. Likewise, the body containingpoint_pair().id_B
is the same body indexed bybodyB_index()
.
- separation_speed(self: pydrake.multibody.plant.PointPairContactInfo_[AutoDiffXd]) pydrake.autodiffutils.AutoDiffXd
Returns the separation speed between body A and B along the normal direction (see PenetrationAsPointPair::nhat_BA_W) at the contact point. It is defined positive for bodies moving apart in the normal direction.
- slip_speed(self: pydrake.multibody.plant.PointPairContactInfo_[AutoDiffXd]) pydrake.autodiffutils.AutoDiffXd
Returns the slip speed between body A and B at contact point C.
- class pydrake.multibody.plant.PointPairContactInfo_[Expression]
A class containing information regarding contact response between two bodies including:
The pair of bodies that are contacting, referenced by their BodyIndex.
A resultant contact force.
A contact point.
Separation speed.
Slip speed.
- __init__(self: pydrake.multibody.plant.PointPairContactInfo_[Expression], bodyA_index: pydrake.multibody.tree.BodyIndex, bodyB_index: pydrake.multibody.tree.BodyIndex, f_Bc_W: numpy.ndarray[object[3, 1]], p_WC: numpy.ndarray[object[3, 1]], separation_speed: pydrake.symbolic.Expression, slip_speed: pydrake.symbolic.Expression, point_pair: pydrake.geometry.PenetrationAsPointPair_[Expression]) None
Constructs the contact information for a given pair of two colliding bodies.
- Parameter
bodyA_index
: Index that references body A in
this
contact pair.- Parameter
bodyB_index
: Index that references body B in
this
contact pair.- Parameter
f_Bc_W
: Force on body B applied at contact point C, expressed in the world frame W.
- Parameter
p_WC
: Position of the contact point C in the world frame W.
- Parameter
separation_speed
: Separation speed along the normal direction between body A and body B, in meters per second. A positive value indicates bodies are moving apart. A negative value indicates bodies are moving towards each other.
- Parameter
slip_speed
: Slip speed, that is, the magnitude of the relative tangential velocity at the contact point in meters per second. A non-negative value always.
- Parameter
point_pair
: Additional point pair information for
this
contact info. Refer to the documentation for PenetrationAsPointPair for further details. It is expected that the body indexed bybodyA_index
is the same body that contains the geometry indexed bypoint_pair.id_A
. Likewise for the body indexed bybodyB_index
and the body contining geometry with idpoint_pair.id_B
.- Precondition:
The two body indexes must reference bodies from the same MultibodyPlant. Contact values should likewise be generated by the same MultibodyPlant.
- Parameter
- bodyA_index(self: pydrake.multibody.plant.PointPairContactInfo_[Expression]) pydrake.multibody.tree.BodyIndex
Returns the index of body A in the contact pair.
- bodyB_index(self: pydrake.multibody.plant.PointPairContactInfo_[Expression]) pydrake.multibody.tree.BodyIndex
Returns the index of body B in the contact pair.
- contact_force(self: pydrake.multibody.plant.PointPairContactInfo_[Expression]) numpy.ndarray[object[3, 1]]
Returns the contact force
f_Bc_W
on B at contact point C expressed in the world frame W.
- contact_point(self: pydrake.multibody.plant.PointPairContactInfo_[Expression]) numpy.ndarray[object[3, 1]]
Returns the position
p_WC
of the contact point C in the world frame W.
- point_pair(self: pydrake.multibody.plant.PointPairContactInfo_[Expression]) pydrake.geometry.PenetrationAsPointPair_[Expression]
Returns additional information for the geometric contact query for
this
pair as a PenetrationAsPointPair. The body containingpoint_pair().id_A
is the same body indexed bybodyA_index()
. Likewise, the body containingpoint_pair().id_B
is the same body indexed bybodyB_index()
.
- separation_speed(self: pydrake.multibody.plant.PointPairContactInfo_[Expression]) pydrake.symbolic.Expression
Returns the separation speed between body A and B along the normal direction (see PenetrationAsPointPair::nhat_BA_W) at the contact point. It is defined positive for bodies moving apart in the normal direction.
- slip_speed(self: pydrake.multibody.plant.PointPairContactInfo_[Expression]) pydrake.symbolic.Expression
Returns the slip speed between body A and B at contact point C.
- class pydrake.multibody.plant.Propeller
Bases:
pydrake.systems.framework.LeafSystem
A System that connects to the MultibodyPlant in order to model the effects of one or more controlled propellers acting on a Body.
command→ body_poses→ Propeller → spatial_forces The command input is a BasicVector<T> with one element per propeller.
It is expected that the body_poses input should be connected to the
MultibodyPlant::get_body_poses_output_port() “MultibodyPlant body_poses output port”. - The output is of type std::vector<ExternallyAppliedSpatialForce<T>>; it is expected that this output will be connected to the MultibodyPlant::get_applied_spatial_force_input_port() “externally_applied_spatial_force input port” of the MultibodyPlant. - This system does not have any state.
The resulting iᵗʰ spatial force will have a force component in the z-axis of the iᵗʰ propeller frame with magnitude
thrust_ratio * command
Newtons, and a moment around the z-axis with magnitudemoment_ratio * command
Newton-meters. (Including these moments tends to be important – a quadrotor does not have a stabilizable linearization around a hovering fixed point in 3D without them).Note
Set PropellerInfo::moment_ratio to zero if you want a simple thruster which applies only a force (no moment) in the Propeller coordinates.
Note
This class is templated; see
Propeller_
for the list of instantiations.- __init__(*args, **kwargs)
Overloaded function.
__init__(self: pydrake.multibody.plant.Propeller, body_index: pydrake.multibody.tree.BodyIndex, X_BP: pydrake.math.RigidTransform = RigidTransform( R=RotationMatrix([ [1.0, 0.0, 0.0], [0.0, 1.0, 0.0], [0.0, 0.0, 1.0], ]), p=[0.0, 0.0, 0.0], ), thrust_ratio: float = 1.0, moment_ratio: float = 0.0) -> None
Constructs a system describing a single propeller.
See also
PropellerInfo for details on the arguments.
__init__(self: pydrake.multibody.plant.Propeller, propeller_info: list[pydrake.multibody.plant.PropellerInfo]) -> None
Constructs a system describing multiple propellers.
See also
PropellerInfo.
- get_body_poses_input_port(self: pydrake.multibody.plant.Propeller) pydrake.systems.framework.InputPort
Returns a reference to the body_poses input port. It is anticipated that this port will be connected the body_poses output port of a MultibodyPlant.
- get_command_input_port(self: pydrake.multibody.plant.Propeller) pydrake.systems.framework.InputPort
Returns a reference to the vector-valued input port for the propeller commands. It has size
num_propellers()
.
- get_spatial_forces_output_port(self: pydrake.multibody.plant.Propeller) pydrake.systems.framework.OutputPort
Returns a reference to the spatial_forces output port. It is anticipated that this port will be connected to the MultibodyPlant::get_applied_spatial_force_input_port() “applied_spatial_force” input port of a MultibodyPlant.
- num_propellers(self: pydrake.multibody.plant.Propeller) int
Returns the number of propellers modeled by this system.
- template pydrake.multibody.plant.Propeller_
Instantiations:
Propeller_[float]
,Propeller_[AutoDiffXd]
,Propeller_[Expression]
- class pydrake.multibody.plant.Propeller_[AutoDiffXd]
Bases:
pydrake.systems.framework.LeafSystem_[AutoDiffXd]
A System that connects to the MultibodyPlant in order to model the effects of one or more controlled propellers acting on a Body.
command→ body_poses→ Propeller → spatial_forces The command input is a BasicVector<T> with one element per propeller.
It is expected that the body_poses input should be connected to the
MultibodyPlant::get_body_poses_output_port() “MultibodyPlant body_poses output port”. - The output is of type std::vector<ExternallyAppliedSpatialForce<T>>; it is expected that this output will be connected to the MultibodyPlant::get_applied_spatial_force_input_port() “externally_applied_spatial_force input port” of the MultibodyPlant. - This system does not have any state.
The resulting iᵗʰ spatial force will have a force component in the z-axis of the iᵗʰ propeller frame with magnitude
thrust_ratio * command
Newtons, and a moment around the z-axis with magnitudemoment_ratio * command
Newton-meters. (Including these moments tends to be important – a quadrotor does not have a stabilizable linearization around a hovering fixed point in 3D without them).Note
Set PropellerInfo::moment_ratio to zero if you want a simple thruster which applies only a force (no moment) in the Propeller coordinates.
- __init__(*args, **kwargs)
Overloaded function.
__init__(self: pydrake.multibody.plant.Propeller_[AutoDiffXd], body_index: pydrake.multibody.tree.BodyIndex, X_BP: pydrake.math.RigidTransform = RigidTransform( R=RotationMatrix([ [1.0, 0.0, 0.0], [0.0, 1.0, 0.0], [0.0, 0.0, 1.0], ]), p=[0.0, 0.0, 0.0], ), thrust_ratio: float = 1.0, moment_ratio: float = 0.0) -> None
Constructs a system describing a single propeller.
See also
PropellerInfo for details on the arguments.
__init__(self: pydrake.multibody.plant.Propeller_[AutoDiffXd], propeller_info: list[pydrake.multibody.plant.PropellerInfo]) -> None
Constructs a system describing multiple propellers.
See also
PropellerInfo.
- get_body_poses_input_port(self: pydrake.multibody.plant.Propeller_[AutoDiffXd]) pydrake.systems.framework.InputPort_[AutoDiffXd]
Returns a reference to the body_poses input port. It is anticipated that this port will be connected the body_poses output port of a MultibodyPlant.
- get_command_input_port(self: pydrake.multibody.plant.Propeller_[AutoDiffXd]) pydrake.systems.framework.InputPort_[AutoDiffXd]
Returns a reference to the vector-valued input port for the propeller commands. It has size
num_propellers()
.
- get_spatial_forces_output_port(self: pydrake.multibody.plant.Propeller_[AutoDiffXd]) pydrake.systems.framework.OutputPort_[AutoDiffXd]
Returns a reference to the spatial_forces output port. It is anticipated that this port will be connected to the MultibodyPlant::get_applied_spatial_force_input_port() “applied_spatial_force” input port of a MultibodyPlant.
- num_propellers(self: pydrake.multibody.plant.Propeller_[AutoDiffXd]) int
Returns the number of propellers modeled by this system.
- class pydrake.multibody.plant.Propeller_[Expression]
Bases:
pydrake.systems.framework.LeafSystem_[Expression]
A System that connects to the MultibodyPlant in order to model the effects of one or more controlled propellers acting on a Body.
command→ body_poses→ Propeller → spatial_forces The command input is a BasicVector<T> with one element per propeller.
It is expected that the body_poses input should be connected to the
MultibodyPlant::get_body_poses_output_port() “MultibodyPlant body_poses output port”. - The output is of type std::vector<ExternallyAppliedSpatialForce<T>>; it is expected that this output will be connected to the MultibodyPlant::get_applied_spatial_force_input_port() “externally_applied_spatial_force input port” of the MultibodyPlant. - This system does not have any state.
The resulting iᵗʰ spatial force will have a force component in the z-axis of the iᵗʰ propeller frame with magnitude
thrust_ratio * command
Newtons, and a moment around the z-axis with magnitudemoment_ratio * command
Newton-meters. (Including these moments tends to be important – a quadrotor does not have a stabilizable linearization around a hovering fixed point in 3D without them).Note
Set PropellerInfo::moment_ratio to zero if you want a simple thruster which applies only a force (no moment) in the Propeller coordinates.
- __init__(*args, **kwargs)
Overloaded function.
__init__(self: pydrake.multibody.plant.Propeller_[Expression], body_index: pydrake.multibody.tree.BodyIndex, X_BP: pydrake.math.RigidTransform = RigidTransform( R=RotationMatrix([ [1.0, 0.0, 0.0], [0.0, 1.0, 0.0], [0.0, 0.0, 1.0], ]), p=[0.0, 0.0, 0.0], ), thrust_ratio: float = 1.0, moment_ratio: float = 0.0) -> None
Constructs a system describing a single propeller.
See also
PropellerInfo for details on the arguments.
__init__(self: pydrake.multibody.plant.Propeller_[Expression], propeller_info: list[pydrake.multibody.plant.PropellerInfo]) -> None
Constructs a system describing multiple propellers.
See also
PropellerInfo.
- get_body_poses_input_port(self: pydrake.multibody.plant.Propeller_[Expression]) pydrake.systems.framework.InputPort_[Expression]
Returns a reference to the body_poses input port. It is anticipated that this port will be connected the body_poses output port of a MultibodyPlant.
- get_command_input_port(self: pydrake.multibody.plant.Propeller_[Expression]) pydrake.systems.framework.InputPort_[Expression]
Returns a reference to the vector-valued input port for the propeller commands. It has size
num_propellers()
.
- get_spatial_forces_output_port(self: pydrake.multibody.plant.Propeller_[Expression]) pydrake.systems.framework.OutputPort_[Expression]
Returns a reference to the spatial_forces output port. It is anticipated that this port will be connected to the MultibodyPlant::get_applied_spatial_force_input_port() “applied_spatial_force” input port of a MultibodyPlant.
- num_propellers(self: pydrake.multibody.plant.Propeller_[Expression]) int
Returns the number of propellers modeled by this system.
- class pydrake.multibody.plant.PropellerInfo
Parameters that describe the kinematic frame and force-production properties of a single propeller.
- __init__(self: pydrake.multibody.plant.PropellerInfo, body_index: pydrake.multibody.tree.BodyIndex, X_BP: pydrake.math.RigidTransform = RigidTransform(R=RotationMatrix([[1.0, 0.0, 0.0], [0.0, 1.0, 0.0], [0.0, 0.0, 1.0]]), p=[0.0, 0.0, 0.0]), thrust_ratio: float = 1.0, moment_ratio: float = 0.0) None
- property body_index
The BodyIndex of a RigidBody in the MultibodyPlant to which the propeller is attached. The spatial forces will be applied to this body.
- property moment_ratio
The moment about the z axis (in frame P) of the spatial force will have magnitude
moment_ratio*command
in Newton-meters. The default is 0, which makes the propeller a simple Cartesian force generator.
- property thrust_ratio
The z component (in frame P) of the spatial force will have magnitude
thrust_ratio*command
in Newtons. The default is 1 (command in Newtons), but this can also be used to scale an actuator command to the resulting force.
- property X_BP
Pose of the propeller frame P measured in the body frame B. $*Default:* is the identity matrix.
- class pydrake.multibody.plant.Wing
Bases:
pydrake.systems.framework.LeafSystem
A System that connects to the MultibodyPlant in order to model the simplified dynamics of an airfoil (or hydrofoil). Currently it only supports a particular model of flat-plate aerodynamics with lift coefficient = 2 sinα cosα, drag coefficient = 2 sin²α, moment coefficient = 0, as documented for a number of NACA airfoils with Reynolds number ≤ 10^5 in:
S. F. Hoerner and H. V. Borst, “Fluid-dynamic lift: practical information on aerodynamic and hydrodynamic lift,” 1985 (Ch. 4, Section 6).
This model was also empirically validated for a bird-scale UAV with flat-plate wings (Reynolds number below 53000) in:
Rick Cory and Russ Tedrake, “Experiments in Fixed-Wing UAV Perching”, Proceedings of the AIAA Guidance, Navigation, and Control Conference , pp. 1-12, 2008.
and may generalize well as a model for other wings in the post-stall regime, but it should only be viewed as a simple / coarse approximation. We aim to generalize this class to general lift/drag/moment coefficients soon.
body_poses→ body_spatial_velocities→ wind_velocity_at_aerodynamic_center (optional)→ fluid_density (optional)→ Wing → spatial_force → aerodynamic_center The optional wind velocity input is a three-element BasicVector<T>
representing the translational velocity of the wind in world coordinates at the aerodynamic center relative to the world origin. See get_aerodynamic_center_output_port() for more details. - It is expected that the body_poses input should be connected to the MultibodyPlant::get_body_poses_output_port() “MultibodyPlant body_poses output port” and that body_spatial_velocities input should be connected to the MultibodyPlant::get_body_spatial_velocities_output_port() “MultibodyPlant body_spatial_velocities output port” - The output is of type std::vector<ExternallyAppliedSpatialForce<T>>; it is expected that this output will be connected to the MultibodyPlant::get_applied_spatial_force_input_port() “externally_applied_spatial_force input port” of the MultibodyPlant.
Note
This class is templated; see
Wing_
for the list of instantiations.- __init__(self: pydrake.multibody.plant.Wing, body_index: pydrake.multibody.tree.BodyIndex, surface_area: float, X_BodyWing: pydrake.math.RigidTransform = RigidTransform(R=RotationMatrix([[1.0, 0.0, 0.0], [0.0, 1.0, 0.0], [0.0, 0.0, 1.0]]), p=[0.0, 0.0, 0.0]), fluid_density: float = 1.204) None
Constructs a system describing a single wing using flat-plate aerodynamics as described in the class documentation.
- Parameter
body_index
: indicates the body on which the aerodynamic forces are applied.
- Parameter
surface_area
: is the total surface area of the wing in meters squared.
- Parameter
X_BodyWing
: is the pose of wing frame relative to the body frame, whose origin is at the aerodynamic center of the wing, the positive x-axis points along the chord towards the leading edge (e.g. towards the nose of the plane), the positive y-axis points along the span, and the z-axis points up. According to thin airfoil theory, the aerodynamic center of a symmetric wing (like this flat plate), is located at a quarter-chord position behind the leading edge.
- Parameter
fluid_density
: is the density of the fluid in kg/m^3. The default value is the density of dry air at 20 deg Celsius at sea-level. This value is only used if the optional fluid_density input port is not connected.
- Parameter
- static AddToBuilder(builder: pydrake.systems.framework.DiagramBuilder, plant: pydrake.multibody.plant.MultibodyPlant, body_index: pydrake.multibody.tree.BodyIndex, surface_area: float, X_BodyWing: pydrake.math.RigidTransform = RigidTransform(R=RotationMatrix([[1.0, 0.0, 0.0], [0.0, 1.0, 0.0], [0.0, 0.0, 1.0]]), p=[0.0, 0.0, 0.0]), fluid_density: float = 1.204) pydrake.multibody.plant.Wing
Helper method that constructs a Wing and connects the input and output ports to the MultibodyPlant.
- Parameter
builder
: is a DiagramBuilder that the Wing will be added to.
- Parameter
plant
: is the MultibodyPlant containing the body referenced by
body_index
, which the wing ports will be connected to.
See the Wing constructor for details on the remaining parameters.
- Parameter
- get_aerodynamic_center_output_port(self: pydrake.multibody.plant.Wing) pydrake.systems.framework.OutputPort
Returns a 3-element position of the aerodynamic center of the wing in world coordinates. This output port does not depend on the optional wind velocity input port, so it may be used to compute the wind velocity at the aerodynamic center without causing any algebraic loops in the Diagram. For instance, the following (sub-)Diagram could be used to implement a wind field: ┌────────────┐ ┌──┤ Wind Field │◄─┐ │ └────────────┘ │ │ ┌──────────┐ │ └──►│ Wing ├───┘ wind_velocity_at_└──────────┘aerodynamic_center aerodynamic_center
- get_body_poses_input_port(self: pydrake.multibody.plant.Wing) pydrake.systems.framework.InputPort
Returns a reference to the body_poses input port. It is anticipated that this port will be connected the body_poses output port of a MultibodyPlant.
- get_body_spatial_velocities_input_port(self: pydrake.multibody.plant.Wing) pydrake.systems.framework.InputPort
Returns a reference to the body_spatial_velocities input port. It is anticipated that this port will be connected the body_spatial_velocities output port of a MultibodyPlant.
- get_fluid_density_input_port(self: pydrake.multibody.plant.Wing) pydrake.systems.framework.InputPort
Returns a reference to the optional fluid_density input port, which accepts a scalar vector in units kg/m^3. This port is provided to support vehicles which must take into account variations in atmospheric density; such as a spacecraft during re-entry. If left unconnected, the aerodynamic forces will be calculated using the default fluid density passed in the constructor.
- get_spatial_force_output_port(self: pydrake.multibody.plant.Wing) pydrake.systems.framework.OutputPort
Returns a reference to the spatial_forces output port. It is anticipated that this port will be connected to the MultibodyPlant::get_applied_spatial_force_input_port() “applied_spatial_force” input port of a MultibodyPlant.
- get_wind_velocity_input_port(self: pydrake.multibody.plant.Wing) pydrake.systems.framework.InputPort
Returns a reference to the input port for the optional three-element BasicVector<T> representing the translational velocity of the wind in world coordinates at the aerodynamic center relative to the world origin. If this port is not connected, then the wind velocity is taken to be zero.
- template pydrake.multibody.plant.Wing_
Instantiations:
Wing_[float]
,Wing_[AutoDiffXd]
,Wing_[Expression]
- class pydrake.multibody.plant.Wing_[AutoDiffXd]
Bases:
pydrake.systems.framework.LeafSystem_[AutoDiffXd]
A System that connects to the MultibodyPlant in order to model the simplified dynamics of an airfoil (or hydrofoil). Currently it only supports a particular model of flat-plate aerodynamics with lift coefficient = 2 sinα cosα, drag coefficient = 2 sin²α, moment coefficient = 0, as documented for a number of NACA airfoils with Reynolds number ≤ 10^5 in:
S. F. Hoerner and H. V. Borst, “Fluid-dynamic lift: practical information on aerodynamic and hydrodynamic lift,” 1985 (Ch. 4, Section 6).
This model was also empirically validated for a bird-scale UAV with flat-plate wings (Reynolds number below 53000) in:
Rick Cory and Russ Tedrake, “Experiments in Fixed-Wing UAV Perching”, Proceedings of the AIAA Guidance, Navigation, and Control Conference , pp. 1-12, 2008.
and may generalize well as a model for other wings in the post-stall regime, but it should only be viewed as a simple / coarse approximation. We aim to generalize this class to general lift/drag/moment coefficients soon.
body_poses→ body_spatial_velocities→ wind_velocity_at_aerodynamic_center (optional)→ fluid_density (optional)→ Wing → spatial_force → aerodynamic_center The optional wind velocity input is a three-element BasicVector<T>
representing the translational velocity of the wind in world coordinates at the aerodynamic center relative to the world origin. See get_aerodynamic_center_output_port() for more details. - It is expected that the body_poses input should be connected to the MultibodyPlant::get_body_poses_output_port() “MultibodyPlant body_poses output port” and that body_spatial_velocities input should be connected to the MultibodyPlant::get_body_spatial_velocities_output_port() “MultibodyPlant body_spatial_velocities output port” - The output is of type std::vector<ExternallyAppliedSpatialForce<T>>; it is expected that this output will be connected to the MultibodyPlant::get_applied_spatial_force_input_port() “externally_applied_spatial_force input port” of the MultibodyPlant.
- __init__(self: pydrake.multibody.plant.Wing_[AutoDiffXd], body_index: pydrake.multibody.tree.BodyIndex, surface_area: float, X_BodyWing: pydrake.math.RigidTransform = RigidTransform(R=RotationMatrix([[1.0, 0.0, 0.0], [0.0, 1.0, 0.0], [0.0, 0.0, 1.0]]), p=[0.0, 0.0, 0.0]), fluid_density: float = 1.204) None
Constructs a system describing a single wing using flat-plate aerodynamics as described in the class documentation.
- Parameter
body_index
: indicates the body on which the aerodynamic forces are applied.
- Parameter
surface_area
: is the total surface area of the wing in meters squared.
- Parameter
X_BodyWing
: is the pose of wing frame relative to the body frame, whose origin is at the aerodynamic center of the wing, the positive x-axis points along the chord towards the leading edge (e.g. towards the nose of the plane), the positive y-axis points along the span, and the z-axis points up. According to thin airfoil theory, the aerodynamic center of a symmetric wing (like this flat plate), is located at a quarter-chord position behind the leading edge.
- Parameter
fluid_density
: is the density of the fluid in kg/m^3. The default value is the density of dry air at 20 deg Celsius at sea-level. This value is only used if the optional fluid_density input port is not connected.
- Parameter
- static AddToBuilder(builder: pydrake.systems.framework.DiagramBuilder_[AutoDiffXd], plant: pydrake.multibody.plant.MultibodyPlant_[AutoDiffXd], body_index: pydrake.multibody.tree.BodyIndex, surface_area: float, X_BodyWing: pydrake.math.RigidTransform = RigidTransform(R=RotationMatrix([[1.0, 0.0, 0.0], [0.0, 1.0, 0.0], [0.0, 0.0, 1.0]]), p=[0.0, 0.0, 0.0]), fluid_density: float = 1.204) pydrake.multibody.plant.Wing_[AutoDiffXd]
Helper method that constructs a Wing and connects the input and output ports to the MultibodyPlant.
- Parameter
builder
: is a DiagramBuilder that the Wing will be added to.
- Parameter
plant
: is the MultibodyPlant containing the body referenced by
body_index
, which the wing ports will be connected to.
See the Wing constructor for details on the remaining parameters.
- Parameter
- get_aerodynamic_center_output_port(self: pydrake.multibody.plant.Wing_[AutoDiffXd]) pydrake.systems.framework.OutputPort_[AutoDiffXd]
Returns a 3-element position of the aerodynamic center of the wing in world coordinates. This output port does not depend on the optional wind velocity input port, so it may be used to compute the wind velocity at the aerodynamic center without causing any algebraic loops in the Diagram. For instance, the following (sub-)Diagram could be used to implement a wind field: ┌────────────┐ ┌──┤ Wind Field │◄─┐ │ └────────────┘ │ │ ┌──────────┐ │ └──►│ Wing ├───┘ wind_velocity_at_└──────────┘aerodynamic_center aerodynamic_center
- get_body_poses_input_port(self: pydrake.multibody.plant.Wing_[AutoDiffXd]) pydrake.systems.framework.InputPort_[AutoDiffXd]
Returns a reference to the body_poses input port. It is anticipated that this port will be connected the body_poses output port of a MultibodyPlant.
- get_body_spatial_velocities_input_port(self: pydrake.multibody.plant.Wing_[AutoDiffXd]) pydrake.systems.framework.InputPort_[AutoDiffXd]
Returns a reference to the body_spatial_velocities input port. It is anticipated that this port will be connected the body_spatial_velocities output port of a MultibodyPlant.
- get_fluid_density_input_port(self: pydrake.multibody.plant.Wing_[AutoDiffXd]) pydrake.systems.framework.InputPort_[AutoDiffXd]
Returns a reference to the optional fluid_density input port, which accepts a scalar vector in units kg/m^3. This port is provided to support vehicles which must take into account variations in atmospheric density; such as a spacecraft during re-entry. If left unconnected, the aerodynamic forces will be calculated using the default fluid density passed in the constructor.
- get_spatial_force_output_port(self: pydrake.multibody.plant.Wing_[AutoDiffXd]) pydrake.systems.framework.OutputPort_[AutoDiffXd]
Returns a reference to the spatial_forces output port. It is anticipated that this port will be connected to the MultibodyPlant::get_applied_spatial_force_input_port() “applied_spatial_force” input port of a MultibodyPlant.
- get_wind_velocity_input_port(self: pydrake.multibody.plant.Wing_[AutoDiffXd]) pydrake.systems.framework.InputPort_[AutoDiffXd]
Returns a reference to the input port for the optional three-element BasicVector<T> representing the translational velocity of the wind in world coordinates at the aerodynamic center relative to the world origin. If this port is not connected, then the wind velocity is taken to be zero.
- class pydrake.multibody.plant.Wing_[Expression]
Bases:
pydrake.systems.framework.LeafSystem_[Expression]
A System that connects to the MultibodyPlant in order to model the simplified dynamics of an airfoil (or hydrofoil). Currently it only supports a particular model of flat-plate aerodynamics with lift coefficient = 2 sinα cosα, drag coefficient = 2 sin²α, moment coefficient = 0, as documented for a number of NACA airfoils with Reynolds number ≤ 10^5 in:
S. F. Hoerner and H. V. Borst, “Fluid-dynamic lift: practical information on aerodynamic and hydrodynamic lift,” 1985 (Ch. 4, Section 6).
This model was also empirically validated for a bird-scale UAV with flat-plate wings (Reynolds number below 53000) in:
Rick Cory and Russ Tedrake, “Experiments in Fixed-Wing UAV Perching”, Proceedings of the AIAA Guidance, Navigation, and Control Conference , pp. 1-12, 2008.
and may generalize well as a model for other wings in the post-stall regime, but it should only be viewed as a simple / coarse approximation. We aim to generalize this class to general lift/drag/moment coefficients soon.
body_poses→ body_spatial_velocities→ wind_velocity_at_aerodynamic_center (optional)→ fluid_density (optional)→ Wing → spatial_force → aerodynamic_center The optional wind velocity input is a three-element BasicVector<T>
representing the translational velocity of the wind in world coordinates at the aerodynamic center relative to the world origin. See get_aerodynamic_center_output_port() for more details. - It is expected that the body_poses input should be connected to the MultibodyPlant::get_body_poses_output_port() “MultibodyPlant body_poses output port” and that body_spatial_velocities input should be connected to the MultibodyPlant::get_body_spatial_velocities_output_port() “MultibodyPlant body_spatial_velocities output port” - The output is of type std::vector<ExternallyAppliedSpatialForce<T>>; it is expected that this output will be connected to the MultibodyPlant::get_applied_spatial_force_input_port() “externally_applied_spatial_force input port” of the MultibodyPlant.
- __init__(self: pydrake.multibody.plant.Wing_[Expression], body_index: pydrake.multibody.tree.BodyIndex, surface_area: float, X_BodyWing: pydrake.math.RigidTransform = RigidTransform(R=RotationMatrix([[1.0, 0.0, 0.0], [0.0, 1.0, 0.0], [0.0, 0.0, 1.0]]), p=[0.0, 0.0, 0.0]), fluid_density: float = 1.204) None
Constructs a system describing a single wing using flat-plate aerodynamics as described in the class documentation.
- Parameter
body_index
: indicates the body on which the aerodynamic forces are applied.
- Parameter
surface_area
: is the total surface area of the wing in meters squared.
- Parameter
X_BodyWing
: is the pose of wing frame relative to the body frame, whose origin is at the aerodynamic center of the wing, the positive x-axis points along the chord towards the leading edge (e.g. towards the nose of the plane), the positive y-axis points along the span, and the z-axis points up. According to thin airfoil theory, the aerodynamic center of a symmetric wing (like this flat plate), is located at a quarter-chord position behind the leading edge.
- Parameter
fluid_density
: is the density of the fluid in kg/m^3. The default value is the density of dry air at 20 deg Celsius at sea-level. This value is only used if the optional fluid_density input port is not connected.
- Parameter
- static AddToBuilder(builder: pydrake.systems.framework.DiagramBuilder_[Expression], plant: pydrake.multibody.plant.MultibodyPlant_[Expression], body_index: pydrake.multibody.tree.BodyIndex, surface_area: float, X_BodyWing: pydrake.math.RigidTransform = RigidTransform(R=RotationMatrix([[1.0, 0.0, 0.0], [0.0, 1.0, 0.0], [0.0, 0.0, 1.0]]), p=[0.0, 0.0, 0.0]), fluid_density: float = 1.204) pydrake.multibody.plant.Wing_[Expression]
Helper method that constructs a Wing and connects the input and output ports to the MultibodyPlant.
- Parameter
builder
: is a DiagramBuilder that the Wing will be added to.
- Parameter
plant
: is the MultibodyPlant containing the body referenced by
body_index
, which the wing ports will be connected to.
See the Wing constructor for details on the remaining parameters.
- Parameter
- get_aerodynamic_center_output_port(self: pydrake.multibody.plant.Wing_[Expression]) pydrake.systems.framework.OutputPort_[Expression]
Returns a 3-element position of the aerodynamic center of the wing in world coordinates. This output port does not depend on the optional wind velocity input port, so it may be used to compute the wind velocity at the aerodynamic center without causing any algebraic loops in the Diagram. For instance, the following (sub-)Diagram could be used to implement a wind field: ┌────────────┐ ┌──┤ Wind Field │◄─┐ │ └────────────┘ │ │ ┌──────────┐ │ └──►│ Wing ├───┘ wind_velocity_at_└──────────┘aerodynamic_center aerodynamic_center
- get_body_poses_input_port(self: pydrake.multibody.plant.Wing_[Expression]) pydrake.systems.framework.InputPort_[Expression]
Returns a reference to the body_poses input port. It is anticipated that this port will be connected the body_poses output port of a MultibodyPlant.
- get_body_spatial_velocities_input_port(self: pydrake.multibody.plant.Wing_[Expression]) pydrake.systems.framework.InputPort_[Expression]
Returns a reference to the body_spatial_velocities input port. It is anticipated that this port will be connected the body_spatial_velocities output port of a MultibodyPlant.
- get_fluid_density_input_port(self: pydrake.multibody.plant.Wing_[Expression]) pydrake.systems.framework.InputPort_[Expression]
Returns a reference to the optional fluid_density input port, which accepts a scalar vector in units kg/m^3. This port is provided to support vehicles which must take into account variations in atmospheric density; such as a spacecraft during re-entry. If left unconnected, the aerodynamic forces will be calculated using the default fluid density passed in the constructor.
- get_spatial_force_output_port(self: pydrake.multibody.plant.Wing_[Expression]) pydrake.systems.framework.OutputPort_[Expression]
Returns a reference to the spatial_forces output port. It is anticipated that this port will be connected to the MultibodyPlant::get_applied_spatial_force_input_port() “applied_spatial_force” input port of a MultibodyPlant.
- get_wind_velocity_input_port(self: pydrake.multibody.plant.Wing_[Expression]) pydrake.systems.framework.InputPort_[Expression]
Returns a reference to the input port for the optional three-element BasicVector<T> representing the translational velocity of the wind in world coordinates at the aerodynamic center relative to the world origin. If this port is not connected, then the wind velocity is taken to be zero.