Drake
Drake C++ Documentation
MultibodyPlant< T > Class Template Reference

Detailed Description

template<typename T>
class drake::multibody::MultibodyPlant< T >

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 Kinematics and Dynamics 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 model_instance_name[i] represent groups of ports, one for each of the 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() and default_model_instance() always exist.)

The ports shown in green are for communication with Drake's SceneGraph system for dealing with geometry.

MultibodyPlant provides a user-facing API for:

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 size nq (see num_positions()), and by its generalized velocities vector v, of size nv (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 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 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]:

         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 inertias), C(q, v)v contains Coriolis, centripetal, and gyroscopic terms and N(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 an nq 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 and yk 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, and contact_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 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 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 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 instance in the MultibodyPlant (see 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)) 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) 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.
The following snippet shows how per model instance actuation can be set:
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);
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 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:

  ũ = -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(), and e 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:

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):

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:

auto items = AddMultibodyPlantSceneGraph(&builder, 0.0 /+ time_step +/);
items.plant.DoFoo(...);
items.scene_graph.DoBar(...);

or taking advantage of C++'s structured binding:

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:

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:

  1. Call to RegisterAsSourceForSceneGraph().
  2. Calls to RegisterCollisionGeometry(), as many as needed.
  3. 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 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:

// 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:

// 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:

// 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:

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:

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 =
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:

All modeling elements must be added before Finalize() is called. See Finalize stage for a discussion.

Modeling contact

Please refer to 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.
Template Parameters
TThe scalar type, which must be one of the default scalars.

#include <drake/multibody/tree/multibody_element.h>

Public Member Functions

Does not allow copy, move, or assignment
 MultibodyPlant (const MultibodyPlant &)=delete
 
MultibodyPlantoperator= (const MultibodyPlant &)=delete
 
 MultibodyPlant (MultibodyPlant &&)=delete
 
MultibodyPlantoperator= (MultibodyPlant &&)=delete
 
Input and output ports

These methods provide access to the Drake System input and output ports as depicted in the MultibodyPlant class documentation.

Actuation values can be provided through a single input port which describes the entire plant, or through multiple input ports which each provide the actuation values for a specific model instance. See AddJointActuator() and num_actuated_dofs().

Output ports provide information about the entire MultibodyPlant or its individual model instances.

const systems::OutputPort< T > & get_body_poses_output_port () const
 Returns the output port of all body poses in the world frame. More...
 
const systems::OutputPort< T > & get_body_spatial_velocities_output_port () const
 Returns the output port of all body spatial velocities in the world frame. More...
 
const systems::OutputPort< T > & get_body_spatial_accelerations_output_port () const
 Returns the output port of all body spatial accelerations in the world frame. More...
 
const systems::InputPort< T > & get_actuation_input_port () const
 Returns a constant reference to the input port for external actuation for all actuated dofs. More...
 
const systems::InputPort< T > & get_actuation_input_port (ModelInstanceIndex model_instance) const
 Returns a constant reference to the input port for external actuation for a specific model instance. More...
 
const systems::OutputPort< T > & get_net_actuation_output_port () const
 Returns a constant reference to the output port that reports actuation values applied through joint actuators. More...
 
const systems::OutputPort< T > & get_net_actuation_output_port (ModelInstanceIndex model_instance) const
 Returns a constant reference to the output port that reports actuation values applied through joint actuators, for a specific model instance. More...
 
const systems::InputPort< T > & get_desired_state_input_port (ModelInstanceIndex model_instance) const
 For models with PD controlled joint actuators, returns the port to provide the desired state for the full model_instance. More...
 
const systems::InputPort< T > & get_applied_generalized_force_input_port () const
 Returns a constant reference to the vector-valued input port for applied generalized forces, and the vector will be added directly into tau (see System dynamics). More...
 
const systems::InputPort< T > & get_applied_spatial_force_input_port () const
 Returns a constant reference to the input port for applying spatial forces to bodies in the plant. More...
 
const systems::InputPort< T > & get_geometry_query_input_port () const
 Returns a constant reference to the input port used to perform geometric queries on a SceneGraph. More...
 
const systems::OutputPort< T > & get_state_output_port () const
 Returns a constant reference to the output port for the multibody state x = [q, v] of the model. More...
 
const systems::OutputPort< T > & get_state_output_port (ModelInstanceIndex model_instance) const
 Returns a constant reference to the output port for the state xᵢ = [qᵢ vᵢ] of model instance i. More...
 
const systems::OutputPort< T > & get_generalized_acceleration_output_port () const
 Returns a constant reference to the output port for generalized accelerations v̇ of the model. More...
 
const systems::OutputPort< T > & get_generalized_acceleration_output_port (ModelInstanceIndex model_instance) const
 Returns a constant reference to the output port for the generalized accelerations v̇ᵢ ⊆ v̇ for model instance i. More...
 
const systems::OutputPort< T > & get_generalized_contact_forces_output_port (ModelInstanceIndex model_instance) const
 Returns a constant reference to the output port of generalized contact forces for a specific model instance. More...
 
const systems::OutputPort< T > & get_reaction_forces_output_port () const
 Returns the port for joint reaction forces. More...
 
const systems::OutputPort< T > & get_contact_results_output_port () const
 Returns a constant reference to the port that outputs ContactResults. More...
 
const systems::OutputPort< T > & get_geometry_pose_output_port () const
 Returns the output port of frames' poses to communicate with a SceneGraph. More...
 
const systems::OutputPort< T > & get_deformable_body_configuration_output_port () const
 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. More...
 
Construction

To add modeling elements like bodies, joints, force elements, constraints, etc. to a MultibodyPlant, use one of the following construction methods. Once all modeling elements have been added, the Finalize() method must be called. A call to any construction method after a call to Finalize() causes an exception to be thrown. After calling Finalize(), you may invoke MultibodyPlant methods that perform computations. See Finalize() for details.

 MultibodyPlant (double time_step)
 This constructor creates a plant with a single "world" body. More...
 
template<typename U >
 MultibodyPlant (const MultibodyPlant< U > &other)
 Scalar-converting copy constructor. See System Scalar Conversion. More...
 
 ~MultibodyPlant () override
 
void SetUseSampledOutputPorts (bool use_sampled_output_ports)
 (Advanced) For a discrete-time plant, configures whether the output ports are sampled (the default) or live (opt-in). More...
 
const RigidBody< T > & AddRigidBody (const std::string &name, ModelInstanceIndex model_instance, const SpatialInertia< double > &M_BBo_B=SpatialInertia< double >::Zero())
 Creates a rigid body with the provided name and spatial inertia. More...
 
const RigidBody< T > & AddRigidBody (const std::string &name, const SpatialInertia< double > &M_BBo_B=SpatialInertia< double >::Zero())
 Creates a rigid body with the provided name and spatial inertia. More...
 
template<template< typename > class FrameType>
const FrameType< T > & AddFrame (std::unique_ptr< FrameType< T >> frame)
 This method adds a Frame of type FrameType<T>. More...
 
template<template< typename Scalar > class JointType>
const JointType< T > & AddJoint (std::unique_ptr< JointType< T >> joint)
 This method adds a Joint of type JointType between two bodies. More...
 
template<template< typename > class JointType, typename... Args>
const JointType< T > & AddJoint (const std::string &name, const RigidBody< T > &parent, const std::optional< math::RigidTransform< double >> &X_PF, const RigidBody< T > &child, const std::optional< math::RigidTransform< double >> &X_BM, Args &&... args)
 This method adds a Joint of type JointType between two bodies. More...
 
void RemoveJoint (const Joint< T > &joint)
 Removes and deletes joint from this MultibodyPlant. More...
 
const WeldJoint< T > & WeldFrames (const Frame< T > &frame_on_parent_F, const Frame< T > &frame_on_child_M, const math::RigidTransform< double > &X_FM=math::RigidTransform< double >::Identity())
 Welds frame_on_parent_F and frame_on_child_M with relative pose X_FM. More...
 
template<template< typename Scalar > class ForceElementType, typename... Args>
const ForceElementType< T > & AddForceElement (Args &&... args)
 Adds a new force element model of type ForceElementType to this MultibodyPlant. More...
 
const JointActuator< T > & AddJointActuator (const std::string &name, const Joint< T > &joint, double effort_limit=std::numeric_limits< double >::infinity())
 Creates and adds a JointActuator model for an actuator acting on a given joint. More...
 
void RemoveJointActuator (const JointActuator< T > &actuator)
 Removes and deletes actuator from this MultibodyPlant. More...
 
ModelInstanceIndex AddModelInstance (const std::string &name)
 Creates a new model instance. More...
 
void RenameModelInstance (ModelInstanceIndex model_instance, const std::string &name)
 Renames an existing model instance. More...
 
void Finalize ()
 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. More...
 
Constraints

Set of APIs to define constraints. To mention a few important examples, constraints can be used to couple the motion of joints, to create kinematic loops, or to weld bodies together.

Currently constraints are only supported for discrete MultibodyPlant models and not for all discrete solvers, see get_discrete_contact_solver(). If the model contains constraints not supported by the discrete solver, the plant will throw an exception at Finalize() time. At this point the user has the option to select a contact model approximation that uses a solver that supports constraints, or to re-define the model so that such a constraint is not needed. A contact model approximation can be set with set_discrete_contact_approximation() or in the MultibodyPlantConfig.

Each constraint is identified with a MultibodyConstraintId returned by the function used to add it (e.g. AddCouplerConstraint()). It is possible to recover constraint specification parameters for each constraint with various introspection functions (e.g. get_coupler_constraint_specs()). Each constraint has an "active" status that is set to true by default. Query a constraint's active status with GetConstraintActiveStatus() and set its active status with SetConstraintActiveStatus().

int num_constraints () const
 Returns the total number of constraints specified by the user. More...
 
std::vector< MultibodyConstraintIdGetConstraintIds () const
 Returns a list of all constraint identifiers. More...
 
int num_coupler_constraints () const
 Returns the total number of coupler constraints specified by the user. More...
 
int num_distance_constraints () const
 Returns the total number of distance constraints specified by the user. More...
 
int num_ball_constraints () const
 Returns the total number of ball constraints specified by the user. More...
 
int num_weld_constraints () const
 Returns the total number of weld constraints specified by the user. More...
 
const internal::CouplerConstraintSpec & get_coupler_constraint_specs (MultibodyConstraintId id) const
 (Internal use only) Returns the coupler constraint specification corresponding to id More...
 
const internal::DistanceConstraintSpec & get_distance_constraint_specs (MultibodyConstraintId id) const
 (Internal use only) Returns the distance constraint specification corresponding to id More...
 
const internal::BallConstraintSpec & get_ball_constraint_specs (MultibodyConstraintId id) const
 (Internal use only) Returns the ball constraint specification corresponding to id More...
 
const internal::WeldConstraintSpec & get_weld_constraint_specs (MultibodyConstraintId id) const
 (Internal use only) Returns the weld constraint specification corresponding to id More...
 
const std::map< MultibodyConstraintId, internal::CouplerConstraintSpec > & get_coupler_constraint_specs () const
 (Internal use only) Returns a reference to the all of the coupler constraints in this plant as a map from MultibodyConstraintId to CouplerConstraintSpec. More...
 
const std::map< MultibodyConstraintId, internal::DistanceConstraintSpec > & get_distance_constraint_specs () const
 (Internal use only) Returns a reference to the all of the distance constraints in this plant as a map from MultibodyConstraintId to DistanceConstraintSpec. More...
 
const std::map< MultibodyConstraintId, internal::BallConstraintSpec > & get_ball_constraint_specs () const
 (Internal use only) Returns a reference to all of the ball constraints in this plant as a map from MultibodyConstraintId to BallConstraintSpec. More...
 
const std::map< MultibodyConstraintId, internal::WeldConstraintSpec > & get_weld_constraint_specs () const
 (Internal use only) Returns a reference to the all of the weld constraints in this plant as a map from MultibodyConstraintId to WeldConstraintSpec. More...
 
bool GetConstraintActiveStatus (const systems::Context< T > &context, MultibodyConstraintId id) const
 Returns the active status of the constraint given by id in context. More...
 
void SetConstraintActiveStatus (systems::Context< T > *context, MultibodyConstraintId id, bool status) const
 Sets the active status of the constraint given by id in context. More...
 
MultibodyConstraintId AddCouplerConstraint (const Joint< T > &joint0, const Joint< T > &joint1, double gear_ratio, double offset=0.0)
 Defines a holonomic constraint between two single-dof joints joint0 and joint1 with positions q₀ and q₁, respectively, such that q₀ = ρ⋅q₁ + Δq, where ρ is the gear ratio and Δq is a fixed offset. More...
 
MultibodyConstraintId AddDistanceConstraint (const RigidBody< T > &body_A, const Vector3< double > &p_AP, const RigidBody< T > &body_B, const Vector3< double > &p_BQ, double distance, double stiffness=std::numeric_limits< double >::infinity(), double damping=0.0)
 Defines a distance constraint between a point P on a body A and a point Q on a body B. More...
 
MultibodyConstraintId AddBallConstraint (const RigidBody< T > &body_A, const Vector3< double > &p_AP, const RigidBody< T > &body_B, const std::optional< Vector3< double >> &p_BQ={})
 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. More...
 
MultibodyConstraintId AddWeldConstraint (const RigidBody< T > &body_A, const math::RigidTransform< double > &X_AP, const RigidBody< T > &body_B, const math::RigidTransform< double > &X_BQ)
 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. More...
 
void RemoveConstraint (MultibodyConstraintId id)
 Removes the constraint id from the plant. More...
 
Geometry

The following geometry methods provide a convenient means for associating geometries with bodies. Ultimately, the geometries are owned by SceneGraph. These methods do the work of registering the requested geometries with SceneGraph and maintaining a mapping between the body and the registered data. Particularly, SceneGraph knows nothing about the concepts inherent in the MultibodyPlant. These methods account for those differences as documented below.

Geometry registration with roles

Geometries can be associated with bodies via the RegisterFooGeometry family of methods. In SceneGraph, geometries have roles. The RegisterCollisionGeometry() methods register geometry with SceneGraph and assign it the proximity role. The RegisterVisualGeometry() methods do the same, but assign the illustration role.

All geometry registration methods return a geometry::GeometryId GeometryId. This is how SceneGraph refers to the geometries. The properties of an individual geometry can be accessed with its id and geometry::SceneGraphInspector and geometry::QueryObject (for its state-dependent pose in world).

Body frames and SceneGraph frames

The first time a geometry registration method is called on a particular body, that body's frame B is registered with SceneGraph. As SceneGraph knows nothing about bodies, in the SceneGraph domain, the frame is simply notated as F; this is merely an alias for the body frame. Thus, the pose of the geometry G in the SceneGraph frame F is the same as the pose of the geometry in the body frame B; X_FG = X_BG.

The model instance index of the body is passed to the SceneGraph frame as its "frame group". This can be retrieved from the geometry::SceneGraphInspector::GetFrameGroup(FrameId) method.

Given a GeometryId, SceneGraph cannot report what body it is affixed to. It can only report the SceneGraph alias frame F. But the following idiom can report the body:

const MultibodyPlant<T>& plant = ...;
const SceneGraphInspector<T>& inspector = ...;
const GeometryId g_id = id_from_some_query;
const FrameId f_id = inspector.GetFrameId(g_id);
const RigidBody<T>* body = plant.GetBodyFromFrameId(f_id);

See documentation of geometry::SceneGraphInspector on where to get an inspector.

In MultibodyPlant, frame names only have to be unique in a single model instance. However, SceneGraph knows nothing of model instances. So, to generate unique names for the corresponding frames in SceneGraph, when MultibodyPlant registers the corresponding SceneGraph frame, it is named with a "scoped name". This is a concatenation of [model instance name]::[body name]. Searching for a frame with just the name body name will fail. (See RigidBody::name() and GetModelInstanceName() for those values.)

geometry::SourceId RegisterAsSourceForSceneGraph (geometry::SceneGraph< T > *scene_graph)
 Registers this plant to serve as a source for an instance of SceneGraph. More...
 
geometry::GeometryId RegisterVisualGeometry (const RigidBody< T > &body, const math::RigidTransform< double > &X_BG, const geometry::Shape &shape, const std::string &name, const geometry::IllustrationProperties &properties)
 Registers geometry in a SceneGraph with a given geometry::Shape to be used for visualization of a given body. More...
 
geometry::GeometryId RegisterVisualGeometry (const RigidBody< T > &body, const math::RigidTransform< double > &X_BG, const geometry::Shape &shape, const std::string &name, const Vector4< double > &diffuse_color)
 Overload for visual geometry registration; it converts the diffuse_color (RGBA with values in the range [0, 1]) into a geometry::DrakeVisualizer-compatible set of geometry::IllustrationProperties. More...
 
geometry::GeometryId RegisterVisualGeometry (const RigidBody< T > &body, const math::RigidTransform< double > &X_BG, const geometry::Shape &shape, const std::string &name)
 Overload for visual geometry registration; it relies on the downstream geometry::IllustrationProperties consumer to provide default parameter values (see Geometry Queries and Roles for details). More...
 
const std::vector< geometry::GeometryId > & GetVisualGeometriesForBody (const RigidBody< T > &body) const
 Returns an array of GeometryId's identifying the different visual geometries for body previously registered with a SceneGraph. More...
 
geometry::GeometryId RegisterCollisionGeometry (const RigidBody< T > &body, const math::RigidTransform< double > &X_BG, const geometry::Shape &shape, const std::string &name, geometry::ProximityProperties properties)
 Registers geometry in a SceneGraph with a given geometry::Shape to be used for the contact modeling of a given body. More...
 
geometry::GeometryId RegisterCollisionGeometry (const RigidBody< T > &body, const math::RigidTransform< double > &X_BG, const geometry::Shape &shape, const std::string &name, const CoulombFriction< double > &coulomb_friction)
 Overload which specifies a single property: coulomb_friction. More...
 
const std::vector< geometry::GeometryId > & GetCollisionGeometriesForBody (const RigidBody< T > &body) const
 Returns an array of GeometryId's identifying the different contact geometries for body previously registered with a SceneGraph. More...
 
void ExcludeCollisionGeometriesWithCollisionFilterGroupPair (const std::pair< std::string, geometry::GeometrySet > &collision_filter_group_a, const std::pair< std::string, geometry::GeometrySet > &collision_filter_group_b)
 Excludes the rigid collision geometries between two given collision filter groups. More...
 
geometry::GeometrySet CollectRegisteredGeometries (const std::vector< const RigidBody< T > * > &bodies) const
 For each of the provided bodies, collects up all geometries that have been registered to that body. More...
 
const RigidBody< T > * GetBodyFromFrameId (geometry::FrameId frame_id) const
 Given a geometry frame identifier, returns a pointer to the body associated with that id (nullptr if there is no such body). More...
 
std::optional< geometry::FrameIdGetBodyFrameIdIfExists (BodyIndex body_index) const
 If the body with body_index belongs to the called plant, it returns the geometry::FrameId associated with it. More...
 
geometry::FrameId GetBodyFrameIdOrThrow (BodyIndex body_index) const
 If the body with body_index belongs to the called plant, it returns the geometry::FrameId associated with it. More...
 
const geometry::SceneGraphInspector< T > & EvalSceneGraphInspector (const systems::Context< T > &context) const
 Returns the inspector from the context for the SceneGraph associated with this plant, via this plant's "geometry_query" input port. More...
 
State accessors and mutators

The following state methods allow getting and setting the kinematic state variables [q; v], where q is the vector of generalized positions and v is the vector of generalized velocities. The state resides in a Context that is supplied as the first argument to every method.

Note
State vectors for the full system are returned as live references into the Context, not independent copies. In contrast, state vectors for individual model instances are returned as copies because the state associated with a model instance is generally not contiguous in a Context.

There are also utilities for accessing and mutating portions of state or actuation arrays corresponding to just a single model instance.

Eigen::VectorBlock< const VectorX< T > > GetPositionsAndVelocities (const systems::Context< T > &context) const
 Returns a const vector reference [q; v] to the generalized positions q and generalized velocities v in a given Context. More...
 
VectorX< T > GetPositionsAndVelocities (const systems::Context< T > &context, ModelInstanceIndex model_instance) const
 Returns a vector [q; v] containing the generalized positions q and generalized velocities v of a specified model instance in a given Context. More...
 
void GetPositionsAndVelocities (const systems::Context< T > &context, ModelInstanceIndex model_instance, EigenPtr< VectorX< T >> qv_out) const
 (Advanced) Populates output vector qv_out representing the generalized positions q and generalized velocities v of a specified model instance in a given Context. More...
 
void SetPositionsAndVelocities (systems::Context< T > *context, const Eigen::Ref< const VectorX< T >> &q_v) const
 Sets generalized positions q and generalized velocities v in a given Context from a given vector [q; v]. More...
 
void SetPositionsAndVelocities (systems::Context< T > *context, ModelInstanceIndex model_instance, const Eigen::Ref< const VectorX< T >> &q_v) const
 Sets generalized positions q and generalized velocities v from a given vector [q; v] for a specified model instance in a given Context. More...
 
Eigen::VectorBlock< const VectorX< T > > GetPositions (const systems::Context< T > &context) const
 Returns a const vector reference to the vector of generalized positions q in a given Context. More...
 
VectorX< T > GetPositions (const systems::Context< T > &context, ModelInstanceIndex model_instance) const
 Returns a vector containing the generalized positions q of a specified model instance in a given Context. More...
 
void GetPositions (const systems::Context< T > &context, ModelInstanceIndex model_instance, EigenPtr< VectorX< T >> q_out) const
 (Advanced) Populates output vector q_out with the generalized positions q of a specified model instance in a given Context. More...
 
void SetPositions (systems::Context< T > *context, const Eigen::Ref< const VectorX< T >> &q) const
 Sets the generalized positions q in a given Context from a given vector. More...
 
void SetPositions (systems::Context< T > *context, ModelInstanceIndex model_instance, const Eigen::Ref< const VectorX< T >> &q_instance) const
 Sets the generalized positions q for a particular model instance in a given Context from a given vector. More...
 
void SetPositions (const systems::Context< T > &context, systems::State< T > *state, ModelInstanceIndex model_instance, const Eigen::Ref< const VectorX< T >> &q_instance) const
 (Advanced) Sets the generalized positions q for a particular model instance in a given State from a given vector. More...
 
VectorX< T > GetDefaultPositions () const
 Gets the default positions for the plant, which can be changed via SetDefaultPositions(). More...
 
VectorX< T > GetDefaultPositions (ModelInstanceIndex model_instance) const
 Gets the default positions for the plant for a given model instance, which can be changed via SetDefaultPositions(). More...
 
void SetDefaultPositions (const Eigen::Ref< const Eigen::VectorXd > &q)
 Sets the default positions for the plant. More...
 
void SetDefaultPositions (ModelInstanceIndex model_instance, const Eigen::Ref< const Eigen::VectorXd > &q_instance)
 Sets the default positions for the model instance. More...
 
Eigen::VectorBlock< const VectorX< T > > GetVelocities (const systems::Context< T > &context) const
 Returns a const vector reference to the generalized velocities v in a given Context. More...
 
VectorX< T > GetVelocities (const systems::Context< T > &context, ModelInstanceIndex model_instance) const
 Returns a vector containing the generalized velocities v of a specified model instance in a given Context. More...
 
void GetVelocities (const systems::Context< T > &context, ModelInstanceIndex model_instance, EigenPtr< VectorX< T >> v_out) const
 (Advanced) Populates output vector v_out with the generalized velocities v of a specified model instance in a given Context. More...
 
void SetVelocities (systems::Context< T > *context, const Eigen::Ref< const VectorX< T >> &v) const
 Sets the generalized velocities v in a given Context from a given vector. More...
 
void SetVelocities (systems::Context< T > *context, ModelInstanceIndex model_instance, const Eigen::Ref< const VectorX< T >> &v_instance) const
 Sets the generalized velocities v for a particular model instance in a given Context from a given vector. More...
 
void SetVelocities (const systems::Context< T > &context, systems::State< T > *state, ModelInstanceIndex model_instance, const Eigen::Ref< const VectorX< T >> &v_instance) const
 (Advanced) Sets the generalized velocities v for a particular model instance in a given State from a given vector. More...
 
void SetDefaultState (const systems::Context< T > &context, systems::State< T > *state) const override
 Sets state according to defaults set by the user for joints (e.g. More...
 
void SetRandomState (const systems::Context< T > &context, systems::State< T > *state, RandomGenerator *generator) const override
 Assigns random values to all elements of the state, by drawing samples independently for each joint/free body (coming soon: and then solving a mathematical program to "project" these samples onto the registered system constraints). More...
 
std::vector< std::string > GetPositionNames (bool add_model_instance_prefix=true, bool always_add_suffix=true) const
 Returns a list of string names corresponding to each element of the position vector. More...
 
std::vector< std::string > GetPositionNames (ModelInstanceIndex model_instance, bool add_model_instance_prefix=false, bool always_add_suffix=true) const
 Returns a list of string names corresponding to each element of the position vector. More...
 
std::vector< std::string > GetVelocityNames (bool add_model_instance_prefix=true, bool always_add_suffix=true) const
 Returns a list of string names corresponding to each element of the velocity vector. More...
 
std::vector< std::string > GetVelocityNames (ModelInstanceIndex model_instance, bool add_model_instance_prefix=false, bool always_add_suffix=true) const
 Returns a list of string names corresponding to each element of the velocity vector. More...
 
std::vector< std::string > GetStateNames (bool add_model_instance_prefix=true) const
 Returns a list of string names corresponding to each element of the multibody state vector. More...
 
std::vector< std::string > GetStateNames (ModelInstanceIndex model_instance, bool add_model_instance_prefix=false) const
 Returns a list of string names corresponding to each element of the multibody state vector. More...
 
std::vector< std::string > GetActuatorNames (bool add_model_instance_prefix=true) const
 Returns a list of string names corresponding to each element of the actuation vector. More...
 
std::vector< std::string > GetActuatorNames (ModelInstanceIndex model_instance, bool add_model_instance_prefix=false) const
 Returns a list of string names corresponding to each element of the actuation vector. More...
 
VectorX< T > GetActuationFromArray (ModelInstanceIndex model_instance, const Eigen::Ref< const VectorX< T >> &u) const
 Returns a vector of actuation values for model_instance from a vector u of actuation values for the entire plant model. More...
 
void SetActuationInArray (ModelInstanceIndex model_instance, const Eigen::Ref< const VectorX< T >> &u_instance, EigenPtr< VectorX< T >> u) const
 Given actuation values u_instance for the actuators in model_instance, this function updates the actuation vector u for the entire plant model to which this actuator belongs to. More...
 
VectorX< T > GetPositionsFromArray (ModelInstanceIndex model_instance, const Eigen::Ref< const VectorX< T >> &q) const
 Returns a vector of generalized positions for model_instance from a vector q_array of generalized positions for the entire model model. More...
 
void GetPositionsFromArray (ModelInstanceIndex model_instance, const Eigen::Ref< const VectorX< T >> &q, EigenPtr< VectorX< T >> q_out) const
 (Advanced) Populates output vector q_out and with the generalized positions for model_instance from a vector q of generalized positions for the entire model. More...
 
void SetPositionsInArray (ModelInstanceIndex model_instance, const Eigen::Ref< const VectorX< T >> &q_instance, EigenPtr< VectorX< T >> q) const
 Sets the vector of generalized positions for model_instance in q using q_instance, leaving all other elements in the array untouched. More...
 
VectorX< T > GetVelocitiesFromArray (ModelInstanceIndex model_instance, const Eigen::Ref< const VectorX< T >> &v) const
 Returns a vector of generalized velocities for model_instance from a vector v of generalized velocities for the entire MultibodyPlant model. More...
 
void GetVelocitiesFromArray (ModelInstanceIndex model_instance, const Eigen::Ref< const VectorX< T >> &v, EigenPtr< VectorX< T >> v_out) const
 (Advanced) Populates output vector v_out with the generalized velocities for model_instance from a vector v of generalized velocities for the entire model. More...
 
void SetVelocitiesInArray (ModelInstanceIndex model_instance, const Eigen::Ref< const VectorX< T >> &v_instance, EigenPtr< VectorX< T >> v) const
 Sets the vector of generalized velocities for model_instance in v using v_instance, leaving all other elements in the array untouched. More...
 
Working with free bodies

A MultibodyPlant user adds sets of RigidBody and Joint objects to this plant to build a physical representation of a mechanical model. At Finalize(), MultibodyPlant builds a mathematical representation of such system, consisting of a tree representation. In this representation each body is assigned a Mobilizer, which grants a certain number of degrees of freedom in accordance to the physical specification. In this regard, the modeling representation can be seen as a forest of tree structures each of which contains a single body at the root of the tree. The root body's parent is always the world body. If a body has six degrees of freedom with respect to its parent, it is called a "free body". If it also the root of a tree, such that its parent is the world body, it is a "floating base" body. Free bodies that are added to the plant without specifying a joint become floating base bodies after finalization. It is possible (and sometimes recommended) to explicitly create a 6-dof joint between two bodies. The child body would be free, because it has six degrees of freedom, but it would not be a "floating base body" because its parent is not the world. The effects of the various APIs below depend on the distinction between "free" and "floating base bodies". Read carefully. A user can request the set of all floating base bodies with a call to GetFloatingBaseBodies(). Alternatively, a user can query whether a RigidBody is a floating base body or not with RigidBody::is_floating(). For many applications, a user might need to work with indices in the multibody state vector. For such applications, RigidBody::floating_positions_start() and RigidBody::floating_velocities_start_in_v() offer the additional level of introspection needed. These APIs only apply to floating base bodies and not 6-dof free bodies generally.

It is sometimes convenient for users to perform operations on RigidBodies uniformly through the APIs of the Joint class. For that reason the plant implicitly constructs a 6-dof joint, QuaternionFloatingJoint, between the body and the world for all bodies otherwise without declared inboard joints at the time of Finalize(). Using Joint APIs to affect a free body (setting state, changing parameters, etc.) has the same effect as using the free body APIs below. Each implicitly created joint is named the same as the free body, as reported by RigidBody::name(). In the rare case that there is already some (unrelated) joint with that name, we'll prepend underscores to the name until it is unique.

The APIs below provide affordances for working with free bodies without explicitly accessing the corresponding floating joint. The pose of a free body (as it is represented in MultibodyPlant's state) is always the pose of the free body relative to its parent frame. That is not necessarily the body's pose in the world (unless the parent frame is the world frame).

std::unordered_set< BodyIndexGetFloatingBaseBodies () const
 Returns the set of body indices corresponding to the floating base bodies in the model, in no particular order. More...
 
math::RigidTransform< T > GetFreeBodyPose (const systems::Context< T > &context, const RigidBody< T > &body) const
 Gets the pose of a given body in the parent frame P. More...
 
void SetFreeBodyPose (systems::Context< T > *context, const RigidBody< T > &body, const math::RigidTransform< T > &X_PB) const
 Sets context to store the pose X_PB of a given body B in the parent frame P. More...
 
void SetFreeBodyPose (const systems::Context< T > &context, systems::State< T > *state, const RigidBody< T > &body, const math::RigidTransform< T > &X_PB) const
 Sets state to store the pose X_PB of a given body B in its parent frame P, for a given context of this model. More...
 
void SetDefaultFreeBodyPose (const RigidBody< T > &body, const math::RigidTransform< double > &X_PB)
 Sets the default pose of body. More...
 
math::RigidTransform< doubleGetDefaultFreeBodyPose (const RigidBody< T > &body) const
 Gets the default pose of body as set by SetDefaultFreeBodyPose(). More...
 
void SetFreeBodySpatialVelocity (systems::Context< T > *context, const RigidBody< T > &body, const SpatialVelocity< T > &V_PB) const
 Sets context to store the spatial velocity V_PB of a given body B in its parent frame P. More...
 
void SetFreeBodySpatialVelocity (const systems::Context< T > &context, systems::State< T > *state, const RigidBody< T > &body, const SpatialVelocity< T > &V_PB) const
 Sets state to store the spatial velocity V_PB of a given body B in its parent frame P, for a given context of this model. More...
 
void SetFreeBodyRandomTranslationDistribution (const RigidBody< T > &body, const Vector3< symbolic::Expression > &translation)
 Sets the distribution used by SetRandomState() to populate the free body's x-y-z translation with respect to its parent frame P. More...
 
void SetFreeBodyRandomRotationDistribution (const RigidBody< T > &body, const Eigen::Quaternion< symbolic::Expression > &rotation)
 Sets the distribution used by SetRandomState() to populate the free body's rotation with respect to its parent frame. More...
 
void SetFreeBodyRandomRotationDistributionToUniform (const RigidBody< T > &body)
 Sets the distribution used by SetRandomState() to populate the free body's rotation with respect to its parent frame using uniformly random rotations. More...
 
void SetFreeBodyPoseInWorldFrame (systems::Context< T > *context, const RigidBody< T > &body, const math::RigidTransform< T > &X_WB) const
 Sets context to store the pose X_WB of a given floating base body B in the world frame W. More...
 
void SetFreeBodyPoseInAnchoredFrame (systems::Context< T > *context, const Frame< T > &frame_F, const RigidBody< T > &body, const math::RigidTransform< T > &X_FB) const
 Updates context to store the pose X_FB of a given body B in a frame F. More...
 
const RigidBody< T > & GetUniqueFreeBaseBodyOrThrow (ModelInstanceIndex model_instance) const
 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. More...
 
bool HasUniqueFreeBaseBody (ModelInstanceIndex model_instance) const
 Return true if there exists a unique base body in the model given by model_instance and that unique base body is free. More...
 
Kinematic and dynamic computations

These methods return kinematic results for the state supplied in the given Context. Methods whose names being with Eval return a reference into the Context's cache, performing computation first only if the relevant state has changed. Methods beginning with Calc perform computation unconditionally and return a result without updating the cache.

const math::RigidTransform< T > & EvalBodyPoseInWorld (const systems::Context< T > &context, const RigidBody< T > &body_B) const
 Evaluate the pose X_WB of a body B in the world frame W. More...
 
const SpatialVelocity< T > & EvalBodySpatialVelocityInWorld (const systems::Context< T > &context, const RigidBody< T > &body_B) const
 Evaluates V_WB, body B's spatial velocity in the world frame W. More...
 
const SpatialAcceleration< T > & EvalBodySpatialAccelerationInWorld (const systems::Context< T > &context, const RigidBody< T > &body_B) const
 Evaluates A_WB, body B's spatial acceleration in the world frame W. More...
 
math::RigidTransform< T > CalcRelativeTransform (const systems::Context< T > &context, const Frame< T > &frame_A, const Frame< T > &frame_B) const
 Calculates the rigid transform (pose) X_AB relating frame A and frame B. More...
 
math::RotationMatrix< T > CalcRelativeRotationMatrix (const systems::Context< T > &context, const Frame< T > &frame_A, const Frame< T > &frame_B) const
 Calculates the rotation matrix R_AB relating frame A and frame B. More...
 
void CalcPointsPositions (const systems::Context< T > &context, const Frame< T > &frame_B, const Eigen::Ref< const MatrixX< T >> &p_BQi, const Frame< T > &frame_A, EigenPtr< MatrixX< T >> p_AQi) const
 Given the positions p_BQi for a set of points Qi measured and expressed in a frame B, this method computes the positions p_AQi(q) of each point Qi in the set as measured and expressed in another frame A, as a function of the generalized positions q of the model. More...
 
CalcTotalMass (const systems::Context< T > &context) const
 Calculates the total mass of all bodies in this MultibodyPlant. More...
 
CalcTotalMass (const systems::Context< T > &context, const std::vector< ModelInstanceIndex > &model_instances) const
 Calculates the total mass of all bodies contained in model_instances. More...
 
Vector3< T > CalcCenterOfMassPositionInWorld (const systems::Context< T > &context) const
 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. More...
 
Vector3< T > CalcCenterOfMassPositionInWorld (const systems::Context< T > &context, const std::vector< ModelInstanceIndex > &model_instances) const
 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. More...
 
SpatialInertia< T > CalcSpatialInertia (const systems::Context< T > &context, const Frame< T > &frame_F, const std::vector< BodyIndex > &body_indexes) const
 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. More...
 
Vector3< T > CalcCenterOfMassTranslationalVelocityInWorld (const systems::Context< T > &context) const
 Calculates system center of mass translational velocity in world frame W. More...
 
Vector3< T > CalcCenterOfMassTranslationalAccelerationInWorld (const systems::Context< T > &context) const
 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. More...
 
Vector3< T > CalcCenterOfMassTranslationalAccelerationInWorld (const systems::Context< T > &context, const std::vector< ModelInstanceIndex > &model_instances) const
 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. More...
 
Vector3< T > CalcCenterOfMassTranslationalVelocityInWorld (const systems::Context< T > &context, const std::vector< ModelInstanceIndex > &model_instances) const
 Calculates system center of mass translational velocity in world frame W. More...
 
SpatialMomentum< T > CalcSpatialMomentumInWorldAboutPoint (const systems::Context< T > &context, const Vector3< T > &p_WoP_W) const
 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. More...
 
SpatialMomentum< T > CalcSpatialMomentumInWorldAboutPoint (const systems::Context< T > &context, const std::vector< ModelInstanceIndex > &model_instances, const Vector3< T > &p_WoP_W) const
 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. More...
 
void CalcSpatialAccelerationsFromVdot (const systems::Context< T > &context, const VectorX< T > &known_vdot, std::vector< SpatialAcceleration< T >> *A_WB_array) const
 Given the state of this model in context and a known vector of generalized accelerations known_vdot, this method computes the spatial acceleration A_WB for each body as measured and expressed in the world frame W. More...
 
VectorX< T > CalcInverseDynamics (const systems::Context< T > &context, const VectorX< T > &known_vdot, const MultibodyForces< T > &external_forces) const
 Given the state of this model in context and a known vector of generalized accelerations vdot, this method computes the set of generalized forces tau that would need to be applied in order to attain the specified generalized accelerations. More...
 
void CalcImplicitTimeDerivativesResidual (const systems::Context< T > &context, const systems::ContinuousState< T > &proposed_derivatives, EigenPtr< VectorX< T >> residual) const
 MultibodyPlant implements the systems::System::CalcImplicitTimeDerivativesResidual method when the plant is modeled as a continuous-time system, returning one residual for each multibody state. More...
 
void CalcForceElementsContribution (const systems::Context< T > &context, MultibodyForces< T > *forces) const
 Computes the combined force contribution of ForceElement objects in the model. More...
 
VectorX< T > CalcGravityGeneralizedForces (const systems::Context< T > &context) const
 Computes the generalized forces tau_g(q) due to gravity as a function of the generalized positions q stored in the input context. More...
 
void CalcGeneralizedForces (const systems::Context< T > &context, const MultibodyForces< T > &forces, VectorX< T > *generalized_forces) const
 Computes the generalized forces result of a set of MultibodyForces applied to this model. More...
 
bool IsVelocityEqualToQDot () const
 Returns true iff the generalized velocity v is exactly the time derivative q̇ of the generalized coordinates q. More...
 
void MapVelocityToQDot (const systems::Context< T > &context, const Eigen::Ref< const VectorX< T >> &v, EigenPtr< VectorX< T >> qdot) const
 Transforms generalized velocities v to time derivatives qdot of the generalized positions vector q (stored in context). More...
 
void MapQDotToVelocity (const systems::Context< T > &context, const Eigen::Ref< const VectorX< T >> &qdot, EigenPtr< VectorX< T >> v) const
 Transforms the time derivative qdot of the generalized positions vector q (stored in context) to generalized velocities v. More...
 
Eigen::SparseMatrix< T > MakeVelocityToQDotMap (const systems::Context< T > &context) const
 Returns the matrix N(q), which maps q̇ = N(q)⋅v, as described in MapVelocityToQDot(). More...
 
Eigen::SparseMatrix< T > MakeQDotToVelocityMap (const systems::Context< T > &context) const
 Returns the matrix N⁺(q), which maps v = N⁺(q)⋅q̇, as described in MapQDotToVelocity(). More...
 
System matrix computations

Methods in this section compute and return various matrices that appear in the system equations of motion. For better performance, prefer to use direct computations where available rather than work with explicit matrices. See Kinematic and dynamics computations for available computations. For example, you can obtain the mass matrix, Coriolis, centripetal, and gyroscopic "bias" terms, and a variety of Jacobian and actuation matrices.

void CalcMassMatrixViaInverseDynamics (const systems::Context< T > &context, EigenPtr< MatrixX< T >> M) const
 Computes the mass matrix M(q) of the model using a slow method (inverse dynamics). More...
 
void CalcMassMatrix (const systems::Context< T > &context, EigenPtr< MatrixX< T >> M) const
 Efficiently computes the mass matrix M(q) of the model. More...
 
MatrixX< doubleMakeStateSelectorMatrix (const std::vector< JointIndex > &user_to_joint_index_map) const
 This method allows users to map the state of this model, x, into a vector of selected state xₛ with a given preferred ordering. More...
 
MatrixX< doubleMakeActuatorSelectorMatrix (const std::vector< JointActuatorIndex > &user_to_actuator_index_map) const
 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 for this full model. More...
 
MatrixX< T > MakeActuationMatrix () const
 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 size nv x nu with nu equal to num_actuated_dofs() and nv equal to num_velocities(). More...
 
Eigen::SparseMatrix< doubleMakeActuationMatrixPseudoinverse () const
 Creates the pseudoinverse of the actuation matrix B directly (without requiring an explicit inverse calculation). More...
 
MatrixX< doubleMakeActuatorSelectorMatrix (const std::vector< JointIndex > &user_to_joint_index_map) const
 Alternative signature to build an actuation selector matrix Su such that u = 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 by user_to_joint_index_map. More...
 
Jacobian functions

Herein, a Jacobian is a matrix that contains the partial derivatives of a vector with respect to a list of scalars. The vector may be a position vector, translational velocity, angular velocity, or spatial velocity and the scalars may be the system's generalized positions q or "speeds" 𝑠 where 𝑠 is either q̇ (time-derivative of generalized positions) or v (generalized velocities).

JAq_p_PQ denotes the Jacobian in a frame A of the position vector from point P to point Q with respect to the generalized positions q. It is calculated with CalcJacobianPositionVector().

J𝑠_w_AB denotes the angular velocity Jacobian in a frame A of a frame B with respect to "speeds" 𝑠. It is calculated with CalcJacobianAngularVelocity().

J𝑠_V_ABp denotes the spatial velocity Jacobian in a frame A of a point Bp of frame B with respect to "speeds" 𝑠. It is calculated with CalcJacobianSpatialVelocity().

J𝑠_v_ABp denotes the translational velocity Jacobian in a frame A of a point Bp of frame B with respect to "speeds" 𝑠. It is calculated with CalcJacobianTranslationalVelocity().

J𝑠_v_AScm_E denotes the translational velocity Jacobian in a frame A of a point Scm with respect to "speeds" 𝑠, where point Scm is the center of mass of a system S. It is calculated with CalcJacobianCenterOfMassTranslationalVelocity()

void CalcJacobianSpatialVelocity (const systems::Context< T > &context, JacobianWrtVariable with_respect_to, const Frame< T > &frame_B, const Eigen::Ref< const Vector3< T >> &p_BoBp_B, const Frame< T > &frame_A, const Frame< T > &frame_E, EigenPtr< MatrixX< T >> Js_V_ABp_E) const
 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" 𝑠. More...
 
void CalcJacobianAngularVelocity (const systems::Context< T > &context, const JacobianWrtVariable with_respect_to, const Frame< T > &frame_B, const Frame< T > &frame_A, const Frame< T > &frame_E, EigenPtr< Matrix3X< T >> Js_w_AB_E) const
 Calculates J𝑠_w_AB, a frame B's angular velocity Jacobian in a frame A with respect to "speeds" 𝑠. More...
 
void CalcJacobianTranslationalVelocity (const systems::Context< T > &context, JacobianWrtVariable with_respect_to, const Frame< T > &frame_B, const Eigen::Ref< const Matrix3X< T >> &p_BoBi_B, const Frame< T > &frame_A, const Frame< T > &frame_E, EigenPtr< MatrixX< T >> Js_v_ABi_E) const
 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" 𝑠. More...
 
void CalcJacobianPositionVector (const systems::Context< T > &context, const Frame< T > &frame_B, const Eigen::Ref< const Matrix3X< T >> &p_BoBi_B, const Frame< T > &frame_A, const Frame< T > &frame_E, EigenPtr< MatrixX< T >> Jq_p_AoBi_E) const
 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₁ ... More...
 
void CalcJacobianCenterOfMassTranslationalVelocity (const systems::Context< T > &context, JacobianWrtVariable with_respect_to, const Frame< T > &frame_A, const Frame< T > &frame_E, EigenPtr< Matrix3X< T >> Js_v_ACcm_E) const
 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. More...
 
void CalcJacobianCenterOfMassTranslationalVelocity (const systems::Context< T > &context, const std::vector< ModelInstanceIndex > &model_instances, JacobianWrtVariable with_respect_to, const Frame< T > &frame_A, const Frame< T > &frame_E, EigenPtr< Matrix3X< T >> Js_v_ACcm_E) const
 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. More...
 
Bias acceleration functions

The name a𝑠Bias_AP denotes a point P's bias translational acceleration with respect to "speeds" 𝑠 measured in a frame A, where 𝑠 is either q̇ (time-derivatives of generalized positions) or v (generalized velocities). a𝑠Bias_AP includes the terms in a_AP (P's translational acceleration in A) that depend on q, q̇, v, but not terms that depend on 𝑠̇, i.e., a𝑠Bias_AP = a_AP when 𝑠̇ = 0. The proof below starts with v_AP (point P's translational velocity in frame A) written in terms of J𝑠_v_AP (point P's translational velocity Jacobian in frame A for s).

   v_AP = J𝑠_v_AP ⋅ 𝑠         which upon vector differentiation in A gives
   a_AP = Ĵ𝑠_v_AP ⋅ 𝑠  +  J𝑠_v_AP ⋅ 𝑠̇                 setting 𝑠̇ = 0, gives
   a𝑠Bias_AP = Ĵ𝑠_v_AP ⋅ 𝑠                               is quadratic in s.
 

Note: Since Ĵ𝑠_v_AP (the time-derivative of J𝑠_v_AP in frame A) is linear in s, a𝑠Bias_AP = Ĵ𝑠_v_AP ⋅ 𝑠 is quadratic in 𝑠.

Similarly, A𝑠Bias_AB denotes a frame B's bias spatial acceleration with respect to speeds 𝑠 measured in frame A. It can be written in terms of the time-derivative of J𝑠_V_AB (B's spatial velocity Jacobian in frame A for speeds 𝑠) as

   A𝑠Bias_AB = Ĵ𝑠_V_AB ⋅ 𝑠                       is quadratic in s. 
See also
CalcJacobianSpatialVelocity() for details on J𝑠_V_AB.
void CalcBiasTerm (const systems::Context< T > &context, EigenPtr< VectorX< T >> Cv) const
 Computes the bias term C(q, v) v containing Coriolis, centripetal, and gyroscopic effects in the multibody equations of motion: More...
 
Matrix3X< T > CalcBiasTranslationalAcceleration (const systems::Context< T > &context, JacobianWrtVariable with_respect_to, const Frame< T > &frame_B, const Eigen::Ref< const Matrix3X< T >> &p_BoBi_B, const Frame< T > &frame_A, const Frame< T > &frame_E) const
 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. More...
 
SpatialAcceleration< T > CalcBiasSpatialAcceleration (const systems::Context< T > &context, JacobianWrtVariable with_respect_to, const Frame< T > &frame_B, const Eigen::Ref< const Vector3< T >> &p_BoBp_B, const Frame< T > &frame_A, const Frame< T > &frame_E) const
 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. More...
 
Vector3< T > CalcBiasCenterOfMassTranslationalAcceleration (const systems::Context< T > &context, JacobianWrtVariable with_respect_to, const Frame< T > &frame_A, const Frame< T > &frame_E) const
 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. More...
 
Vector3< T > CalcBiasCenterOfMassTranslationalAcceleration (const systems::Context< T > &context, const std::vector< ModelInstanceIndex > &model_instances, JacobianWrtVariable with_respect_to, const Frame< T > &frame_A, const Frame< T > &frame_E) const
 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. More...
 
Introspection

These methods allow a user to query whether a given multibody element is part of this plant's model. These queries can be performed at any time during the lifetime of a MultibodyPlant model, i.e. there is no restriction on whether they must be called before or after Finalize(). These queries can be performed while new multibody elements are being added to the model. These methods allow a user to retrieve a reference to a multibody element by its name. An exception is thrown if there is no element with the requested name.

If the named element is present in more than one model instance and a model instance is not explicitly specified, std::logic_error is thrown.

double time_step () const
 The time step (or period) used to model this plant as a discrete system with periodic updates. More...
 
bool is_finalized () const
 Returns true if this MultibodyPlant was finalized with a call to Finalize(). More...
 
bool has_sampled_output_ports () const
 (Advanced) If this plant is continuous (i.e., is_discrete() is false), returns false. More...
 
const RigidBody< T > & world_body () const
 Returns a constant reference to the world body. More...
 
const RigidBodyFrame< T > & world_frame () const
 Returns a constant reference to the world frame. More...
 
int num_bodies () const
 Returns the number of RigidBody elements in the model, including the "world" RigidBody, which is always part of the model. More...
 
const RigidBody< T > & get_body (BodyIndex body_index) const
 Returns a constant reference to the body with unique index body_index. More...
 
bool IsAnchored (const RigidBody< T > &body) const
 Returns true if body is anchored (i.e. More...
 
bool HasBodyNamed (std::string_view name) const
 
int NumBodiesWithName (std::string_view name) const
 
bool HasBodyNamed (std::string_view name, ModelInstanceIndex model_instance) const
 
const RigidBody< T > & GetBodyByName (std::string_view name) const
 Returns a constant reference to a body that is identified by the string name in this MultibodyPlant. More...
 
const RigidBody< T > & GetBodyByName (std::string_view name, ModelInstanceIndex model_instance) const
 Returns a constant reference to the body that is uniquely identified by the string name and model_instance in this MultibodyPlant. More...
 
std::vector< BodyIndexGetBodyIndices (ModelInstanceIndex model_instance) const
 Returns a list of body indices associated with model_instance. More...
 
const RigidBody< T > & GetRigidBodyByName (std::string_view name) const
 Returns a constant reference to a rigid body that is identified by the string name in this model. More...
 
const RigidBody< T > & GetRigidBodyByName (std::string_view name, ModelInstanceIndex model_instance) const
 Returns a constant reference to the rigid body that is uniquely identified by the string name in model_instance. More...
 
std::vector< const RigidBody< T > * > GetBodiesWeldedTo (const RigidBody< T > &body) const
 Returns all bodies that are transitively welded, or rigidly affixed, to body, per these two definitions: More...
 
std::vector< BodyIndexGetBodiesKinematicallyAffectedBy (const std::vector< JointIndex > &joint_indexes) const
 Returns all bodies whose kinematics are transitively affected by the given vector of Joints. More...
 
int num_joints () const
 Returns the number of joints in the model. More...
 
bool has_joint (JointIndex joint_index) const
 Returns true if plant has a joint with unique index joint_index. More...
 
const Joint< T > & get_joint (JointIndex joint_index) const
 Returns a constant reference to the joint with unique index joint_index. More...
 
bool HasJointNamed (std::string_view name) const
 
bool HasJointNamed (std::string_view name, ModelInstanceIndex model_instance) const
 
Joint< T > & get_mutable_joint (JointIndex joint_index)
 Returns a mutable reference to the joint with unique index joint_index. More...
 
const std::vector< JointIndex > & GetJointIndices () const
 Returns a list of all joint indices. More...
 
std::vector< JointIndexGetJointIndices (ModelInstanceIndex model_instance) const
 Returns a list of joint indices associated with model_instance. More...
 
const std::vector< JointActuatorIndex > & GetJointActuatorIndices () const
 Returns a list of all joint actuator indices. More...
 
std::vector< JointActuatorIndexGetJointActuatorIndices (ModelInstanceIndex model_instance) const
 Returns a list of joint actuator indices associated with model_instance. More...
 
std::vector< JointIndexGetActuatedJointIndices (ModelInstanceIndex model_instance) const
 Returns a list of actuated joint indices associated with model_instance. More...
 
template<template< typename > class JointType = Joint>
const JointType< T > & GetJointByName (std::string_view name, std::optional< ModelInstanceIndex > model_instance=std::nullopt) const
 Returns a constant reference to a joint that is identified by the string name in this MultibodyPlant. More...
 
template<template< typename > class JointType = Joint>
JointType< T > & GetMutableJointByName (std::string_view name, std::optional< ModelInstanceIndex > model_instance=std::nullopt)
 A version of GetJointByName that returns a mutable reference. More...
 
int num_frames () const
 Returns the number of Frame objects in this model. More...
 
const Frame< T > & get_frame (FrameIndex frame_index) const
 Returns a constant reference to the frame with unique index frame_index. More...
 
bool HasFrameNamed (std::string_view name) const
 
bool HasFrameNamed (std::string_view name, ModelInstanceIndex model_instance) const
 
const Frame< T > & GetFrameByName (std::string_view name) const
 Returns a constant reference to a frame that is identified by the string name in this model. More...
 
const Frame< T > & GetFrameByName (std::string_view name, ModelInstanceIndex model_instance) const
 Returns a constant reference to the frame that is uniquely identified by the string name in model_instance. More...
 
std::vector< FrameIndexGetFrameIndices (ModelInstanceIndex model_instance) const
 Returns a list of frame indices associated with model_instance. More...
 
int num_actuators () const
 Returns the number of joint actuators in the model. More...
 
int num_actuators (ModelInstanceIndex model_instance) const
 Returns the number of actuators for a specific model instance. More...
 
int num_actuated_dofs () const
 Returns the total number of actuated degrees of freedom. More...
 
int num_actuated_dofs (ModelInstanceIndex model_instance) const
 Returns the total number of actuated degrees of freedom for a specific model instance. More...
 
bool has_joint_actuator (JointActuatorIndex actuator_index) const
 Returns true if plant has a joint actuator with unique index actuator_index. More...
 
const JointActuator< T > & get_joint_actuator (JointActuatorIndex actuator_index) const
 Returns a constant reference to the joint actuator with unique index actuator_index. More...
 
JointActuator< T > & get_mutable_joint_actuator (JointActuatorIndex actuator_index)
 Returns a mutable reference to the joint actuator with unique index actuator_index. More...
 
bool HasJointActuatorNamed (std::string_view name) const
 
bool HasJointActuatorNamed (std::string_view name, ModelInstanceIndex model_instance) const
 
const JointActuator< T > & GetJointActuatorByName (std::string_view name) const
 Returns a constant reference to an actuator that is identified by the string name in this MultibodyPlant. More...
 
const JointActuator< T > & GetJointActuatorByName (std::string_view name, ModelInstanceIndex model_instance) const
 Returns a constant reference to the actuator that is uniquely identified by the string name and model_instance in this MultibodyPlant. More...
 
int num_force_elements () const
 Returns the number of ForceElement objects. More...
 
const ForceElement< T > & get_force_element (ForceElementIndex force_element_index) const
 Returns a constant reference to the force element with unique index force_element_index. More...
 
template<template< typename > class ForceElementType = ForceElement>
const ForceElementType< T > & GetForceElement (ForceElementIndex force_element_index) const
 Returns a constant reference to a force element identified by its unique index in this MultibodyPlant. More...
 
bool is_gravity_enabled (ModelInstanceIndex model_instance) const
 
void set_gravity_enabled (ModelInstanceIndex model_instance, bool is_enabled)
 Sets is_gravity_enabled() for model_instance to is_enabled. More...
 
const UniformGravityFieldElement< T > & gravity_field () const
 An accessor to the current gravity field. More...
 
UniformGravityFieldElement< T > & mutable_gravity_field ()
 A mutable accessor to the current gravity field. More...
 
int num_model_instances () const
 Returns the number of model instances in the model. More...
 
const std::string & GetModelInstanceName (ModelInstanceIndex model_instance) const
 Returns the name of a model_instance. More...
 
bool HasModelInstanceNamed (std::string_view name) const
 
ModelInstanceIndex GetModelInstanceByName (std::string_view name) const
 Returns the index to the model instance that is uniquely identified by the string name in this MultibodyPlant. More...
 
std::string GetTopologyGraphvizString () const
 Returns a Graphviz string describing the topology of this plant. More...
 
int num_positions () const
 Returns the size of the generalized position vector q for this model. More...
 
int num_positions (ModelInstanceIndex model_instance) const
 Returns the size of the generalized position vector qᵢ for model instance i. More...
 
int num_velocities () const
 Returns the size of the generalized velocity vector v for this model. More...
 
int num_velocities (ModelInstanceIndex model_instance) const
 Returns the size of the generalized velocity vector vᵢ for model instance i. More...
 
int num_multibody_states () const
 Returns the size of the multibody system state vector x = [q v]. More...
 
int num_multibody_states (ModelInstanceIndex model_instance) const
 Returns the size of the multibody system state vector xᵢ = [qᵢ vᵢ] for model instance i. More...
 
VectorX< doubleGetPositionLowerLimits () const
 Returns a vector of size num_positions() containing the lower position limits for every generalized position coordinate. More...
 
VectorX< doubleGetPositionUpperLimits () const
 Upper limit analog of GetPositionLowerLimits(), where any unbounded or unspecified limits will be +infinity. More...
 
VectorX< doubleGetVelocityLowerLimits () const
 Returns a vector of size num_velocities() containing the lower velocity limits for every generalized velocity coordinate. More...
 
VectorX< doubleGetVelocityUpperLimits () const
 Upper limit analog of GetVelocitysLowerLimits(), where any unbounded or unspecified limits will be +infinity. More...
 
VectorX< doubleGetAccelerationLowerLimits () const
 Returns a vector of size num_velocities() containing the lower acceleration limits for every generalized velocity coordinate. More...
 
VectorX< doubleGetAccelerationUpperLimits () const
 Upper limit analog of GetAccelerationsLowerLimits(), where any unbounded or unspecified limits will be +infinity. More...
 
VectorX< doubleGetEffortLowerLimits () const
 Returns a vector of size num_actuated_dofs() containing the lower effort limits for every actuator. More...
 
VectorX< doubleGetEffortUpperLimits () const
 Returns a vector of size num_actuated_dofs() containing the upper effort limits for every actuator. More...
 
ContactModel get_contact_model () const
 Returns the model used for contact. See documentation for ContactModel. More...
 
int num_visual_geometries () const
 Returns the number of geometries registered for visualization. More...
 
int num_collision_geometries () const
 Returns the number of geometries registered for contact modeling. More...
 
std::optional< geometry::SourceIdget_source_id () const
 Returns the unique id identifying this plant as a source for a SceneGraph. More...
 
bool geometry_source_is_registered () const
 Returns true if this MultibodyPlant was registered with a SceneGraph. More...
 
geometry::SceneGraph< T > * GetMutableSceneGraphPreFinalize ()
 (Internal use only) Returns a mutable pointer to the SceneGraph that this plant is registered as a source for. More...
 

Friends

template<typename U >
class MultibodyPlant
 
class MultibodyPlantTester
 
class internal::MultibodyPlantModelAttorney< T >
 
class internal::MultibodyPlantDiscreteUpdateManagerAttorney< T >
 

Related Functions

(Note that these are not member functions.)

template<typename T >
AddMultibodyPlantSceneGraphResult< T > AddMultibodyPlantSceneGraph (systems::DiagramBuilder< T > *builder, double time_step, std::unique_ptr< geometry::SceneGraph< T >> scene_graph=nullptr)
 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. More...
 
template<typename T >
AddMultibodyPlantSceneGraphResult< T > AddMultibodyPlantSceneGraph (systems::DiagramBuilder< T > *builder, std::unique_ptr< MultibodyPlant< T >> plant, std::unique_ptr< geometry::SceneGraph< T >> scene_graph=nullptr)
 Adds a MultibodyPlant and a SceneGraph instance to a diagram builder, connecting the geometry ports. More...
 

Contact modeling

Use methods in this section to choose the contact model and to provide parameters for that model. Currently Drake supports an advanced compliant model of continuous surface patches we call Hydroelastic contact and a compliant point contact model as a reliable fallback. Please refer to Modeling Compliant Contact for details.

void set_contact_model (ContactModel model)
 Sets the contact model to be used by this MultibodyPlant, see ContactModel for available options. More...
 
void set_discrete_contact_solver (DiscreteContactSolver contact_solver)
 Sets the contact solver type used for discrete MultibodyPlant models. More...
 
DiscreteContactSolver get_discrete_contact_solver () const
 Returns the contact solver type used for discrete MultibodyPlant models. More...
 
void set_discrete_contact_approximation (DiscreteContactApproximation approximation)
 Sets the discrete contact model approximation. More...
 
DiscreteContactApproximation get_discrete_contact_approximation () const
 
void set_sap_near_rigid_threshold (double near_rigid_threshold=MultibodyPlantConfig{}.sap_near_rigid_threshold)
 Non-negative dimensionless number typically in the range [0.0, 1.0], though larger values are allowed even if uncommon. More...
 
double get_sap_near_rigid_threshold () const
 
void set_contact_surface_representation (geometry::HydroelasticContactRepresentation representation)
 Sets the representation of contact surfaces to be used by this MultibodyPlant. More...
 
geometry::HydroelasticContactRepresentation get_contact_surface_representation () const
 Gets the current representation of contact surfaces used by this MultibodyPlant. More...
 
void set_adjacent_bodies_collision_filters (bool value)
 Sets whether to apply collision filters to topologically adjacent bodies at Finalize() time. More...
 
bool get_adjacent_bodies_collision_filters () const
 Returns whether to apply collision filters to topologically adjacent bodies at Finalize() time. More...
 
void SetDiscreteUpdateManager (std::unique_ptr< internal::DiscreteUpdateManager< T >> manager)
 For use only by advanced developers wanting to try out their custom time stepping strategies, including contact resolution. More...
 
const DeformableModel< T > & deformable_model () const
 Returns the DeformableModel owned by this plant. More...
 
DeformableModel< T > & mutable_deformable_model ()
 Returns a mutable reference to the DeformableModel owned by this plant. More...
 
void set_penetration_allowance (double penetration_allowance=MultibodyPlantConfig{}.penetration_allowance)
 Sets the penetration allowance used to estimate the coefficients in the penalty method used to impose non-penetration among bodies. More...
 
double get_contact_penalty_method_time_scale () const
 Returns a time-scale estimate tc based on the requested penetration allowance δ set with set_penetration_allowance(). More...
 
void set_stiction_tolerance (double v_stiction=MultibodyPlantConfig{}.stiction_tolerance)
 
double stiction_tolerance () const
 
static geometry::HydroelasticContactRepresentation GetDefaultContactSurfaceRepresentation (double time_step)
 Return the default value for contact representation, given the desired time step. More...
 

Constructor & Destructor Documentation

◆ MultibodyPlant() [1/4]

MultibodyPlant ( const MultibodyPlant< T > &  )
delete

◆ MultibodyPlant() [2/4]

MultibodyPlant ( MultibodyPlant< T > &&  )
delete

◆ MultibodyPlant() [3/4]

MultibodyPlant ( double  time_step)
explicit

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 Simulation of Multibody Systems with Frictional Contact 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.
Parameters
[in]time_stepIndicates whether this plant is modeled as a continuous system (time_step = 0) or as a discrete system with periodic updates of period time_step > 0. See Simulation of Multibody Systems with Frictional Contact 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.
Exceptions
std::exceptionif time_step is negative.

◆ MultibodyPlant() [4/4]

MultibodyPlant ( const MultibodyPlant< U > &  other)
explicit

Scalar-converting copy constructor. See System Scalar Conversion.

◆ ~MultibodyPlant()

~MultibodyPlant ( )
override

Member Function Documentation

◆ AddBallConstraint()

MultibodyConstraintId AddBallConstraint ( const RigidBody< T > &  body_A,
const Vector3< double > &  p_AP,
const RigidBody< T > &  body_B,
const std::optional< Vector3< double >> &  p_BQ = {} 
)

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.

Parameters
[in]body_ARigidBody to which point P is rigidly attached.
[in]p_APPosition of point P in body A's frame.
[in]body_BRigidBody to which point Q is rigidly attached.
[in]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.
Exceptions
std::exceptionif bodies A and B are the same body.
std::exceptionif the MultibodyPlant has already been finalized.
std::exceptionif this MultibodyPlant is not a discrete model (is_discrete() == false)
std::exceptionif this MultibodyPlant's underlying contact solver is not SAP. (i.e. get_discrete_contact_solver() != DiscreteContactSolver::kSap)

◆ AddCouplerConstraint()

MultibodyConstraintId AddCouplerConstraint ( const Joint< T > &  joint0,
const Joint< T > &  joint1,
double  gear_ratio,
double  offset = 0.0 
)

Defines a holonomic constraint between two single-dof joints joint0 and joint1 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 of q₀.

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.
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.
Exceptions
ifjoint0 and joint1 are not both single-dof joints.
std::exceptionif the MultibodyPlant has already been finalized.
std::exceptionif this MultibodyPlant is not a discrete model (is_discrete() == false)
std::exceptionif this MultibodyPlant's underlying contact solver is not SAP. (i.e. get_discrete_contact_solver() != DiscreteContactSolver::kSap)

◆ AddDistanceConstraint()

MultibodyConstraintId AddDistanceConstraint ( const RigidBody< T > &  body_A,
const Vector3< double > &  p_AP,
const RigidBody< T > &  body_B,
const Vector3< double > &  p_BQ,
double  distance,
double  stiffness = std::numeric_limits< double >::infinity(),
double  damping = 0.0 
)

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 given stiffness and damping 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 ⋅ ḋ

Parameters
[in]body_ARigidBody to which point P is rigidly attached.
[in]p_APPosition of point P in body A's frame.
[in]body_BRigidBody to which point Q is rigidly attached.
[in]p_BQPosition of point Q in body B's frame.
[in]distanceFixed length of the distance constraint, in meters. It must be strictly positive.
[in]stiffnessFor 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 length distance connecting points A and B.
[in]dampingFor 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.
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.
Exceptions
std::exceptionif bodies A and B are the same body.
std::exceptionif distance is not strictly positive.
std::exceptionif stiffness is not positive or zero.
std::exceptionif damping is not positive or zero.
std::exceptionif the MultibodyPlant has already been finalized.
std::exceptionif this MultibodyPlant is not a discrete model (is_discrete() == false)
std::exceptionif this MultibodyPlant's underlying contact solver is not SAP. (i.e. get_discrete_contact_solver() != DiscreteContactSolver::kSap)

◆ AddForceElement()

const ForceElementType<T>& AddForceElement ( Args &&...  args)

Adds a new force element model of type ForceElementType to this MultibodyPlant.

The arguments to this method args are forwarded to ForceElementType's constructor.

Parameters
[in]argsZero 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 Parameters
ForceElementTypeThe 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 of this MultibodyPlant. It will remain valid for the lifetime of this MultibodyPlant.
See also
The ForceElement class's documentation for further details on how a force element is defined.

◆ AddFrame()

const FrameType<T>& AddFrame ( std::unique_ptr< FrameType< T >>  frame)

This method adds a Frame of type FrameType<T>.

For more information, please see the corresponding constructor of FrameType.

Template Parameters
FrameTypeTemplate which will be instantiated on T.
Parameters
frameUnique pointer frame instance.
Returns
A constant reference to the new Frame just added, which will remain valid for the lifetime of this MultibodyPlant.

◆ AddJoint() [1/2]

const JointType<T>& AddJoint ( std::unique_ptr< JointType< T >>  joint)

This method adds a Joint of type JointType between two bodies.

For more information, see the below overload of AddJoint<>.

◆ AddJoint() [2/2]

const JointType<T>& AddJoint ( const std::string &  name,
const RigidBody< T > &  parent,
const std::optional< math::RigidTransform< double >> &  X_PF,
const RigidBody< T > &  child,
const std::optional< math::RigidTransform< double >> &  X_BM,
Args &&...  args 
)

This method adds a Joint of type JointType between two bodies.

The two bodies connected by this Joint object are referred to as parent and child bodies. The parent/child ordering defines the sign conventions for the generalized coordinates and the coordinate ordering for multi-DOF joints.

BodyParentChildJointCM.png

width=50%

Note: The previous figure also shows Pcm which is body P's center of mass and point Bcm which is body B's center of mass.

As explained in the Joint class's documentation, in Drake we define a frame F attached to the parent body P with pose X_PF and a frame M attached to the child body B with pose X_BM. This method helps creating a joint between two bodies with fixed poses X_PF and X_BM. Refer to the Joint class's documentation for more details.

Parameters
nameA string that uniquely identifies the new joint to be added to this model. A std::runtime_error is thrown if a joint named name already is part of the model. See HasJointNamed(), Joint::name().
[in]parentThe parent body connected by the new joint.
[in]X_PFThe fixed pose of frame F attached to the parent body, measured in the frame P of that body. X_PF is an optional parameter; empty curly braces {} imply that frame F is the same body frame P. If instead your intention is to make a frame F with pose X_PF equal to the identity pose, provide RigidTransform<double>::Identity() as your input. When non-nullopt, adds a FixedOffsetFrame named {name}_parent.
[in]childThe child body connected by the new joint.
[in]X_BMThe fixed pose of frame M attached to the child body, measured in the frame B of that body. X_BM is an optional parameter; empty curly braces {} imply that frame M is the same body frame B. If instead your intention is to make a frame M with pose X_BM equal to the identity pose, provide RigidTransform<double>::Identity() as your input. When non-nullopt, adds a FixedOffsetFrame named {name}_child.
[in]argsZero or more parameters provided to the constructor of the new joint. It must be the case that JointType<T>( const std::string&, const Frame<T>&, const Frame<T>&, args) is a valid constructor.
Template Parameters
JointTypeThe type of the Joint to add.
Returns
A constant reference to the new joint just added, of type JointType<T> specialized on the scalar type T of this MultibodyPlant. It will remain valid for the lifetime of this MultibodyPlant.

Example of usage:

MultibodyPlant<T> plant;
// Code to define bodies serving as the joint's parent and child bodies.
const RigidBody<double>& body_1 =
plant.AddRigidBody("Body1", SpatialInertia<double>(...));
const RigidBody<double>& body_2 =
plant.AddRigidBody("Body2", SpatialInertia<double>(...));
// RigidBody 1 serves as parent, RigidBody 2 serves as child.
// Define the pose X_BM of a frame M rigidly attached to child body B.
const RevoluteJoint<double>& elbow =
plant.AddJoint<RevoluteJoint>(
"Elbow", /* joint name */
body_1, /* parent body */
{}, /* frame F IS the parent body frame P */
body_2, /* child body, the pendulum */
X_BM, /* pose of frame M in the body frame B */
Vector3d::UnitZ()); /* revolute axis in this case */
Exceptions
std::exceptionif this MultibodyPlant already contains a joint with the given name. See HasJointNamed(), Joint::name().
std::exceptionif parent and child are the same body or if they are not both from this MultibodyPlant.
See also
The Joint class's documentation for further details on how a Joint is defined.

◆ AddJointActuator()

const JointActuator<T>& AddJointActuator ( const std::string &  name,
const Joint< T > &  joint,
double  effort_limit = std::numeric_limits< double >::infinity() 
)

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 of this plant.

Parameters
[in]nameA string that uniquely identifies the new actuator to be added to this model. A std::runtime_error is thrown if an actuator with the same name already exists in the model. See HasJointActuatorNamed().
[in]jointThe Joint to be actuated by the new JointActuator.
[in]effort_limitThe maximum effort for the actuator. It must be strictly positive, otherwise an std::exception 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().
Exceptions
std::exceptionif joint.num_velocities() > 1 since for now we only support actuators for single dof joints.
See also
RemoveJointActuator()

◆ AddModelInstance()

ModelInstanceIndex AddModelInstance ( const std::string &  name)

Creates a new model instance.

Returns the index for the model instance.

Parameters
[in]nameA 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().

◆ AddRigidBody() [1/2]

const RigidBody<T>& AddRigidBody ( const std::string &  name,
ModelInstanceIndex  model_instance,
const SpatialInertia< double > &  M_BBo_B = SpatialInertia<double>::Zero() 
)

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:

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);
Parameters
[in]nameA string that identifies the new body to be added to this model. A std::runtime_error is thrown if a body named name already is part of model_instance. See HasBodyNamed(), RigidBody::name().
[in]model_instanceA model instance index which this body is part of.
[in]M_BBo_BThe SpatialInertia of the new rigid body to be added to this MultibodyPlant, computed about the body frame origin Bo 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.

◆ AddRigidBody() [2/2]

const RigidBody<T>& AddRigidBody ( const std::string &  name,
const SpatialInertia< double > &  M_BBo_B = SpatialInertia<double>::Zero() 
)

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 (more on model instances).

Example of usage:

MultibodyPlant<T> plant;
// ... Code to define spatial_inertia, a SpatialInertia<T> object ...
const RigidBody<T>& body =
plant.AddRigidBody("BodyName", spatial_inertia);
Parameters
[in]nameA string that identifies the new body to be added to this model. A std::runtime_error is thrown if a body named name already is part of the model in the default model instance. See HasBodyNamed(), RigidBody::name().
[in]M_BBo_BThe SpatialInertia of the new rigid body to be added to this MultibodyPlant, computed about the body frame origin Bo 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.
Exceptions
std::exceptionif additional model instances have been created beyond the world and default instances.

◆ AddWeldConstraint()

MultibodyConstraintId AddWeldConstraint ( const RigidBody< T > &  body_A,
const math::RigidTransform< double > &  X_AP,
const RigidBody< T > &  body_B,
const math::RigidTransform< double > &  X_BQ 
)

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.

Parameters
[in]body_ARigidBody to which frame P is rigidly attached.
[in]X_APPose of frame P in body A's frame.
[in]body_BRigidBody to which frame Q is rigidly attached.
[in]X_BQPose of frame Q in body B's frame.
Returns
the id of the newly added constraint.
Exceptions
std::exceptionif bodies A and B are the same body.
std::exceptionif the MultibodyPlant has already been finalized.
std::exceptionif this MultibodyPlant is not a discrete model (is_discrete() == false)
std::exceptionif this MultibodyPlant's underlying contact solver is not SAP. (i.e. get_discrete_contact_solver() != DiscreteContactSolver::kSap)

◆ CalcBiasCenterOfMassTranslationalAcceleration() [1/2]

Vector3<T> CalcBiasCenterOfMassTranslationalAcceleration ( const systems::Context< T > &  context,
JacobianWrtVariable  with_respect_to,
const Frame< T > &  frame_A,
const Frame< T > &  frame_E 
) const

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.

Parameters
[in]contextContains the state of the multibody system.
[in]with_respect_toEnum 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.
[in]frame_AThe frame in which a𝑠Bias_AScm is measured.
[in]frame_EThe 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.
Exceptions
std::exceptionif this has no body except world_body().
std::exceptionif mₛ ≤ 0, where mₛ is the mass of system S.
std::exceptionif 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).
See Bias acceleration functions for theory and details.

◆ CalcBiasCenterOfMassTranslationalAcceleration() [2/2]

Vector3<T> CalcBiasCenterOfMassTranslationalAcceleration ( const systems::Context< T > &  context,
const std::vector< ModelInstanceIndex > &  model_instances,
JacobianWrtVariable  with_respect_to,
const Frame< T > &  frame_A,
const Frame< T > &  frame_E 
) const

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.

Parameters
[in]contextContains the state of the multibody system.
[in]model_instancesVector of selected model instances. If a model instance is repeated in the vector (unusual), it is only counted once.
[in]with_respect_toEnum 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.
[in]frame_AThe frame in which a𝑠Bias_AScm is measured.
[in]frame_EThe 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.
Exceptions
std::exceptionif this has no body except world_body().
std::exceptionif mₛ ≤ 0, where mₛ is the mass of system S.
std::exceptionif 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).
See Bias acceleration functions for theory and details.

◆ CalcBiasSpatialAcceleration()

SpatialAcceleration<T> CalcBiasSpatialAcceleration ( const systems::Context< T > &  context,
JacobianWrtVariable  with_respect_to,
const Frame< T > &  frame_B,
const Eigen::Ref< const Vector3< T >> &  p_BoBp_B,
const Frame< T > &  frame_A,
const Frame< T > &  frame_E 
) const

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.

Parameters
[in]contextContains the state of the multibody system.
[in]with_respect_toEnum 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.
[in]frame_BThe frame on which point Bp is affixed/welded.
[in]p_BoBp_BPosition vector from Bo (frame_B's origin) to point Bp (regarded as affixed/welded to B), expressed in frame_B.
[in]frame_AThe frame in which A𝑠Bias_ABp is measured.
[in]frame_EThe 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 𝑠.
Exceptions
std::exceptionif 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.
See Bias acceleration functions for theory and details.

◆ CalcBiasTerm()

void CalcBiasTerm ( const systems::Context< T > &  context,
EigenPtr< VectorX< T >>  Cv 
) const

Computes the bias term C(q, v) v containing Coriolis, centripetal, and gyroscopic effects in the multibody equations of motion:

  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 inertias) and tau_app is a vector of applied generalized forces. The last term is a summation over all bodies of the dot-product of Fapp_Bo_W (applied spatial force on body B at Bo) with Jv_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 written V_WB = Jv_V_WB * v.

Parameters
[in]contextContains the state of the multibody system, including the generalized positions q and the generalized velocities v.
[out]CvOn output, Cv will contain the product C(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.

◆ CalcBiasTranslationalAcceleration()

Matrix3X<T> CalcBiasTranslationalAcceleration ( const systems::Context< T > &  context,
JacobianWrtVariable  with_respect_to,
const Frame< T > &  frame_B,
const Eigen::Ref< const Matrix3X< T >> &  p_BoBi_B,
const Frame< T > &  frame_A,
const Frame< T > &  frame_E 
) const

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.

Parameters
[in]contextContains the state of the multibody system.
[in]with_respect_toEnum 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.
[in]frame_BThe frame on which points Bi are affixed/welded.
[in]p_BoBi_BA 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.
[in]frame_AThe frame in which a𝑠Bias_ABi is measured.
[in]frame_EThe 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.
Exceptions
std::exceptionif with_respect_to is JacobianWrtVariable::kQDot.
Note
See Bias acceleration functions for theory and details.

◆ CalcCenterOfMassPositionInWorld() [1/2]

Vector3<T> CalcCenterOfMassPositionInWorld ( const systems::Context< T > &  context) const

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.

Parameters
[in]contextContains the state of the model.
Return values
p_WoScm_Wposition 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.
Exceptions
std::exceptionif this has no body except world_body().
std::exceptionif 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() [2/2]

Vector3<T> CalcCenterOfMassPositionInWorld ( const systems::Context< T > &  context,
const std::vector< ModelInstanceIndex > &  model_instances 
) const

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.

Parameters
[in]contextContains the state of the model.
[in]model_instancesVector of selected model instances. If a model instance is repeated in the vector (unusual), it is only counted once.
Return values
p_WoScm_Wposition 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.
Exceptions
std::exceptionif model_instances is empty or only has world body.
std::exceptionif 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() [1/2]

Vector3<T> CalcCenterOfMassTranslationalAccelerationInWorld ( const systems::Context< T > &  context) const

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.

Parameters
[in]contextThe context contains the state of the model.
Return values
a_WScm_WScm's translational acceleration in the world frame W expressed in the world frame W.
Exceptions
std::exceptionif this has no body except world_body().
std::exceptionif 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).
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() [2/2]

Vector3<T> CalcCenterOfMassTranslationalAccelerationInWorld ( const systems::Context< T > &  context,
const std::vector< ModelInstanceIndex > &  model_instances 
) const

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.

Parameters
[in]contextThe context contains the state of the model.
[in]model_instancesVector of selected model instances. If a model instance is repeated in the vector (unusual), it is only counted once.
Return values
a_WScm_WScm's translational acceleration in the world frame W expressed in the world frame W.
Exceptions
std::exceptionif model_instances is empty or only has world body.
std::exceptionif 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).
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() [1/2]

Vector3<T> CalcCenterOfMassTranslationalVelocityInWorld ( const systems::Context< T > &  context) const

Calculates system center of mass translational velocity in world frame W.

Parameters
[in]contextThe context contains the state of the model.
Return values
v_WScm_WScm's translational velocity in frame W, expressed in W, where Scm is the center of mass of the system S stored by this plant.
Exceptions
std::exceptionif this has no body except world_body().
std::exceptionif 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() [2/2]

Vector3<T> CalcCenterOfMassTranslationalVelocityInWorld ( const systems::Context< T > &  context,
const std::vector< ModelInstanceIndex > &  model_instances 
) const

Calculates system center of mass translational velocity in world frame W.

Parameters
[in]contextThe context contains the state of the model.
[in]model_instancesVector of selected model instances. If a model instance is repeated in the vector (unusual), it is only counted once.
Return values
v_WScm_WScm'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.
Exceptions
std::exceptionif model_instances is empty or only has world body.
std::exceptionif 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()

void CalcForceElementsContribution ( const systems::Context< T > &  context,
MultibodyForces< T > *  forces 
) const

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.

Parameters
[in]contextThe context containing the state of this model.
[out]forcesA 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.
Exceptions
std::exceptionif forces is null or not compatible with this model, per MultibodyForces::CheckInvariants().

◆ CalcGeneralizedForces()

void CalcGeneralizedForces ( const systems::Context< T > &  context,
const MultibodyForces< T > &  forces,
VectorX< T > *  generalized_forces 
) const

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:

  τᵣₑₛᵤₗₜ = τ + J_WBo⋅F
Parameters
[in]contextContext that stores the state of the model.
[in]forcesSet of multibody forces, including both generalized forces and per-body spatial forces.
[out]generalized_forcesThe total generalized forces on the model that would result from applying forces. In other words, forces can be replaced by the equivalent generalized_forces. On output, generalized_forces is resized to num_velocities().
Exceptions
std::exceptionif forces is null or not compatible with this model.
std::exceptionif generalized_forces is not a valid non-null pointer.

◆ CalcGravityGeneralizedForces()

VectorX<T> CalcGravityGeneralizedForces ( const systems::Context< T > &  context) const

Computes the generalized forces tau_g(q) due to gravity as a function of the generalized positions q stored in the input context.

The vector of generalized forces due to gravity tau_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:

  Mv̇ + C(q, v)v = tau_g(q) + tau_app

where tau_app includes any other generalized forces applied on the system.

Parameters
[in]contextThe 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 for this so that the inner product v⋅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.

◆ CalcImplicitTimeDerivativesResidual()

void CalcImplicitTimeDerivativesResidual ( const systems::Context< T > &  context,
const systems::ContinuousState< T > &  proposed_derivatives,
EigenPtr< VectorX< T >>  residual 
) const

MultibodyPlant implements the systems::System::CalcImplicitTimeDerivativesResidual method when the plant is modeled as a continuous-time system, returning one residual for each multibody state.

In particular, the first num_positions() residuals are given by

  q̇_proposed - N(q)⋅v

and the final num_velocities() residuals are given by

  CalcInverseDynamics(context, v_proposed)

including all actuator and applied forces.

See also
systems::System::CalcImplicitTimeDerivativesResidual for more details.

◆ CalcInverseDynamics()

VectorX<T> CalcInverseDynamics ( const systems::Context< T > &  context,
const VectorX< T > &  known_vdot,
const MultibodyForces< T > &  external_forces 
) const

Given the state of this model in context and a known vector of generalized accelerations vdot, this method computes the set of generalized forces tau that would need to be applied in order to attain the specified generalized accelerations.

Mathematically, this method computes:

  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 inertias), C(q, v)v is the bias term for Coriolis and gyroscopic effects and tau_app consists of a vector applied generalized forces. The last term is a summation over all bodies in the model where Fapp_Bo_W is an applied spatial force on body B at Bo which gets projected into the space of generalized forces with the transpose of Jv_V_WB(q) (where Jv_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 as V_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 an O(n) Newton-Euler recursive algorithm, where n is the number of bodies in the model. The explicit formation of the mass matrix M(q) would require the calculation of O(n²) entries while explicitly forming the product C(q, v) * v could require up to O(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].

Parameters
[in]contextThe context containing the state of the model.
[in]known_vdotA vector with the known generalized accelerations vdot for the full model. Use the provided Joint APIs in order to access entries into this array.
[in]external_forcesA set of forces to be applied to the system either as body spatial forces Fapp_Bo_W or generalized forces tau_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.

◆ CalcJacobianAngularVelocity()

void CalcJacobianAngularVelocity ( const systems::Context< T > &  context,
const JacobianWrtVariable  with_respect_to,
const Frame< T > &  frame_B,
const Frame< T > &  frame_A,
const Frame< T > &  frame_E,
EigenPtr< Matrix3X< T >>  Js_w_AB_E 
) const

Calculates J𝑠_w_AB, a frame B's angular velocity Jacobian in a frame A with respect to "speeds" 𝑠.

     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).

Parameters
[in]contextThe state of the multibody system.
[in]with_respect_toEnum 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).
[in]frame_BThe frame B in w_AB (B's angular velocity in A).
[in]frame_AThe frame A in w_AB (B's angular velocity in A).
[in]frame_EThe frame in which w_AB is expressed on input and the frame in which the Jacobian J𝑠_w_AB is expressed on output.
[out]J𝑠_w_AB_EFrame 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 size 3 x n, where n is the number of elements in 𝑠.
See also
See Jacobian functions for related functions.
Exceptions
std::exceptionif J𝑠_w_AB_E is nullptr or not of size 3 x n.

◆ CalcJacobianCenterOfMassTranslationalVelocity() [1/2]

void CalcJacobianCenterOfMassTranslationalVelocity ( const systems::Context< T > &  context,
JacobianWrtVariable  with_respect_to,
const Frame< T > &  frame_A,
const Frame< T > &  frame_E,
EigenPtr< Matrix3X< T >>  Js_v_ACcm_E 
) const

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.

Parameters
[in]contextcontains the state of the model.
[in]with_respect_toEnum 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).
[in]frame_AThe frame in which the translational velocity v_ACcm and its Jacobian J𝑠_v_ACcm are measured.
[in]frame_EThe frame in which the Jacobian J𝑠_v_ACcm is expressed on output.
[out]J𝑠_v_ACcm_EPoint 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).
Exceptions
std::exceptionif CCm does not exist, which occurs if there are no massive bodies in MultibodyPlant (except world_body()).
std::exceptionif mₛ ≤ 0 (where mₛ is the mass of all non-world bodies contained in this MultibodyPlant).
See also
See Jacobian functions for related functions.

◆ CalcJacobianCenterOfMassTranslationalVelocity() [2/2]

void CalcJacobianCenterOfMassTranslationalVelocity ( const systems::Context< T > &  context,
const std::vector< ModelInstanceIndex > &  model_instances,
JacobianWrtVariable  with_respect_to,
const Frame< T > &  frame_A,
const Frame< T > &  frame_E,
EigenPtr< Matrix3X< T >>  Js_v_ACcm_E 
) const

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.

Parameters
[in]contextcontains the state of the model.
[in]model_instancesVector of selected model instances. If a model instance is repeated in the vector (unusual), it is only counted once.
[in]with_respect_toEnum 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).
[in]frame_AThe frame in which the translational velocity v_ACcm and its Jacobian J𝑠_v_ACcm are measured.
[in]frame_EThe frame in which the Jacobian J𝑠_v_ACcm is expressed on output.
[out]J𝑠_v_ACcm_EPoint 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).
Exceptions
std::exceptionif mₛ ≤ 0 (where mₛ is the mass of all non-world bodies contained in model_instances).
std::exceptionif 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 for related functions.

◆ CalcJacobianPositionVector()

void CalcJacobianPositionVector ( const systems::Context< T > &  context,
const Frame< T > &  frame_B,
const Eigen::Ref< const Matrix3X< T >> &  p_BoBi_B,
const Frame< T > &  frame_A,
const Frame< T > &  frame_E,
EigenPtr< MatrixX< T >>  Jq_p_AoBi_E 
) const

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

     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ₙ.

Parameters
[in]contextThe state of the multibody system.
[in]frame_BThe frame on which point Bi is affixed/welded.
[in]p_BoBi_BA 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.
[in]frame_AThe frame in which partial derivatives are calculated and the frame in which point Ao is affixed.
[in]frame_EThe frame in which the Jacobian Jq_p_AoBi is expressed on output.
[out]Jq_p_AoBi_EPoint 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).
Exceptions
std::exceptionif 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.
[∂(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 Jacobian functions for related functions.

◆ CalcJacobianSpatialVelocity()

void CalcJacobianSpatialVelocity ( const systems::Context< T > &  context,
JacobianWrtVariable  with_respect_to,
const Frame< T > &  frame_B,
const Eigen::Ref< const Vector3< T >> &  p_BoBp_B,
const Frame< T > &  frame_A,
const Frame< T > &  frame_E,
EigenPtr< MatrixX< T >>  Js_V_ABp_E 
) const

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" 𝑠.

     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).

Parameters
[in]contextThe state of the multibody system.
[in]with_respect_toEnum 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).
[in]frame_BThe frame on which point Bp is fixed/welded.
[in]p_BoBp_BA position vector from Bo (frame_B's origin) to point Bp (regarded as fixed/welded to B), expressed in frame_B.
[in]frame_AThe 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.
[in]frame_EThe frame in which v_ABp is expressed on input and the frame in which the Jacobian J𝑠_V_ABp is expressed on output.
[out]J𝑠_V_ABp_EPoint 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 a 6 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.,
    J𝑠_w_AB_E = J𝑠_V_ABp_E.topRows<3>();
    J𝑠_v_ABp_E = J𝑠_V_ABp_E.bottomRows<3>();
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 for related functions.
Exceptions
std::exceptionif J𝑠_V_ABp_E is nullptr or not sized 6 x n.

◆ CalcJacobianTranslationalVelocity()

void CalcJacobianTranslationalVelocity ( const systems::Context< T > &  context,
JacobianWrtVariable  with_respect_to,
const Frame< T > &  frame_B,
const Eigen::Ref< const Matrix3X< T >> &  p_BoBi_B,
const Frame< T > &  frame_A,
const Frame< T > &  frame_E,
EigenPtr< MatrixX< T >>  Js_v_ABi_E 
) const

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" 𝑠.

     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).

Parameters
[in]contextThe state of the multibody system.
[in]with_respect_toEnum 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).
[in]frame_BThe frame on which point Bi is affixed/welded.
[in]p_BoBi_BA 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.
[in]frame_AThe 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.
[in]frame_EThe frame in which v_ABi is expressed on input and the frame in which the Jacobian J𝑠_v_ABi is expressed on output.
[out]J𝑠_v_ABi_EPoint 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 a 3*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).
Exceptions
std::exceptionif 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.
[∂(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 Jacobian functions for related functions.

◆ CalcMassMatrix()

void CalcMassMatrix ( const systems::Context< T > &  context,
EigenPtr< MatrixX< T >>  M 
) const

Efficiently computes the mass matrix M(q) of the model.

The generalized positions q are taken from the given context. M includes the mass properties of rigid bodies and 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.

Parameters
[in]contextThe Context containing the state of the model from which generalized coordinates q are extracted.
[out]MA 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)

◆ CalcMassMatrixViaInverseDynamics()

void CalcMassMatrixViaInverseDynamics ( const systems::Context< T > &  context,
EigenPtr< MatrixX< T >>  M 
) const

Computes the mass matrix M(q) of the model using a slow method (inverse dynamics).

The generalized positions q are taken from the given context. M includes the mass properties of rigid bodies and reflected inertias as provided with JointActuator specifications.

Use CalcMassMatrix() for a faster implementation using the Composite Body Algorithm.

Parameters
[in]contextThe Context containing the state of the model from which generalized coordinates q are extracted.
[out]MA 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 of M(q) at a time using inverse dynamics. The result from inverse dynamics, with no applied forces, is the vector of generalized forces:

  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 term C(q, v)v is zero. Therefore the i-th column of M(q) can be obtained performing inverse dynamics with an acceleration vector v̇ = eᵢ, with eᵢ the standard (or natural) basis of ℛⁿ with n the number of generalized velocities. We write this as:

  M.ᵢ(q) = M(q) * e_i

where M.ᵢ(q) (notice the dot for the rows index) denotes the i-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()

◆ CalcPointsPositions()

void CalcPointsPositions ( const systems::Context< T > &  context,
const Frame< T > &  frame_B,
const Eigen::Ref< const MatrixX< T >> &  p_BQi,
const Frame< T > &  frame_A,
EigenPtr< MatrixX< T >>  p_AQi 
) const

Given the positions p_BQi for a set of points Qi measured and expressed in a frame B, this method computes the positions p_AQi(q) of each point Qi in the set as measured and expressed in another frame A, as a function of the generalized positions q of the model.

Parameters
[in]contextThe context containing the state of the model. It stores the generalized positions q of the model.
[in]frame_BThe frame B in which the positions p_BQi of a set of points Qi are given.
[in]p_BQiThe input positions of each point Qi in frame B. p_BQi ∈ ℝ³ˣⁿᵖ with np the number of points in the set. Each column of p_BQi corresponds to a vector in ℝ³ holding the position of one of the points in the set as measured and expressed in frame B.
[in]frame_AThe frame A in which it is desired to compute the positions p_AQi of each point Qi in the set.
[out]p_AQiThe output positions of each point Qi now computed as measured and expressed in frame A. The output p_AQi must have the same size as the input p_BQi or otherwise this method aborts. That is p_AQi must be in ℝ³ˣⁿᵖ.
Note
Both p_BQi and p_AQi must have three rows. Otherwise this method will throw a std::exception. This method also throws a std::exception if p_BQi and p_AQi differ in the number of columns.

◆ CalcRelativeRotationMatrix()

math::RotationMatrix<T> CalcRelativeRotationMatrix ( const systems::Context< T > &  context,
const Frame< T > &  frame_A,
const Frame< T > &  frame_B 
) const

Calculates the rotation matrix R_AB relating frame A and frame B.

Parameters
[in]contextThe state of the multibody system, which includes the system's generalized positions q. Note: R_AB is a function of q.
[in]frame_AThe frame A designated in the rigid transform R_AB.
[in]frame_BThe frame G designated in the rigid transform R_AB.
Return values
R_ABThe RigidTransform relating frame A and frame B.

◆ CalcRelativeTransform()

math::RigidTransform<T> CalcRelativeTransform ( const systems::Context< T > &  context,
const Frame< T > &  frame_A,
const Frame< T > &  frame_B 
) const

Calculates the rigid transform (pose) X_AB relating frame A and frame B.

Parameters
[in]contextThe state of the multibody system, which includes the system's generalized positions q. Note: X_AB is a function of q.
[in]frame_AThe frame A designated in the rigid transform X_AB.
[in]frame_BThe frame G designated in the rigid transform X_AB.
Return values
X_ABThe RigidTransform relating frame A and frame B.

◆ CalcSpatialAccelerationsFromVdot()

void CalcSpatialAccelerationsFromVdot ( const systems::Context< T > &  context,
const VectorX< T > &  known_vdot,
std::vector< SpatialAcceleration< T >> *  A_WB_array 
) const

Given the state of this model in context and a known vector of generalized accelerations known_vdot, this method computes the spatial acceleration A_WB for each body as measured and expressed in the world frame W.

Parameters
[in]contextThe context containing the state of this model.
[in]known_vdotA vector with the generalized accelerations for the full model.
[out]A_WB_arrayA 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.
Exceptions
std::exceptionif A_WB_array is not of size num_bodies().

◆ CalcSpatialInertia()

SpatialInertia<T> CalcSpatialInertia ( const systems::Context< T > &  context,
const Frame< T > &  frame_F,
const std::vector< BodyIndex > &  body_indexes 
) const

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.

Parameters
[in]contextContains the configuration of the set S of bodies.
[in]frame_Fspecifies the about-point Fo (frame_F's origin) and the expressed-in frame for the returned spatial inertia.
[in]body_indexesArray of selected bodies. This method does not distinguish between welded bodies, joint-connected bodies, etc.
Exceptions
std::exceptionif 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.

◆ CalcSpatialMomentumInWorldAboutPoint() [1/2]

SpatialMomentum<T> CalcSpatialMomentumInWorldAboutPoint ( const systems::Context< T > &  context,
const Vector3< T > &  p_WoP_W 
) const

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.

Parameters
[in]contextContains the state of the model.
[in]p_WoP_WPosition from Wo (origin of the world frame W) to an arbitrary point P, expressed in the world frame W.
Return values
L_WSP_W,spatialmomentum 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:
  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() [2/2]

SpatialMomentum<T> CalcSpatialMomentumInWorldAboutPoint ( const systems::Context< T > &  context,
const std::vector< ModelInstanceIndex > &  model_instances,
const Vector3< T > &  p_WoP_W 
) const

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.

Parameters
[in]contextContains the state of the model.
[in]model_instancesSet of selected model instances.
[in]p_WoP_WPosition from Wo (origin of the world frame W) to an arbitrary point P, expressed in the world frame W.
Return values
L_WSP_W,spatialmomentum 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:
  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);
Exceptions
std::exceptionif model_instances contains an invalid ModelInstanceIndex.

◆ CalcTotalMass() [1/2]

T CalcTotalMass ( const systems::Context< T > &  context) const

Calculates the total mass of all bodies in this MultibodyPlant.

Parameters
[in]contextContains the state of the model.
Return values
Thetotal 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() [2/2]

T CalcTotalMass ( const systems::Context< T > &  context,
const std::vector< ModelInstanceIndex > &  model_instances 
) const

Calculates the total mass of all bodies contained in model_instances.

Parameters
[in]contextContains the state of the model.
[in]model_instancesVector of selected model instances. This method does not distinguish between welded, joint connected, or floating bodies.
Return values
Thetotal 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()

geometry::GeometrySet CollectRegisteredGeometries ( const std::vector< const RigidBody< T > * > &  bodies) const

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:

// 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:
  1. Bodies and geometries must be added to the MultibodyPlant.
  2. Create GeometrySet instances from bodies (via this method).
  3. Invoke SceneGraph::ExcludeCollisions*() to filter collisions.
  4. Allocate context.

Changing the order will cause exceptions to be thrown.

Exceptions
std::exceptionif this MultibodyPlant was not registered with a SceneGraph.

◆ deformable_model()

const DeformableModel<T>& deformable_model ( ) const

Returns the DeformableModel owned by this plant.

Exceptions
std::exceptionif 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()

const math::RigidTransform<T>& EvalBodyPoseInWorld ( const systems::Context< T > &  context,
const RigidBody< T > &  body_B 
) const

Evaluate the pose X_WB of a body B in the world frame W.

Parameters
[in]contextThe context storing the state of the model.
[in]body_BThe body B for which the pose is requested.
Return values
X_WBThe pose of body frame B in the world frame W.
Exceptions
std::exceptionif Finalize() was not called on this model or if body_B does not belong to this model.

◆ EvalBodySpatialAccelerationInWorld()

const SpatialAcceleration<T>& EvalBodySpatialAccelerationInWorld ( const systems::Context< T > &  context,
const RigidBody< T > &  body_B 
) const

Evaluates A_WB, body B's spatial acceleration in the world frame W.

Parameters
[in]contextThe context storing the state of the model.
[in]body_BThe body for which spatial acceleration is requested.
Return values
A_WB_WRigidBody B's spatial acceleration in the world frame W, expressed in W (for point Bo, the body's origin).
Exceptions
std::exceptionif 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.

◆ EvalBodySpatialVelocityInWorld()

const SpatialVelocity<T>& EvalBodySpatialVelocityInWorld ( const systems::Context< T > &  context,
const RigidBody< T > &  body_B 
) const

Evaluates V_WB, body B's spatial velocity in the world frame W.

Parameters
[in]contextThe context storing the state of the model.
[in]body_BThe body B for which the spatial velocity is requested.
Return values
V_WB_WRigidBody B's spatial velocity in the world frame W, expressed in W (for point Bo, the body's origin).
Exceptions
std::exceptionif Finalize() was not called on this model or if body_B does not belong to this model.

◆ EvalSceneGraphInspector()

const geometry::SceneGraphInspector<T>& EvalSceneGraphInspector ( const systems::Context< T > &  context) const

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.)

◆ ExcludeCollisionGeometriesWithCollisionFilterGroupPair()

void ExcludeCollisionGeometriesWithCollisionFilterGroupPair ( const std::pair< std::string, geometry::GeometrySet > &  collision_filter_group_a,
const std::pair< std::string, geometry::GeometrySet > &  collision_filter_group_b 
)

Excludes the rigid collision geometries between two given collision filter groups.

Note that collisions involving deformable geometries are not filtered by this function.

Precondition
RegisterAsSourceForSceneGraph() has been called.
Finalize() has not been called.

◆ Finalize()

void Finalize ( )

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 Finalize() stage.

See also
is_finalized(), Finalize() stage.
Exceptions
std::exceptionif the MultibodyPlant has already been finalized.

◆ geometry_source_is_registered()

bool geometry_source_is_registered ( ) const

Returns true if this MultibodyPlant was registered with a SceneGraph.

This method can be called at any time during the lifetime of this plant to query if this plant has been registered with a SceneGraph, either pre- or post-finalize, see Finalize().

◆ get_actuation_input_port() [1/2]

const systems::InputPort<T>& get_actuation_input_port ( ) const

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 Actuation for further details.

Precondition
Finalize() was already called on this plant.
Exceptions
std::exceptionif called before Finalize().

◆ get_actuation_input_port() [2/2]

const systems::InputPort<T>& get_actuation_input_port ( ModelInstanceIndex  model_instance) const

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 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.
Exceptions
std::exceptionif called before Finalize().
std::exceptionif the model instance does not exist.

◆ get_adjacent_bodies_collision_filters()

bool get_adjacent_bodies_collision_filters ( ) const

Returns whether to apply collision filters to topologically adjacent bodies at Finalize() time.

◆ get_applied_generalized_force_input_port()

const systems::InputPort<T>& get_applied_generalized_force_input_port ( ) const

Returns a constant reference to the vector-valued input port for applied generalized forces, and the vector will be added directly into tau (see 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).

Exceptions
std::exceptionif called before Finalize().

◆ get_applied_spatial_force_input_port()

const systems::InputPort<T>& get_applied_spatial_force_input_port ( ) const

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_ball_constraint_specs() [1/2]

const internal::BallConstraintSpec& get_ball_constraint_specs ( MultibodyConstraintId  id) const

(Internal use only) Returns the ball constraint specification corresponding to id

Exceptions
ifid is not a valid identifier for a ball constraint.

◆ get_ball_constraint_specs() [2/2]

const std::map<MultibodyConstraintId, internal::BallConstraintSpec>& get_ball_constraint_specs ( ) const

(Internal use only) Returns a reference to all of the ball constraints in this plant as a map from MultibodyConstraintId to BallConstraintSpec.

◆ get_body()

const RigidBody<T>& get_body ( BodyIndex  body_index) const

Returns a constant reference to the body with unique index body_index.

Exceptions
std::exceptionif body_index does not correspond to a body in this model.

◆ get_body_poses_output_port()

const systems::OutputPort<T>& get_body_poses_output_port ( ) const

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:

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.

Exceptions
std::exceptionif called pre-finalize.

◆ get_body_spatial_accelerations_output_port()

const systems::OutputPort<T>& get_body_spatial_accelerations_output_port ( ) const

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:

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 for details. When sampling is enabled and the plant has not yet taken a step, the output value will be all zeros.

Exceptions
std::exceptionif called pre-finalize.

◆ get_body_spatial_velocities_output_port()

const systems::OutputPort<T>& get_body_spatial_velocities_output_port ( ) const

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:

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.

Exceptions
std::exceptionif called pre-finalize.

◆ get_contact_model()

ContactModel get_contact_model ( ) const

Returns the model used for contact. See documentation for ContactModel.

◆ get_contact_penalty_method_time_scale()

double get_contact_penalty_method_time_scale ( ) const

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 scale tc 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 scale tc. 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. If vn represents a reference velocity scale for the normal relative velocity between bodies, the new time scale tn = δ / vn represents the time it would take for the distance between two bodies approaching with relative normal velocity vn 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 scales tc and tn.

◆ get_contact_results_output_port()

const systems::OutputPort<T>& get_contact_results_output_port ( ) const

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 for details. When sampling is enabled and the plant has not yet taken a step, the output value will be empty (no contacts).

Exceptions
std::exceptionif called pre-finalize, see Finalize().

◆ get_contact_surface_representation()

geometry::HydroelasticContactRepresentation get_contact_surface_representation ( ) const

Gets the current representation of contact surfaces used by this MultibodyPlant.

◆ get_coupler_constraint_specs() [1/2]

const internal::CouplerConstraintSpec& get_coupler_constraint_specs ( MultibodyConstraintId  id) const

(Internal use only) Returns the coupler constraint specification corresponding to id

Exceptions
ifid is not a valid identifier for a coupler constraint.

◆ get_coupler_constraint_specs() [2/2]

const std::map<MultibodyConstraintId, internal::CouplerConstraintSpec>& get_coupler_constraint_specs ( ) const

(Internal use only) Returns a reference to the all of the coupler constraints in this plant as a map from MultibodyConstraintId to CouplerConstraintSpec.

◆ get_deformable_body_configuration_output_port()

const systems::OutputPort<T>& get_deformable_body_configuration_output_port ( ) const

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()

const systems::InputPort<T>& get_desired_state_input_port ( ModelInstanceIndex  model_instance) const

For models with PD controlled joint actuators, returns the port to provide the desired state for the full model_instance.

Refer to 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:
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.
It is required to connect this port for PD controlled model instances.

◆ get_discrete_contact_approximation()

DiscreteContactApproximation get_discrete_contact_approximation ( ) const
Returns
the discrete contact solver approximation.

◆ get_discrete_contact_solver()

DiscreteContactSolver get_discrete_contact_solver ( ) const

Returns the contact solver type used for discrete MultibodyPlant models.

◆ get_distance_constraint_specs() [1/2]

const internal::DistanceConstraintSpec& get_distance_constraint_specs ( MultibodyConstraintId  id) const

(Internal use only) Returns the distance constraint specification corresponding to id

Exceptions
ifid is not a valid identifier for a distance constraint.

◆ get_distance_constraint_specs() [2/2]

const std::map<MultibodyConstraintId, internal::DistanceConstraintSpec>& get_distance_constraint_specs ( ) const

(Internal use only) Returns a reference to the all of the distance constraints in this plant as a map from MultibodyConstraintId to DistanceConstraintSpec.

◆ get_force_element()

const ForceElement<T>& get_force_element ( ForceElementIndex  force_element_index) const

Returns a constant reference to the force element with unique index force_element_index.

Exceptions
std::exceptionwhen force_element_index does not correspond to a force element in this model.

◆ get_frame()

const Frame<T>& get_frame ( FrameIndex  frame_index) const

Returns a constant reference to the frame with unique index frame_index.

Exceptions
std::exceptionif frame_index does not correspond to a frame in this plant.

◆ get_generalized_acceleration_output_port() [1/2]

const systems::OutputPort<T>& get_generalized_acceleration_output_port ( ) const

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 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.
Exceptions
std::exceptionif called before Finalize().

◆ get_generalized_acceleration_output_port() [2/2]

const systems::OutputPort<T>& get_generalized_acceleration_output_port ( ModelInstanceIndex  model_instance) const

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 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.
Exceptions
std::exceptionif called before Finalize().
std::exceptionif the model instance does not exist.

◆ get_generalized_contact_forces_output_port()

const systems::OutputPort<T>& get_generalized_contact_forces_output_port ( ModelInstanceIndex  model_instance) const

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 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.
Exceptions
std::exceptionif called before Finalize().
std::exceptionif the model instance does not exist.

◆ get_geometry_pose_output_port()

const systems::OutputPort<T>& get_geometry_pose_output_port ( ) const

Returns the output port of frames' poses to communicate with a SceneGraph.

◆ get_geometry_query_input_port()

const systems::InputPort<T>& get_geometry_query_input_port ( ) const

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 Geometry of this class's documentation for further details on collision geometry registration and connection with a SceneGraph.

◆ get_joint()

const Joint<T>& get_joint ( JointIndex  joint_index) const

Returns a constant reference to the joint with unique index joint_index.

Exceptions
std::exceptionwhen joint_index does not correspond to a joint in this model.

◆ get_joint_actuator()

const JointActuator<T>& get_joint_actuator ( JointActuatorIndex  actuator_index) const

Returns a constant reference to the joint actuator with unique index actuator_index.

Exceptions
std::exceptionif actuator_index does not correspond to a joint actuator in this tree.

◆ get_mutable_joint()

Joint<T>& get_mutable_joint ( JointIndex  joint_index)

Returns a mutable reference to the joint with unique index joint_index.

Exceptions
std::exceptionwhen joint_index does not correspond to a joint in this model.

◆ get_mutable_joint_actuator()

JointActuator<T>& get_mutable_joint_actuator ( JointActuatorIndex  actuator_index)

Returns a mutable reference to the joint actuator with unique index actuator_index.

Exceptions
std::exceptionif actuator_index does not correspond to a joint actuator in this tree.

◆ get_net_actuation_output_port() [1/2]

const systems::OutputPort<T>& get_net_actuation_output_port ( ) const

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 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 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.
Exceptions
std::exceptionif called before Finalize().

◆ get_net_actuation_output_port() [2/2]

const systems::OutputPort<T>& get_net_actuation_output_port ( ModelInstanceIndex  model_instance) const

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 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 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.
Exceptions
std::exceptionif called before Finalize().

◆ get_reaction_forces_output_port()

const systems::OutputPort<T>& get_reaction_forces_output_port ( ) const

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 frame Jc 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, at Jc, 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 force F_CJc_Jc applied on the joint's child body C (Joint::child_body()), at the joint's child frame Jc (Joint::frame_on_child()) and expressed in frame Jc.

In a discrete-time plant, the use_sampled_output_ports setting affects the output of this port. See 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.

Exceptions
std::exceptionif called pre-finalize.

◆ get_sap_near_rigid_threshold()

double get_sap_near_rigid_threshold ( ) const
Returns
the SAP near rigid regime threshold.
See also
See set_sap_near_rigid_threshold().

◆ get_source_id()

std::optional<geometry::SourceId> get_source_id ( ) const

Returns the unique id identifying this plant as a source for a SceneGraph.

Returns nullopt if this plant did not register any geometry. This method can be called at any time during the lifetime of this plant to query if this 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() [1/2]

const systems::OutputPort<T>& get_state_output_port ( ) const

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.
Exceptions
std::exceptionif called before Finalize().

◆ get_state_output_port() [2/2]

const systems::OutputPort<T>& get_state_output_port ( ModelInstanceIndex  model_instance) const

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.
Exceptions
std::exceptionif called before Finalize().
std::exceptionif the model instance does not exist.

◆ get_weld_constraint_specs() [1/2]

const internal::WeldConstraintSpec& get_weld_constraint_specs ( MultibodyConstraintId  id) const

(Internal use only) Returns the weld constraint specification corresponding to id

Exceptions
ifid is not a valid identifier for a weld constraint.

◆ get_weld_constraint_specs() [2/2]

const std::map<MultibodyConstraintId, internal::WeldConstraintSpec>& get_weld_constraint_specs ( ) const

(Internal use only) Returns a reference to the all of the weld constraints in this plant as a map from MultibodyConstraintId to WeldConstraintSpec.

◆ GetAccelerationLowerLimits()

VectorX<double> GetAccelerationLowerLimits ( ) const

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.

Exceptions
std::exceptionif called pre-finalize.

◆ GetAccelerationUpperLimits()

VectorX<double> GetAccelerationUpperLimits ( ) const

Upper limit analog of GetAccelerationsLowerLimits(), where any unbounded or unspecified limits will be +infinity.

See also
GetAccelerationLowerLimits() for more information.

◆ GetActuatedJointIndices()

std::vector<JointIndex> GetActuatedJointIndices ( ModelInstanceIndex  model_instance) const

Returns a list of actuated joint indices associated with model_instance.

Exceptions
std::exceptionif called pre-finalize.

◆ GetActuationFromArray()

VectorX<T> GetActuationFromArray ( ModelInstanceIndex  model_instance,
const Eigen::Ref< const VectorX< T >> &  u 
) const

Returns a vector of actuation values for model_instance from a vector u of actuation values for the entire plant model.

Refer to Actuation for further details.

Parameters
[in]uActuation values for the entire model. The actuation value in u for a particular actuator must be found at offset JointActuator::input_start().
Returns
Actuation values for model_instance, ordered by monotonically increasing JointActuatorIndex.
Exceptions
std::exceptionif u is not of size MultibodyPlant::num_actuated_dofs().

◆ GetActuatorNames() [1/2]

std::vector<std::string> GetActuatorNames ( bool  add_model_instance_prefix = true) const

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 using add_model_instance_prefix.

The returned names are guaranteed to be unique if add_model_instance_prefix is true (the default).

Exceptions
std::exceptionif the plant is not finalized.

◆ GetActuatorNames() [2/2]

std::vector<std::string> GetActuatorNames ( ModelInstanceIndex  model_instance,
bool  add_model_instance_prefix = false 
) const

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 using add_model_instance_prefix.

The returned names are guaranteed to be unique.

Exceptions
std::exceptionif the plant is not finalized or if the model_instance is invalid.

◆ GetBodiesKinematicallyAffectedBy()

std::vector<BodyIndex> GetBodiesKinematicallyAffectedBy ( const std::vector< JointIndex > &  joint_indexes) const

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().

Exceptions
std::exceptionif any of the given joint has an invalid index, doesn't correspond to a mobilizer, or is welded.

◆ GetBodiesWeldedTo()

std::vector<const RigidBody<T>*> GetBodiesWeldedTo ( const RigidBody< T > &  body) const

Returns all bodies that are transitively welded, or rigidly affixed, to body, per these two definitions:

  1. 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:

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.
Exceptions
std::exceptionif body is not part of this plant.

◆ GetBodyByName() [1/2]

const RigidBody<T>& GetBodyByName ( std::string_view  name) const

Returns a constant reference to a body that is identified by the string name in this MultibodyPlant.

Exceptions
std::exceptionif there is no body with the requested name.
std::exceptionif 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() [2/2]

const RigidBody<T>& GetBodyByName ( std::string_view  name,
ModelInstanceIndex  model_instance 
) const

Returns a constant reference to the body that is uniquely identified by the string name and model_instance in this MultibodyPlant.

Exceptions
std::exceptionif 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()

std::optional<geometry::FrameId> GetBodyFrameIdIfExists ( BodyIndex  body_index) const

If the body with body_index belongs to the called plant, it returns the geometry::FrameId associated with it.

Otherwise, it returns nullopt.

◆ GetBodyFrameIdOrThrow()

geometry::FrameId GetBodyFrameIdOrThrow ( BodyIndex  body_index) const

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.

Exceptions
std::exceptionif the called plant does not have the body indicated by body_index.

◆ GetBodyFromFrameId()

const RigidBody<T>* GetBodyFromFrameId ( geometry::FrameId  frame_id) const

Given a geometry frame identifier, returns a pointer to the body associated with that id (nullptr if there is no such body).

◆ GetBodyIndices()

std::vector<BodyIndex> GetBodyIndices ( ModelInstanceIndex  model_instance) const

Returns a list of body indices associated with model_instance.

◆ GetCollisionGeometriesForBody()

const std::vector<geometry::GeometryId>& GetCollisionGeometriesForBody ( const RigidBody< T > &  body) const

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()

bool GetConstraintActiveStatus ( const systems::Context< T > &  context,
MultibodyConstraintId  id 
) const

Returns the active status of the constraint given by id in context.

Exceptions
std::exceptionif the MultibodyPlant has not been finalized.
std::exceptionif id does not belong to any multibody constraint in context.

◆ GetConstraintIds()

std::vector<MultibodyConstraintId> GetConstraintIds ( ) const

Returns a list of all constraint identifiers.

The returned vector becomes invalid after any calls to Add*Constraint() or RemoveConstraint().

◆ GetDefaultContactSurfaceRepresentation()

static geometry::HydroelasticContactRepresentation GetDefaultContactSurfaceRepresentation ( double  time_step)
static

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()

math::RigidTransform<double> GetDefaultFreeBodyPose ( const RigidBody< T > &  body) const

Gets the default pose of body as set by SetDefaultFreeBodyPose().

If no pose is specified for the body, returns the identity pose.

Parameters
[in]bodyRigidBody whose default pose will be retrieved.
Return values
X_PBThe pose of the free body relative to its parent frame.
Note
The parent frame is not necessarily the world frame. See above for details.

◆ GetDefaultPositions() [1/2]

VectorX<T> GetDefaultPositions ( ) const

Gets the default positions for the plant, which can be changed via SetDefaultPositions().

Exceptions
std::exceptionif the plant is not finalized.

◆ GetDefaultPositions() [2/2]

VectorX<T> GetDefaultPositions ( ModelInstanceIndex  model_instance) const

Gets the default positions for the plant for a given model instance, which can be changed via SetDefaultPositions().

Exceptions
std::exceptionif the plant is not finalized, or if the model_instance is invalid,

◆ GetEffortLowerLimits()

VectorX<double> GetEffortLowerLimits ( ) const

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()
Exceptions
std::exceptionif called pre-finalize.

◆ GetEffortUpperLimits()

VectorX<double> GetEffortUpperLimits ( ) const

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()
Exceptions
std::exceptionif called pre-finalize.

◆ GetFloatingBaseBodies()

std::unordered_set<BodyIndex> GetFloatingBaseBodies ( ) const

Returns the set of body indices corresponding to the floating base bodies in the model, in no particular order.

Exceptions
std::exceptionif called pre-finalize, see Finalize().

◆ GetForceElement()

const ForceElementType<T>& GetForceElement ( ForceElementIndex  force_element_index) const

Returns a constant reference to a force element identified by its unique index in this MultibodyPlant.

If the optional template argument is supplied, then the returned value is downcast to the specified ForceElementType.

Template Parameters
ForceElementTypeThe specific type of the ForceElement to be retrieved. It must be a subclass of ForceElement.
Exceptions
std::exceptionif the force element is not of type ForceElementType or if there is no ForceElement with that index.

◆ GetFrameByName() [1/2]

const Frame<T>& GetFrameByName ( std::string_view  name) const

Returns a constant reference to a frame that is identified by the string name in this model.

Exceptions
std::exceptionif there is no frame with the requested name.
std::exceptionif 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() [2/2]

const Frame<T>& GetFrameByName ( std::string_view  name,
ModelInstanceIndex  model_instance 
) const

Returns a constant reference to the frame that is uniquely identified by the string name in model_instance.

Exceptions
std::exceptionif there is no frame with the requested name.
std::exceptionif 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()

std::vector<FrameIndex> GetFrameIndices ( ModelInstanceIndex  model_instance) const

Returns a list of frame indices associated with model_instance.

◆ GetFreeBodyPose()

math::RigidTransform<T> GetFreeBodyPose ( const systems::Context< T > &  context,
const RigidBody< T > &  body 
) const

Gets the pose of a given body in the parent frame P.

Note
The parent frame is not necessarily the world frame. See above for details. To acquire X_WB, regardless of what P is, kinematics need to be evaluated by calling EvalBodyPoseInWorld().
Exceptions
std::exceptionif body is not a free body in the model.
std::exceptionif called pre-finalize.

◆ GetJointActuatorByName() [1/2]

const JointActuator<T>& GetJointActuatorByName ( std::string_view  name) const

Returns a constant reference to an actuator that is identified by the string name in this MultibodyPlant.

Exceptions
std::exceptionif there is no actuator with the requested name.
std::exceptionif 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() [2/2]

const JointActuator<T>& GetJointActuatorByName ( std::string_view  name,
ModelInstanceIndex  model_instance 
) const

Returns a constant reference to the actuator that is uniquely identified by the string name and model_instance in this MultibodyPlant.

Exceptions
std::exceptionif there is no actuator with the requested name.
std::exceptionif 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() [1/2]

const std::vector<JointActuatorIndex>& GetJointActuatorIndices ( ) const

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() [2/2]

std::vector<JointActuatorIndex> GetJointActuatorIndices ( ModelInstanceIndex  model_instance) const

Returns a list of joint actuator indices associated with model_instance.

The vector is ordered by monotonically increasing JointActuatorIndex.

Exceptions
std::exceptionif called pre-finalize.

◆ GetJointByName()

const JointType<T>& GetJointByName ( std::string_view  name,
std::optional< ModelInstanceIndex model_instance = std::nullopt 
) const

Returns a constant reference to a joint that is identified by the string name in this MultibodyPlant.

If the optional template argument is supplied, then the returned value is downcast to the specified JointType.

Template Parameters
JointTypeThe specific type of the Joint to be retrieved. It must be a subclass of Joint.
Exceptions
std::exceptionif the named joint is not of type JointType or if there is no Joint with that name.
std::exceptionif 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.

◆ GetJointIndices() [1/2]

const std::vector<JointIndex>& GetJointIndices ( ) const

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() [2/2]

std::vector<JointIndex> GetJointIndices ( ModelInstanceIndex  model_instance) const

Returns a list of joint indices associated with model_instance.

◆ GetModelInstanceByName()

ModelInstanceIndex GetModelInstanceByName ( std::string_view  name) const

Returns the index to the model instance that is uniquely identified by the string name in this MultibodyPlant.

Exceptions
std::exceptionif 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()

const std::string& GetModelInstanceName ( ModelInstanceIndex  model_instance) const

Returns the name of a model_instance.

Exceptions
std::exceptionwhen model_instance does not correspond to a model in this model.

◆ GetMutableJointByName()

JointType<T>& GetMutableJointByName ( std::string_view  name,
std::optional< ModelInstanceIndex model_instance = std::nullopt 
)

A version of GetJointByName that returns a mutable reference.

See also
GetJointByName.

◆ GetMutableSceneGraphPreFinalize()

geometry::SceneGraph<T>* GetMutableSceneGraphPreFinalize ( )

(Internal use only) Returns a mutable pointer to the SceneGraph that this plant is registered as a source for.

This method can only be used pre-Finalize.

Exceptions
std::exceptionif is_finalized() == true || geometry_source_is_registered() == false

◆ GetPositionLowerLimits()

VectorX<double> GetPositionLowerLimits ( ) const

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.

Exceptions
std::exceptionif called pre-finalize.

◆ GetPositionNames() [1/2]

std::vector<std::string> GetPositionNames ( bool  add_model_instance_prefix = true,
bool  always_add_suffix = true 
) const

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 using add_model_instance_prefix and always_add_suffix.

Parameters
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 is true (the default).

Exceptions
std::exceptionif the plant is not finalized.

◆ GetPositionNames() [2/2]

std::vector<std::string> GetPositionNames ( ModelInstanceIndex  model_instance,
bool  add_model_instance_prefix = false,
bool  always_add_suffix = true 
) const

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 using add_model_instance_prefix and always_add_suffix.

Parameters
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.

Exceptions
std::exceptionif the plant is not finalized or if the model_instance is invalid.

◆ GetPositions() [1/3]

Eigen::VectorBlock<const VectorX<T> > GetPositions ( const systems::Context< T > &  context) const

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.
Exceptions
std::exceptionif context does not correspond to the Context for a multibody model.

◆ GetPositions() [2/3]

VectorX<T> GetPositions ( const systems::Context< T > &  context,
ModelInstanceIndex  model_instance 
) const

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 with model_instance by copying from context.
Exceptions
std::exceptionif context does not correspond to the Context for a multibody model or model_instance is invalid.

◆ GetPositions() [3/3]

void GetPositions ( const systems::Context< T > &  context,
ModelInstanceIndex  model_instance,
EigenPtr< VectorX< T >>  q_out 
) const

(Advanced) Populates output vector q_out with the generalized positions q of a specified model instance in a given Context.

Note
q_out is a dense vector of dimension ‘num_positions(model_instance)’ associated with model_instance and is populated by copying from context.
This function is guaranteed to allocate no heap.
Exceptions
std::exceptionif context does not correspond to the Context for a multibody model or model_instance is invalid.

◆ GetPositionsAndVelocities() [1/3]

Eigen::VectorBlock<const VectorX<T> > GetPositionsAndVelocities ( const systems::Context< T > &  context) const

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.
Exceptions
std::exceptionif context does not correspond to the Context for a multibody model.

◆ GetPositionsAndVelocities() [2/3]

VectorX<T> GetPositionsAndVelocities ( const systems::Context< T > &  context,
ModelInstanceIndex  model_instance 
) const

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 with model_instance by copying from context.
Exceptions
std::exceptionif context does not correspond to the Context for a multibody model or model_instance is invalid.

◆ GetPositionsAndVelocities() [3/3]

void GetPositionsAndVelocities ( const systems::Context< T > &  context,
ModelInstanceIndex  model_instance,
EigenPtr< VectorX< T >>  qv_out 
) const

(Advanced) Populates output vector qv_out representing the generalized positions q and generalized velocities v of a specified model instance in a given Context.

Note
qv_out is a dense vector of dimensions num_positions(model_instance) + num_velocities(model_instance) associated with model_instance and is populated by copying from context.
This function is guaranteed to allocate no heap.
Exceptions
std::exceptionif context does not correspond to the Context for a multibody model or model_instance is invalid.
std::exceptionif qv_out does not have size num_positions(model_instance) + num_velocities(model_instance)

◆ GetPositionsFromArray() [1/2]

VectorX<T> GetPositionsFromArray ( ModelInstanceIndex  model_instance,
const Eigen::Ref< const VectorX< T >> &  q 
) const

Returns a vector of generalized positions for model_instance from a vector q_array of generalized positions for the entire model model.

This method throws an exception if q is not of size MultibodyPlant::num_positions().

◆ GetPositionsFromArray() [2/2]

void GetPositionsFromArray ( ModelInstanceIndex  model_instance,
const Eigen::Ref< const VectorX< T >> &  q,
EigenPtr< VectorX< T >>  q_out 
) const

(Advanced) Populates output vector q_out and with the generalized positions for model_instance from a vector q of generalized positions for the entire model.

This method throws an exception if q is not of size MultibodyPlant::num_positions().

◆ GetPositionUpperLimits()

VectorX<double> GetPositionUpperLimits ( ) const

Upper limit analog of GetPositionLowerLimits(), where any unbounded or unspecified limits will be +infinity.

See also
GetPositionLowerLimits() for more information.

◆ GetRigidBodyByName() [1/2]

const RigidBody<T>& GetRigidBodyByName ( std::string_view  name) const

Returns a constant reference to a rigid body that is identified by the string name in this model.

Exceptions
std::exceptionif there is no body with the requested name.
std::exceptionif the body name occurs in multiple model instances.
std::exceptionif 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() [2/2]

const RigidBody<T>& GetRigidBodyByName ( std::string_view  name,
ModelInstanceIndex  model_instance 
) const

Returns a constant reference to the rigid body that is uniquely identified by the string name in model_instance.

Exceptions
std::exceptionif there is no body with the requested name.
std::exceptionif the requested body is not a RigidBody.
std::exceptionif 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() [1/2]

std::vector<std::string> GetStateNames ( bool  add_model_instance_prefix = true) const

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 using add_model_instance_prefix.

The returned names are guaranteed to be unique if add_model_instance_prefix is true (the default).

Exceptions
std::exceptionif the plant is not finalized.

◆ GetStateNames() [2/2]

std::vector<std::string> GetStateNames ( ModelInstanceIndex  model_instance,
bool  add_model_instance_prefix = false 
) const

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 using add_model_instance_prefix.

The returned names are guaranteed to be unique.

Exceptions
std::exceptionif the plant is not finalized or if the model_instance is invalid.

◆ GetTopologyGraphvizString()

std::string GetTopologyGraphvizString ( ) const

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()

const RigidBody<T>& GetUniqueFreeBaseBodyOrThrow ( ModelInstanceIndex  model_instance) const

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.

Exceptions
std::exceptionif called pre-finalize.
std::exceptionif model_instance is not valid.
std::exceptionif HasUniqueFreeBaseBody(model_instance) == false.

◆ GetVelocities() [1/3]

Eigen::VectorBlock<const VectorX<T> > GetVelocities ( const systems::Context< T > &  context) const

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.
Exceptions
std::exceptionif context does not correspond to the Context for a multibody model.

◆ GetVelocities() [2/3]

VectorX<T> GetVelocities ( const systems::Context< T > &  context,
ModelInstanceIndex  model_instance 
) const

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 with model_instance by copying from context.
Exceptions
std::exceptionif context does not correspond to the Context for a multibody model or model_instance is invalid.

◆ GetVelocities() [3/3]

void GetVelocities ( const systems::Context< T > &  context,
ModelInstanceIndex  model_instance,
EigenPtr< VectorX< T >>  v_out 
) const

(Advanced) Populates output vector v_out with the generalized velocities v of a specified model instance in a given Context.

Note
v_out is a dense vector of dimension num_velocities(model_instance) associated with model_instance and is populated by copying from context.
This function is guaranteed to allocate no heap.
Exceptions
std::exceptionif context does not correspond to the Context for a multibody model or model_instance is invalid.

◆ GetVelocitiesFromArray() [1/2]

VectorX<T> GetVelocitiesFromArray ( ModelInstanceIndex  model_instance,
const Eigen::Ref< const VectorX< T >> &  v 
) const

Returns a vector of generalized velocities for model_instance from a vector v of generalized velocities for the entire MultibodyPlant model.

This method throws an exception if the input array is not of size MultibodyPlant::num_velocities().

◆ GetVelocitiesFromArray() [2/2]

void GetVelocitiesFromArray ( ModelInstanceIndex  model_instance,
const Eigen::Ref< const VectorX< T >> &  v,
EigenPtr< VectorX< T >>  v_out 
) const

(Advanced) Populates output vector v_out with the generalized velocities for model_instance from a vector v of generalized velocities for the entire model.

This method throws an exception if v is not of size MultibodyPlant::num_velocities().

◆ GetVelocityLowerLimits()

VectorX<double> GetVelocityLowerLimits ( ) const

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.

Exceptions
std::exceptionif called pre-finalize.

◆ GetVelocityNames() [1/2]

std::vector<std::string> GetVelocityNames ( bool  add_model_instance_prefix = true,
bool  always_add_suffix = true 
) const

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 using add_model_instance_prefix and always_add_suffix.

Parameters
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 is true (the default).

Exceptions
std::exceptionif the plant is not finalized.

◆ GetVelocityNames() [2/2]

std::vector<std::string> GetVelocityNames ( ModelInstanceIndex  model_instance,
bool  add_model_instance_prefix = false,
bool  always_add_suffix = true 
) const

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 using add_model_instance_prefix and always_add_suffix.

Parameters
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.

Exceptions
std::exceptionif the plant is not finalized or if the model_instance is invalid.

◆ GetVelocityUpperLimits()

VectorX<double> GetVelocityUpperLimits ( ) const

Upper limit analog of GetVelocitysLowerLimits(), where any unbounded or unspecified limits will be +infinity.

See also
GetVelocityLowerLimits() for more information.

◆ GetVisualGeometriesForBody()

const std::vector<geometry::GeometryId>& GetVisualGeometriesForBody ( const RigidBody< T > &  body) const

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()

const UniformGravityFieldElement<T>& gravity_field ( ) const

An accessor to the current gravity field.

◆ has_joint()

bool has_joint ( JointIndex  joint_index) const

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()

bool has_joint_actuator ( JointActuatorIndex  actuator_index) const

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()

bool has_sampled_output_ports ( ) const

(Advanced) If this plant is continuous (i.e., is_discrete() is false), returns false.

If this 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 for details.

◆ HasBodyNamed() [1/2]

bool HasBodyNamed ( std::string_view  name) const
Returns
true if a body named name was added to the MultibodyPlant.
See also
AddRigidBody().
Exceptions
std::exceptionif the body name occurs in multiple model instances.

◆ HasBodyNamed() [2/2]

bool HasBodyNamed ( std::string_view  name,
ModelInstanceIndex  model_instance 
) const
Returns
true if a body named name was added to the MultibodyPlant in model_instance.
See also
AddRigidBody().
Exceptions
std::exceptionif model_instance is not valid for this model.

◆ HasFrameNamed() [1/2]

bool HasFrameNamed ( std::string_view  name) const
Returns
true if a frame named name was added to the model.
See also
AddFrame().
Exceptions
std::exceptionif the frame name occurs in multiple model instances.

◆ HasFrameNamed() [2/2]

bool HasFrameNamed ( std::string_view  name,
ModelInstanceIndex  model_instance 
) const
Returns
true if a frame named name was added to model_instance.
See also
AddFrame().
Exceptions
std::exceptionif model_instance is not valid for this model.

◆ HasJointActuatorNamed() [1/2]

bool HasJointActuatorNamed ( std::string_view  name) const
Returns
true if an actuator named name was added to this model.
See also
AddJointActuator().
Exceptions
std::exceptionif the actuator name occurs in multiple model instances.

◆ HasJointActuatorNamed() [2/2]

bool HasJointActuatorNamed ( std::string_view  name,
ModelInstanceIndex  model_instance 
) const
Returns
true if an actuator named name was added to model_instance.
See also
AddJointActuator().
Exceptions
std::exceptionif model_instance is not valid for this model.

◆ HasJointNamed() [1/2]

bool HasJointNamed ( std::string_view  name) const
Returns
true if a joint named name was added to this model.
See also
AddJoint().
Exceptions
std::exceptionif the joint name occurs in multiple model instances.

◆ HasJointNamed() [2/2]

bool HasJointNamed ( std::string_view  name,
ModelInstanceIndex  model_instance 
) const
Returns
true if a joint named name was added to model_instance.
See also
AddJoint().
Exceptions
std::exceptionif model_instance is not valid for this model.

◆ HasModelInstanceNamed()

bool HasModelInstanceNamed ( std::string_view  name) const
Returns
true if a model instance named name was added to this model.
See also
AddModelInstance().

◆ HasUniqueFreeBaseBody()

bool HasUniqueFreeBaseBody ( ModelInstanceIndex  model_instance) const

Return true if there exists a unique base body in the model given by model_instance and that unique base body is free.

Exceptions
std::exceptionif called pre-finalize.
std::exceptionif model_instance is not valid.

◆ is_finalized()

bool is_finalized ( ) const

Returns true if this MultibodyPlant was finalized with a call to Finalize().

See also
Finalize().

◆ is_gravity_enabled()

bool is_gravity_enabled ( ModelInstanceIndex  model_instance) const
Returns
true iff gravity is enabled for model_instance.
See also
set_gravity_enabled().
Exceptions
std::exceptionif the model instance is invalid.

◆ IsAnchored()

bool IsAnchored ( const RigidBody< T > &  body) const

Returns true if body is anchored (i.e.

the kinematic path between body and the world only contains weld joints.)

Exceptions
std::exceptionif called pre-finalize.

◆ IsVelocityEqualToQDot()

bool IsVelocityEqualToQDot ( ) const

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()

MatrixX<T> MakeActuationMatrix ( ) const

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 size nv x nu with nu equal to num_actuated_dofs() and nv 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 to Joint::velocity_start().

Warning
B is a permutation matrix. While making a permutation has O(n) complexity, making a full B matrix has O(n²) complexity. For most applications this cost can be neglected but it could become significant for very large systems.

◆ MakeActuationMatrixPseudoinverse()

Eigen::SparseMatrix<double> MakeActuationMatrixPseudoinverse ( ) const

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() [1/2]

MatrixX<double> MakeActuatorSelectorMatrix ( const std::vector< JointActuatorIndex > &  user_to_actuator_index_map) const

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 for this full model.

The mapping, or selection, is returned in the form of a selector matrix Su such that u = 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 in user_to_actuator_index_map. The actuation value in the full vector of actuation values u for a particular actuator can be found at offset JointActuator::input_start().

◆ MakeActuatorSelectorMatrix() [2/2]

MatrixX<double> MakeActuatorSelectorMatrix ( const std::vector< JointIndex > &  user_to_joint_index_map) const

Alternative signature to build an actuation selector matrix Su such that u = 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 by user_to_joint_index_map.

It is assumed that all joints referenced by user_to_joint_index_map are actuated. See MakeActuatorSelectorMatrix(const std::vector<JointActuatorIndex>&) for details.

Exceptions
std::exceptionif any of the joints in user_to_joint_index_map does not have an actuator.

◆ MakeQDotToVelocityMap()

Eigen::SparseMatrix<T> MakeQDotToVelocityMap ( const systems::Context< T > &  context) const

Returns the matrix N⁺(q), which maps v = 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.

Parameters
[in]contextThe context containing the state of the model.
See also
MapVelocityToQDot()

◆ MakeStateSelectorMatrix()

MatrixX<double> MakeStateSelectorMatrix ( const std::vector< JointIndex > &  user_to_joint_index_map) const

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 that xₛ = 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 in xₛ = [qₛ, vₛ]. The positions in qₛ are a concatenation of the positions for each joint in the order they appear in user_to_joint_index_map. That is, the positions for user_to_joint_index_map[0] are first, followed by the positions for user_to_joint_index_map[1], etc. Similarly for the selected velocities vₛ.

Exceptions
std::exceptionif there are repeated indices in user_to_joint_index_map.

◆ MakeVelocityToQDotMap()

Eigen::SparseMatrix<T> MakeVelocityToQDotMap ( const systems::Context< T > &  context) const

Returns the matrix N(q), which maps q̇ = 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 of N(q); call MakeQDotToVelocityMap instead. This method is, in the worst case, O(n), where n is the number of joints.

Parameters
[in]contextThe context containing the state of the model.
See also
MapVelocityToQDot()

◆ MapQDotToVelocity()

void MapQDotToVelocity ( const systems::Context< T > &  context,
const Eigen::Ref< const VectorX< T >> &  qdot,
EigenPtr< VectorX< T >>  v 
) const

Transforms the time derivative qdot of the generalized positions vector q (stored in context) to generalized velocities v.

v and are related linearly by q̇ = N(q)⋅v. Although N(q) is not necessarily square, its left pseudo-inverse N⁺(q) can be used to invert that relationship without residual error, provided that qdot is in the range space of N(q) (that is, if it could have been produced as q̇ = N(q)⋅v for some v). Using the configuration q stored in the given context this method calculates v = N⁺(q)⋅q̇.

Parameters
[in]contextThe context containing the state of the model.
[in]qdotA vector containing the time derivatives of the generalized positions. This method aborts if qdot is not of size num_positions().
[out]vA 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()
Mobilizer::MapQDotToVelocity()

◆ MapVelocityToQDot()

void MapVelocityToQDot ( const systems::Context< T > &  context,
const Eigen::Ref< const VectorX< T >> &  v,
EigenPtr< VectorX< T >>  qdot 
) const

Transforms generalized velocities v to time derivatives qdot of the generalized positions vector q (stored in context).

v and qdot are related linearly by q̇ = N(q)⋅v. Using the configuration q stored in the given context this method calculates q̇ = N(q)⋅v.

Parameters
[in]contextThe context containing the state of the model.
[in]vA vector of generalized velocities for this model. This method aborts if v is not of size num_velocities().
[out]qdotA valid (non-null) pointer to a vector in ℝⁿ with n being the number of generalized positions in this model, given by num_positions(). This method aborts if qdot is nullptr or if it is not of size num_positions().
See also
MapQDotToVelocity()
Mobilizer::MapVelocityToQDot()

◆ mutable_deformable_model()

DeformableModel<T>& mutable_deformable_model ( )

Returns a mutable reference to the DeformableModel owned by this plant.

Exceptions
std::exceptionif 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()

UniformGravityFieldElement<T>& mutable_gravity_field ( )

A mutable accessor to the current gravity field.

◆ num_actuated_dofs() [1/2]

int num_actuated_dofs ( ) const

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() [2/2]

int num_actuated_dofs ( ModelInstanceIndex  model_instance) const

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().

Exceptions
std::exceptionif called pre-finalize.

◆ num_actuators() [1/2]

int num_actuators ( ) const

Returns the number of joint actuators in the model.

See also
AddJointActuator().

◆ num_actuators() [2/2]

int num_actuators ( ModelInstanceIndex  model_instance) const

Returns the number of actuators for a specific model instance.

Exceptions
std::exceptionif called pre-finalize.

◆ num_ball_constraints()

int num_ball_constraints ( ) const

Returns the total number of ball constraints specified by the user.

◆ num_bodies()

int num_bodies ( ) const

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()

int num_collision_geometries ( ) const

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()

int num_constraints ( ) const

Returns the total number of constraints specified by the user.

◆ num_coupler_constraints()

int num_coupler_constraints ( ) const

Returns the total number of coupler constraints specified by the user.

◆ num_distance_constraints()

int num_distance_constraints ( ) const

Returns the total number of distance constraints specified by the user.

◆ num_force_elements()

int num_force_elements ( ) const

Returns the number of ForceElement objects.

See also
AddForceElement().

◆ num_frames()

int num_frames ( ) const

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()

int num_joints ( ) const

Returns the number of joints in the model.

See also
AddJoint().

◆ num_model_instances()

int num_model_instances ( ) const

Returns the number of model instances in the model.

See also
AddModelInstance().

◆ num_multibody_states() [1/2]

int num_multibody_states ( ) const

Returns the size of the multibody system state vector x = [q v].

This will be num_positions() plus num_velocities().

Exceptions
std::exceptionif called pre-finalize.

◆ num_multibody_states() [2/2]

int num_multibody_states ( ModelInstanceIndex  model_instance) const

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) plus num_velocities(model_instance).

Exceptions
std::exceptionif called pre-finalize.

◆ num_positions() [1/2]

int num_positions ( ) const

Returns the size of the generalized position vector q for this model.

Exceptions
std::exceptionif called pre-finalize.

◆ num_positions() [2/2]

int num_positions ( ModelInstanceIndex  model_instance) const

Returns the size of the generalized position vector qᵢ for model instance i.

Exceptions
std::exceptionif called pre-finalize.

◆ num_velocities() [1/2]

int num_velocities ( ) const

Returns the size of the generalized velocity vector v for this model.

Exceptions
std::exceptionif called pre-finalize.

◆ num_velocities() [2/2]

int num_velocities ( ModelInstanceIndex  model_instance) const

Returns the size of the generalized velocity vector vᵢ for model instance i.

Exceptions
std::exceptionif called pre-finalize.

◆ num_visual_geometries()

int num_visual_geometries ( ) const

Returns the number of geometries registered for visualization.

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_weld_constraints()

int num_weld_constraints ( ) const

Returns the total number of weld constraints specified by the user.

◆ NumBodiesWithName()

int NumBodiesWithName ( std::string_view  name) const
Returns
The total number of bodies (across all model instances) with the given name.

◆ operator=() [1/2]

MultibodyPlant& operator= ( const MultibodyPlant< T > &  )
delete

◆ operator=() [2/2]

MultibodyPlant& operator= ( MultibodyPlant< T > &&  )
delete

◆ RegisterAsSourceForSceneGraph()

geometry::SourceId RegisterAsSourceForSceneGraph ( geometry::SceneGraph< T > *  scene_graph)

Registers this plant to serve as a source for an instance of SceneGraph.

This registration allows MultibodyPlant to register geometry with scene_graph for visualization and/or collision queries. The string returned by this->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 argument scene_graph points to. Failure to do so will result in runtime exceptions.

Parameters
scene_graphA 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 in scene_graph. It can also later on be retrieved with get_source_id().
Exceptions
std::exceptionif called post-finalize.
std::exceptionif scene_graph is the nullptr.
std::exceptionif called more than once.

◆ RegisterCollisionGeometry() [1/2]

geometry::GeometryId RegisterCollisionGeometry ( const RigidBody< T > &  body,
const math::RigidTransform< double > &  X_BG,
const geometry::Shape shape,
const std::string &  name,
geometry::ProximityProperties  properties 
)

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.

Parameters
[in]bodyThe body for which geometry is being registered.
[in]X_BGThe fixed pose of the geometry frame G in the body frame B.
[in]shapeThe geometry::Shape used for visualization. E.g.: geometry::Sphere, geometry::Cylinder, etc.
[in]propertiesThe proximity properties associated with the collision geometry. They must include the (material, coulomb_friction) property of type CoulombFriction<double>.
Exceptions
std::exceptionif called post-finalize or if the properties are missing the coulomb friction property (or if it is of the wrong type).

◆ RegisterCollisionGeometry() [2/2]

geometry::GeometryId RegisterCollisionGeometry ( const RigidBody< T > &  body,
const math::RigidTransform< double > &  X_BG,
const geometry::Shape shape,
const std::string &  name,
const CoulombFriction< double > &  coulomb_friction 
)

Overload which specifies a single property: coulomb_friction.

◆ RegisterVisualGeometry() [1/3]

geometry::GeometryId RegisterVisualGeometry ( const RigidBody< T > &  body,
const math::RigidTransform< double > &  X_BG,
const geometry::Shape shape,
const std::string &  name,
const geometry::IllustrationProperties properties 
)

Registers geometry in a SceneGraph with a given geometry::Shape to be used for visualization of a given body.

Note
Currently, the visual geometry will also be assigned a perception role. Its render label's value will be equal to the body's index and its perception color will be the same as its illustration color (defaulting to gray if no color is provided). This behavior will change in the near future and code that directly relies on this behavior will break.
Parameters
[in]bodyThe body for which geometry is being registered.
[in]X_BGThe fixed pose of the geometry frame G in the body frame B.
[in]shapeThe geometry::Shape used for visualization. E.g.: geometry::Sphere, geometry::Cylinder, etc.
[in]nameThe name for the geometry. It must satisfy the requirements defined in drake::geometry::GeometryInstance.
[in]propertiesThe illustration properties for this geometry.
Exceptions
std::exceptionif called post-finalize.
std::exceptionif scene_graph does not correspond to the same instance with which RegisterAsSourceForSceneGraph() was called.
Returns
the id for the registered geometry.

◆ RegisterVisualGeometry() [2/3]

geometry::GeometryId RegisterVisualGeometry ( const RigidBody< T > &  body,
const math::RigidTransform< double > &  X_BG,
const geometry::Shape shape,
const std::string &  name,
const Vector4< double > &  diffuse_color 
)

Overload for visual geometry registration; it converts the diffuse_color (RGBA with values in the range [0, 1]) into a geometry::DrakeVisualizer-compatible set of geometry::IllustrationProperties.

◆ RegisterVisualGeometry() [3/3]

geometry::GeometryId RegisterVisualGeometry ( const RigidBody< T > &  body,
const math::RigidTransform< double > &  X_BG,
const geometry::Shape shape,
const std::string &  name 
)

Overload for visual geometry registration; it relies on the downstream geometry::IllustrationProperties consumer to provide default parameter values (see Geometry Queries and Roles for details).

◆ RemoveConstraint()

void RemoveConstraint ( MultibodyConstraintId  id)

Removes the constraint id from the plant.

Note that this will not remove constraints registered directly with DeformableModel.

Exceptions
std::exceptionif the MultibodyPlant has already been finalized.
std::exceptionif id does not identify any multibody constraint in this plant.

◆ RemoveJoint()

void RemoveJoint ( const Joint< T > &  joint)

Removes and deletes joint from this MultibodyPlant.

Any existing references to joint will become invalid, and future calls to get_joint(joint_index) will throw an exception. Other elements of the plant may depend on joint at the time of removal and should be removed first. For example, a JointActuator that depends on joint 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.

Exceptions
std::exceptionif the plant is already finalized.
std::exceptionif the plant contains a non-zero number of user-added force elements or user-added constraints.
std::exceptionif 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 from 0 to num_joints() - 1. Instead users should use the provided GetJointIndices() and GetJointIndices(ModelIndex) functions:
for (JointIndex index : plant.GetJointIndices()) {
const Joint<double>& joint = plant.get_joint(index);
...
}

◆ RemoveJointActuator()

void RemoveJointActuator ( const JointActuator< T > &  actuator)

Removes and deletes actuator from this MultibodyPlant.

Any existing references to actuator will become invalid, and future calls to get_joint_actuator(actuator_index) will throw an exception.

Exceptions
std::exceptionif the plant is already finalized.
See also
AddJointActuator()

◆ RenameModelInstance()

void RenameModelInstance ( ModelInstanceIndex  model_instance,
const std::string &  name 
)

Renames an existing model instance.

Parameters
[in]model_instanceThe instance to rename.
[in]nameA string that uniquely identifies the instance within this model.
Exceptions
std::exceptionif called after Finalize().
std::exceptionif model_instance is not a valid index.
std::exceptionif HasModelInstanceNamed(name) is true.

◆ set_adjacent_bodies_collision_filters()

void set_adjacent_bodies_collision_filters ( bool  value)

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.

Exceptions
std::exceptioniff called post-finalize.

◆ set_contact_model()

void set_contact_model ( ContactModel  model)

Sets the contact model to be used by this MultibodyPlant, see ContactModel for available options.

The default contact model is ContactModel::kHydroelasticWithFallback.

Exceptions
std::exceptioniff called post-finalize.

◆ set_contact_surface_representation()

void set_contact_surface_representation ( geometry::HydroelasticContactRepresentation  representation)

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.

Exceptions
std::exceptionif called post-finalize.

◆ set_discrete_contact_approximation()

void set_discrete_contact_approximation ( DiscreteContactApproximation  approximation)

Sets the discrete contact model approximation.

Note
Calling this method also sets the contact solver type (see set_discrete_contact_solver()) according to:
Exceptions
iffthis plant is continuous (i.e. is_discrete() is false.)
std::exceptioniff called post-finalize.

◆ set_discrete_contact_solver()

void set_discrete_contact_solver ( DiscreteContactSolver  contact_solver)

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:
Warning
This function is a no-op for continuous models (when is_discrete() is false.)
Exceptions
std::exceptioniff 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()

void set_gravity_enabled ( ModelInstanceIndex  model_instance,
bool  is_enabled 
)

Sets is_gravity_enabled() for model_instance to is_enabled.

The effect of is_enabled = false is effectively equivalent to disabling (or making zero) gravity for all bodies in the specified model instance. By default is_gravity_enabled() equals true for all model instances.

Exceptions
std::exceptionif called post-finalize.
std::exceptionif the model instance is invalid.

◆ set_penetration_allowance()

void set_penetration_allowance ( double  penetration_allowance = MultibodyPlantConfig{}.penetration_allowance)

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 Default Parameters for further details.

Exceptions
std::exceptionif penetration_allowance is not positive.

◆ set_sap_near_rigid_threshold()

void set_sap_near_rigid_threshold ( double  near_rigid_threshold = MultibodyPlantConfig{}.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 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.

Exceptions
std::exceptionif near_rigid_threshold is negative.
std::exceptionif called post-finalize.

◆ set_stiction_tolerance()

void set_stiction_tolerance ( double  v_stiction = MultibodyPlantConfig{}.stiction_tolerance)

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 Simulation of Multibody Systems with Frictional Contact). See Continuous Approximation of Coulomb Friction for a detailed discussion of the Stribeck model.

Sets the stiction tolerance v_stiction for the Stribeck model, where v_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 for v_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 that v_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 Continuous Approximation of Coulomb Friction.

Exceptions
std::exceptionif v_stiction is non-positive.

◆ SetActuationInArray()

void SetActuationInArray ( ModelInstanceIndex  model_instance,
const Eigen::Ref< const VectorX< T >> &  u_instance,
EigenPtr< VectorX< T >>  u 
) const

Given actuation values u_instance for the actuators in model_instance, this function updates the actuation vector u for the entire plant model to which this actuator belongs to.

Refer to Actuation for further details.

Parameters
[in]u_instanceActuation values for the model instance. Values are ordered by monotonically increasing JointActuatorIndex within the model instance.
[in,out]uActuation 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 to model_instance are changed.
Exceptions
std::exceptionif the size of u_instance is not equal to the number of actuation inputs for the joints of model_instance.

◆ SetConstraintActiveStatus()

void SetConstraintActiveStatus ( systems::Context< T > *  context,
MultibodyConstraintId  id,
bool  status 
) const

Sets the active status of the constraint given by id in context.

Exceptions
std::exceptionif the MultibodyPlant has not been finalized.
std::exceptionif context == nullptr
std::exceptionif id does not belong to any multibody constraint in context.

◆ SetDefaultFreeBodyPose()

void SetDefaultFreeBodyPose ( const RigidBody< T > &  body,
const math::RigidTransform< double > &  X_PB 
)

Sets the default pose of body.

If body.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 above for details.
Parameters
[in]bodyRigidBody whose default pose will be set.
[in]X_PBDefault pose of the body.

◆ SetDefaultPositions() [1/2]

void SetDefaultPositions ( const Eigen::Ref< const Eigen::VectorXd > &  q)

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.

Exceptions
std::exceptionif the plant is not finalized or if q is not of size num_positions().

◆ SetDefaultPositions() [2/2]

void SetDefaultPositions ( ModelInstanceIndex  model_instance,
const Eigen::Ref< const Eigen::VectorXd > &  q_instance 
)

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.

Exceptions
std::exceptionif 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()

void SetDefaultState ( const systems::Context< T > &  context,
systems::State< T > *  state 
) const
override

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.

Exceptions
std::exceptionif called pre-finalize. See Finalize().

◆ SetDiscreteUpdateManager()

void SetDiscreteUpdateManager ( std::unique_ptr< internal::DiscreteUpdateManager< T >>  manager)

For use only by advanced developers wanting to try out their custom time stepping strategies, including contact resolution.

Warning
This feature is considered to be experimental and may change or be removed at any time, without any deprecation notice ahead of time.

With this method MultibodyPlant takes ownership of manager.

Note
Setting a contact manager bypasses the mechanism to set a different contact solver with SetContactSolver(). Use only one of these two experimental mechanisms but never both.
Parameters
managerAfter this call the new manager is used to advance discrete states.
Precondition
this MultibodyPlant is discrete.
manager != nullptr.
Exceptions
std::exceptionif called pre-finalize. See Finalize().

◆ SetFreeBodyPose() [1/2]

void SetFreeBodyPose ( systems::Context< T > *  context,
const RigidBody< T > &  body,
const math::RigidTransform< T > &  X_PB 
) const

Sets context to store the pose X_PB of a given body B in the parent frame P.

Note
The parent frame is not necessarily the world frame. See above for details.
Exceptions
std::exceptionif body is not a free body in the model.
std::exceptionif called pre-finalize.

◆ SetFreeBodyPose() [2/2]

void SetFreeBodyPose ( const systems::Context< T > &  context,
systems::State< T > *  state,
const RigidBody< T > &  body,
const math::RigidTransform< T > &  X_PB 
) const

Sets state to store the pose X_PB of a given body B in its parent frame P, for a given context of this model.

Note
The parent frame is not necessarily the world frame. See above for details.
Exceptions
std::exceptionif body is not a free body in the model.
std::exceptionif called pre-finalize.
Precondition
state comes from this MultibodyPlant.

◆ SetFreeBodyPoseInAnchoredFrame()

void SetFreeBodyPoseInAnchoredFrame ( systems::Context< T > *  context,
const Frame< T > &  frame_F,
const RigidBody< T > &  body,
const math::RigidTransform< T > &  X_FB 
) const

Updates context to store the pose X_FB of a given body B in a frame F.

Frame F must be anchored, meaning that it is either directly welded to the world frame W or, more generally, that there is a kinematic path between frame F and the world frame W that only includes weld joints.

Exceptions
std::exceptionif called pre-finalize.
std::exceptionif frame F is not anchored to the world.

◆ SetFreeBodyPoseInWorldFrame()

void SetFreeBodyPoseInWorldFrame ( systems::Context< T > *  context,
const RigidBody< T > &  body,
const math::RigidTransform< T > &  X_WB 
) const

Sets context to store the pose X_WB of a given floating base body B in the world frame W.

Parameters
[in]contextThe context to store the pose X_WB of body_B.
[in]body_BThe floating base body B corresponding to the pose X_WB to be stored in context.
Return values
X_WBThe pose of body frame B in the world frame W.
Note
In general setting the pose and/or velocity of a body in the model would involve a complex inverse kinematics problem. This method allows us to simplify this process when we know the body is free in space.
Warning
This method only applies to "floating base" bodies; i.e., body.is_floating() returns true. I.e., not just any free body, despite the method name.
Exceptions
std::exceptionif body is not a free body in the model.
std::exceptionif called pre-finalize.
std::exceptionif body.is_floating() returns false.

◆ SetFreeBodyRandomRotationDistribution()

void SetFreeBodyRandomRotationDistribution ( const RigidBody< T > &  body,
const Eigen::Quaternion< symbolic::Expression > &  rotation 
)

Sets the distribution used by SetRandomState() to populate the free body's rotation with respect to its parent frame.

Note
The parent frame is not necessarily the world frame. See above for details.
Exceptions
std::exceptionif body is not a free body in the model.
std::exceptionif called pre-finalize.

◆ SetFreeBodyRandomRotationDistributionToUniform()

void SetFreeBodyRandomRotationDistributionToUniform ( const RigidBody< T > &  body)

Sets the distribution used by SetRandomState() to populate the free body's rotation with respect to its parent frame using uniformly random rotations.

Note
The parent frame is not necessarily the world frame. See above for details.
Exceptions
std::exceptionif body is not a free body in the model.
std::exceptionif called pre-finalize.

◆ SetFreeBodyRandomTranslationDistribution()

void SetFreeBodyRandomTranslationDistribution ( const RigidBody< T > &  body,
const Vector3< symbolic::Expression > &  translation 
)

Sets the distribution used by SetRandomState() to populate the free body's x-y-z translation with respect to its parent frame P.

Note
The parent frame is not necessarily the world frame. See above for details.
Exceptions
std::exceptionif body is not a free body in the model.
std::exceptionif called pre-finalize.

◆ SetFreeBodySpatialVelocity() [1/2]

void SetFreeBodySpatialVelocity ( systems::Context< T > *  context,
const RigidBody< T > &  body,
const SpatialVelocity< T > &  V_PB 
) const

Sets context to store the spatial velocity V_PB of a given body B in its parent frame P.

Note
The parent frame is not necessarily the world frame. See above for details.
Exceptions
std::exceptionif body is not a free body in the model.
std::exceptionif called pre-finalize.

◆ SetFreeBodySpatialVelocity() [2/2]

void SetFreeBodySpatialVelocity ( const systems::Context< T > &  context,
systems::State< T > *  state,
const RigidBody< T > &  body,
const SpatialVelocity< T > &  V_PB 
) const

Sets state to store the spatial velocity V_PB of a given body B in its parent frame P, for a given context of this model.

Note
The parent frame is not necessarily the world frame. See above for details.
Exceptions
std::exceptionif body is not a free body in the model.
std::exceptionif called pre-finalize.
Precondition
state comes from this MultibodyPlant.

◆ SetPositions() [1/3]

void SetPositions ( systems::Context< T > *  context,
const Eigen::Ref< const VectorX< T >> &  q 
) const

Sets the generalized positions q in a given Context from a given vector.

Prefer this method over GetMutablePositions().

Exceptions
std::exceptionif 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() [2/3]

void SetPositions ( systems::Context< T > *  context,
ModelInstanceIndex  model_instance,
const Eigen::Ref< const VectorX< T >> &  q_instance 
) const

Sets the generalized positions q for a particular model instance in a given Context from a given vector.

Exceptions
std::exceptionif 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 q_instance is not equal to num_positions(model_instance).

◆ SetPositions() [3/3]

void SetPositions ( const systems::Context< T > &  context,
systems::State< T > *  state,
ModelInstanceIndex  model_instance,
const Eigen::Ref< const VectorX< T >> &  q_instance 
) const

(Advanced) Sets the generalized positions q for a particular model instance in a given State from a given vector.

Note
No cache invalidation occurs.
Exceptions
std::exceptionif 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 q_instance is not equal to num_positions(model_instance).
Precondition
state comes from this MultibodyPlant.

◆ SetPositionsAndVelocities() [1/2]

void SetPositionsAndVelocities ( systems::Context< T > *  context,
const Eigen::Ref< const VectorX< T >> &  q_v 
) const

Sets generalized positions q and generalized velocities v in a given Context from a given vector [q; v].

Prefer this method over GetMutablePositionsAndVelocities().

Exceptions
std::exceptionif 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() [2/2]

void SetPositionsAndVelocities ( systems::Context< T > *  context,
ModelInstanceIndex  model_instance,
const Eigen::Ref< const VectorX< T >> &  q_v 
) const

Sets generalized positions q and generalized velocities v from a given vector [q; v] for a specified model instance in a given Context.

Exceptions
std::exceptionif 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()

void SetPositionsInArray ( ModelInstanceIndex  model_instance,
const Eigen::Ref< const VectorX< T >> &  q_instance,
EigenPtr< VectorX< T >>  q 
) const

Sets the vector of generalized positions for model_instance in q using q_instance, leaving all other elements in the array untouched.

This method throws an exception if q is not of size MultibodyPlant::num_positions() or q_instance is not of size MultibodyPlant::num_positions(model_instance).

◆ SetRandomState()

void SetRandomState ( const systems::Context< T > &  context,
systems::State< T > *  state,
RandomGenerator generator 
) const
override

Assigns random values to all elements of the state, by drawing samples independently for each joint/free body (coming soon: and then solving a mathematical program to "project" these samples onto the registered system constraints).

If a random distribution is not specified for a joint/free body, the default state is used.

See also
Stochastic Systems

◆ SetUseSampledOutputPorts()

void SetUseSampledOutputPorts ( bool  use_sampled_output_ports)

(Advanced) For a discrete-time plant, configures whether the output ports are sampled (the default) or live (opt-in).

See Output port sampling for details.

Exceptions
std::exceptionif the plant is already finalized.
std::exceptionif use_sampled_output_ports is true but this MultibodyPlant is not a discrete model (is_discrete() == false).

◆ SetVelocities() [1/3]

void SetVelocities ( systems::Context< T > *  context,
const Eigen::Ref< const VectorX< T >> &  v 
) const

Sets the generalized velocities v in a given Context from a given vector.

Prefer this method over GetMutableVelocities().

Exceptions
std::exceptionif 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() [2/3]

void SetVelocities ( systems::Context< T > *  context,
ModelInstanceIndex  model_instance,
const Eigen::Ref< const VectorX< T >> &  v_instance 
) const

Sets the generalized velocities v for a particular model instance in a given Context from a given vector.

Exceptions
std::exceptionif 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).

◆ SetVelocities() [3/3]

void SetVelocities ( const systems::Context< T > &  context,
systems::State< T > *  state,
ModelInstanceIndex  model_instance,
const Eigen::Ref< const VectorX< T >> &  v_instance 
) const

(Advanced) Sets the generalized velocities v for a particular model instance in a given State from a given vector.

Note
No cache invalidation occurs.
Exceptions
std::exceptionif 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).
Precondition
state comes from this MultibodyPlant.

◆ SetVelocitiesInArray()

void SetVelocitiesInArray ( ModelInstanceIndex  model_instance,
const Eigen::Ref< const VectorX< T >> &  v_instance,
EigenPtr< VectorX< T >>  v 
) const

Sets the vector of generalized velocities for model_instance in v using v_instance, leaving all other elements in the array untouched.

This method throws an exception if v is not of size MultibodyPlant::num_velocities() or v_instance is not of size MultibodyPlant::num_positions(model_instance).

◆ stiction_tolerance()

double stiction_tolerance ( ) const
Returns
the stiction tolerance parameter, in m/s.
See also
set_stiction_tolerance.

◆ time_step()

double time_step ( ) const

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()

const WeldJoint<T>& WeldFrames ( const Frame< T > &  frame_on_parent_F,
const Frame< T > &  frame_on_child_M,
const math::RigidTransform< double > &  X_FM = math::RigidTransformdouble >::Identity() 
)

Welds frame_on_parent_F and frame_on_child_M with relative pose X_FM.

That is, the pose of frame M in frame F is fixed, with value X_FM. If X_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.
Exceptions
std::exceptionif the weld produces a duplicate joint name.

◆ world_body()

const RigidBody<T>& world_body ( ) const

Returns a constant reference to the world body.

◆ world_frame()

const RigidBodyFrame<T>& world_frame ( ) const

Returns a constant reference to the world frame.

Friends And Related Function Documentation

◆ AddMultibodyPlantSceneGraph() [1/2]

AddMultibodyPlantSceneGraphResult< T > AddMultibodyPlantSceneGraph ( systems::DiagramBuilder< T > *  builder,
double  time_step,
std::unique_ptr< geometry::SceneGraph< T >>  scene_graph = nullptr 
)
related

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 AddMultibodyPlantSceneGraph.
Parameters
[in,out]builderBuilder to add to.
[in]time_stepThe 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.
[in]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.
Template Parameters
TThe scalar type, which must be one of the default scalars.

◆ AddMultibodyPlantSceneGraph() [2/2]

AddMultibodyPlantSceneGraphResult< T > AddMultibodyPlantSceneGraph ( systems::DiagramBuilder< T > *  builder,
std::unique_ptr< MultibodyPlant< T >>  plant,
std::unique_ptr< geometry::SceneGraph< T >>  scene_graph = nullptr 
)
related

Adds a MultibodyPlant and a SceneGraph instance to a diagram builder, connecting the geometry ports.

Note
Usage examples in AddMultibodyPlantSceneGraph.
Parameters
[in,out]builderBuilder to add to.
[in]plantPlant to be added to the builder.
[in]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 and plant must be non-null.
Template Parameters
TThe scalar type, which must be one of the default scalars.

◆ internal::MultibodyPlantDiscreteUpdateManagerAttorney< T >

friend class internal::MultibodyPlantDiscreteUpdateManagerAttorney< T >
friend

◆ internal::MultibodyPlantModelAttorney< T >

friend class internal::MultibodyPlantModelAttorney< T >
friend

◆ MultibodyPlant

friend class MultibodyPlant
friend

◆ MultibodyPlantTester

friend class MultibodyPlantTester
friend

The documentation for this class was generated from the following files: