forked from RobotLocomotion/drake
-
Notifications
You must be signed in to change notification settings - Fork 0
/
multibody_plant.h
4859 lines (4444 loc) · 234 KB
/
multibody_plant.h
1
2
3
4
5
6
7
8
9
10
11
12
13
14
15
16
17
18
19
20
21
22
23
24
25
26
27
28
29
30
31
32
33
34
35
36
37
38
39
40
41
42
43
44
45
46
47
48
49
50
51
52
53
54
55
56
57
58
59
60
61
62
63
64
65
66
67
68
69
70
71
72
73
74
75
76
77
78
79
80
81
82
83
84
85
86
87
88
89
90
91
92
93
94
95
96
97
98
99
100
101
102
103
104
105
106
107
108
109
110
111
112
113
114
115
116
117
118
119
120
121
122
123
124
125
126
127
128
129
130
131
132
133
134
135
136
137
138
139
140
141
142
143
144
145
146
147
148
149
150
151
152
153
154
155
156
157
158
159
160
161
162
163
164
165
166
167
168
169
170
171
172
173
174
175
176
177
178
179
180
181
182
183
184
185
186
187
188
189
190
191
192
193
194
195
196
197
198
199
200
201
202
203
204
205
206
207
208
209
210
211
212
213
214
215
216
217
218
219
220
221
222
223
224
225
226
227
228
229
230
231
232
233
234
235
236
237
238
239
240
241
242
243
244
245
246
247
248
249
250
251
252
253
254
255
256
257
258
259
260
261
262
263
264
265
266
267
268
269
270
271
272
273
274
275
276
277
278
279
280
281
282
283
284
285
286
287
288
289
290
291
292
293
294
295
296
297
298
299
300
301
302
303
304
305
306
307
308
309
310
311
312
313
314
315
316
317
318
319
320
321
322
323
324
325
326
327
328
329
330
331
332
333
334
335
336
337
338
339
340
341
342
343
344
345
346
347
348
349
350
351
352
353
354
355
356
357
358
359
360
361
362
363
364
365
366
367
368
369
370
371
372
373
374
375
376
377
378
379
380
381
382
383
384
385
386
387
388
389
390
391
392
393
394
395
396
397
398
399
400
401
402
403
404
405
406
407
408
409
410
411
412
413
414
415
416
417
418
419
420
421
422
423
424
425
426
427
428
429
430
431
432
433
434
435
436
437
438
439
440
441
442
443
444
445
446
447
448
449
450
451
452
453
454
455
456
457
458
459
460
461
462
463
464
465
466
467
468
469
470
471
472
473
474
475
476
477
478
479
480
481
482
483
484
485
486
487
488
489
490
491
492
493
494
495
496
497
498
499
500
501
502
503
504
505
506
507
508
509
510
511
512
513
514
515
516
517
518
519
520
521
522
523
524
525
526
527
528
529
530
531
532
533
534
535
536
537
538
539
540
541
542
543
544
545
546
547
548
549
550
551
552
553
554
555
556
557
558
559
560
561
562
563
564
565
566
567
568
569
570
571
572
573
574
575
576
577
578
579
580
581
582
583
584
585
586
587
588
589
590
591
592
593
594
595
596
597
598
599
600
601
602
603
604
605
606
607
608
609
610
611
612
613
614
615
616
617
618
619
620
621
622
623
624
625
626
627
628
629
630
631
632
633
634
635
636
637
638
639
640
641
642
643
644
645
646
647
648
649
650
651
652
653
654
655
656
657
658
659
660
661
662
663
664
665
666
667
668
669
670
671
672
673
674
675
676
677
678
679
680
681
682
683
684
685
686
687
688
689
690
691
692
693
694
695
696
697
698
699
700
701
702
703
704
705
706
707
708
709
710
711
712
713
714
715
716
717
718
719
720
721
722
723
724
725
726
727
728
729
730
731
732
733
734
735
736
737
738
739
740
741
742
743
744
745
746
747
748
749
750
751
752
753
754
755
756
757
758
759
760
761
762
763
764
765
766
767
768
769
770
771
772
773
774
775
776
777
778
779
780
781
782
783
784
785
786
787
788
789
790
791
792
793
794
795
796
797
798
799
800
801
802
803
804
805
806
807
808
809
810
811
812
813
814
815
816
817
818
819
820
821
822
823
824
825
826
827
828
829
830
831
832
833
834
835
836
837
838
839
840
841
842
843
844
845
846
847
848
849
850
851
852
853
854
855
856
857
858
859
860
861
862
863
864
865
866
867
868
869
870
871
872
873
874
875
876
877
878
879
880
881
882
883
884
885
886
887
888
889
890
891
892
893
894
895
896
897
898
899
900
901
902
903
904
905
906
907
908
909
910
911
912
913
914
915
916
917
918
919
920
921
922
923
924
925
926
927
928
929
930
931
932
933
934
935
936
937
938
939
940
941
942
943
944
945
946
947
948
949
950
951
952
953
954
955
956
957
958
959
960
961
962
963
964
965
966
967
968
969
970
971
972
973
974
975
976
977
978
979
980
981
982
983
984
985
986
987
988
989
990
991
992
993
994
995
996
997
998
999
1000
#pragma once
#include <limits>
#include <map>
#include <memory>
#include <optional>
#include <string>
#include <string_view>
#include <tuple>
#include <type_traits>
#include <unordered_map>
#include <unordered_set>
#include <utility>
#include <vector>
#include "drake/common/default_scalars.h"
#include "drake/common/nice_type_name.h"
#include "drake/common/random.h"
#include "drake/geometry/scene_graph.h"
#include "drake/math/rigid_transform.h"
#include "drake/multibody/contact_solvers/contact_solver.h"
#include "drake/multibody/contact_solvers/contact_solver_results.h"
#include "drake/multibody/hydroelastics/hydroelastic_engine.h"
#include "drake/multibody/plant/contact_jacobians.h"
#include "drake/multibody/plant/contact_results.h"
#include "drake/multibody/plant/coulomb_friction.h"
#include "drake/multibody/plant/discrete_contact_pair.h"
#include "drake/multibody/plant/tamsi_solver.h"
#include "drake/multibody/topology/multibody_graph.h"
#include "drake/multibody/tree/force_element.h"
#include "drake/multibody/tree/multibody_tree-inl.h"
#include "drake/multibody/tree/multibody_tree_system.h"
#include "drake/multibody/tree/rigid_body.h"
#include "drake/multibody/tree/weld_joint.h"
#include "drake/systems/framework/diagram_builder.h"
#include "drake/systems/framework/leaf_system.h"
#include "drake/systems/framework/scalar_conversion_traits.h"
namespace drake {
namespace multibody {
namespace internal {
// Data stored in the cache entry for the hydroelastic with fallback contact
// model.
template <typename T>
struct HydroelasticFallbackCacheData {
std::vector<geometry::ContactSurface<T>> contact_surfaces;
std::vector<geometry::PenetrationAsPointPair<T>> point_pairs;
};
// Structure used in the calculation of hydroelastic contact forces.
template <typename T>
struct HydroelasticContactInfoAndBodySpatialForces {
explicit HydroelasticContactInfoAndBodySpatialForces(int num_bodies) {
F_BBo_W_array.resize(num_bodies);
}
// Forces from hydroelastic contact applied to the origin of each body
// (indexed by BodyNodeIndex) in the MultibodyPlant.
std::vector<SpatialForce<T>> F_BBo_W_array;
// Information used for contact reporting collected through the evaluation
// of the hydroelastic model.
std::vector<HydroelasticContactInfo<T>> contact_info;
};
} // namespace internal
// TODO(amcastro-tri): Add a section on contact models in
// contact_model_doxygen.h.
/// Enumeration for contact model options.
enum class ContactModel {
/// Contact forces are computed using the Hydroelastic model. Conctact between
/// unsupported geometries will cause a runtime exception.
kHydroelasticsOnly,
/// Contact forces are computed using a point contact model, see @ref
/// point_contact_approximation "Numerical Approximation of Point Contact".
kPointContactOnly,
/// Contact forces are computed using the hydroelastic model, where possible.
/// For most other unsupported colliding pairs, the point model from
/// kPointContactOnly is used. See
/// geometry::QueryObject:ComputeContactSurfacesWithFallback for more
/// details.
kHydroelasticWithFallback
};
/// @cond
// Helper macro to throw an exception within methods that should not be called
// post-finalize.
#define DRAKE_MBP_THROW_IF_FINALIZED() ThrowIfFinalized(__func__)
// Helper macro to throw an exception within methods that should not be called
// pre-finalize.
#define DRAKE_MBP_THROW_IF_NOT_FINALIZED() ThrowIfNotFinalized(__func__)
/// @endcond
// TODO(sherm1) Rename "continuous_state" output ports to just "state" since
// they can be discrete. However see issue #12214.
/**
%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 @ref multibody for an overview of
concepts/notation.
@system
name: MultibodyPlant
input_ports:
- applied_generalized_force
- applied_spatial_force
- <em style="color:gray">model_instance_name[i]</em>_actuation
- <span style="color:green">geometry_query</span>
output_ports:
- continuous_state
- body_poses
- body_spatial_velocities
- body_spatial_accelerations
- generalized_acceleration
- reaction_forces
- contact_results
- <em style="color:gray">model_instance_name[i]</em>_continuous_state
- '<em style="color:gray">
model_instance_name[i]</em>_generalized_acceleration'
- '<em style="color:gray">
model_instance_name[i]</em>_generalized_contact_forces'
- <span style="color:green">geometry_pose</span>
@endsystem
The ports whose names begin with <em style="color:gray">
model_instance_name[i]</em> represent groups of ports, one for each of the
@ref model_instances "model instances", with i ∈ {0, ..., N-1} for the N
model instances. If a model instance does not contain any data of the
indicated type the port will still be present but its value will be a
zero-length vector. (Model instances `world_model_instance()` and
`default_model_instance()` always exist.)
The ports shown in <span style="color:green">
green</span> are for communication with Drake's
@ref geometry::SceneGraph "SceneGraph" system for dealing with geometry.
%MultibodyPlant provides a user-facing API for:
- @ref mbp_input_and_output_ports "Ports":
Access input and output ports.
- @ref mbp_construction "Construction":
Add bodies, joints, frames, force elements, and actuators.
- @ref mbp_geometry "Geometry":
Register geometries to a provided SceneGraph instance.
- @ref mbp_contact_modeling "Contact modeling":
Select and parameterize contact models.
- @ref mbp_state_accessors_and_mutators "State access and modification":
Obtain and manipulate position and velocity state variables.
- @ref mbp_parameters "Parameters"
Working with system parameters for various multibody elements.
- @ref mbp_working_with_free_bodies "Free bodies":
Work conveniently with free (floating) bodies.
- @ref mbp_kinematic_and_dynamic_computations "Kinematics and dynamics":
Perform @ref systems::Context "Context"-dependent kinematic and dynamic
queries.
- @ref mbp_system_matrix_computations "System matrices":
Explicitly form matrices that appear in the equations of motion.
- @ref mbp_introspection "Introspection":
Perform introspection to find out what's in the %MultibodyPlant.
@anchor model_instances
### 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 SDF files
(using the `model` tag) and are automatically created when SDF
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().
@anchor mbp_equations_of_motion
### System dynamics
<!-- TODO(amcastro-tri): Update this documentation to include:
- Bilateral constraints.
- Unilateral constraints and contact. -->
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()).
As a Drake @ref systems::System "System", %MultibodyPlant implements the
governing equations for a
multibody dynamical system in the form `ẋ = f(t, x, u)` with t being
time and u the actuation forces. The governing equations for
the dynamics of a multibody system modeled with %MultibodyPlant are
[Featherstone 2008, Jain 2010]: <pre>
q̇ = N(q)v
(1) M(q)v̇ + C(q, v)v = τ
</pre>
where `M(q)` is the mass matrix of the multibody system, `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.
@anchor sdf_loading
### Loading models from SDF files
Drake has the capability to load multibody models from SDF and URDF
files. Consider the example below which loads an acrobot model:
@code
MultibodyPlant<T> acrobot;
SceneGraph<T> scene_graph;
Parser parser(&acrobot, &scene_graph);
const std::string relative_name =
"drake/multibody/benchmarks/acrobot/acrobot.sdf";
const std::string full_name = FindResourceOrThrow(relative_name);
parser.AddModelFromFile(full_name);
@endcode
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 AddAllModelsFromFile() which allows creating model instances per
each `<model>` tag found in the file. Please refer to each of these
methods' documentation for further details.
@anchor working_with_scenegraph
### Working with %SceneGraph
@anchor add_multibody_plant_scene_graph
#### 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):
@code
MultibodyPlant<double>& plant =
AddMultibodyPlantSceneGraph(&builder, 0.0 /+ time_step +/);
plant.DoFoo(...);
@endcode
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:
@code
auto items = AddMultibodyPlantSceneGraph(&builder, 0.0 /+ time_step +/);
items.plant.DoFoo(...);
items.scene_graph.DoBar(...);
@endcode
or taking advantage of C++17's structured binding
@code
auto [plant, scene_graph] = AddMultibodyPlantSceneGraph(&builder, 0.0);
...
plant.DoFoo(...);
scene_graph.DoBar(...);
@endcode
This is the easiest way to use both the plant and scene_graph.
Assign to already-declared pointer variables:
@code
MultibodyPlant<double>* plant{};
SceneGraph<double>* scene_graph{};
std::tie(plant, scene_graph) =
AddMultibodyPlantSceneGraph(&builder, 0.0 /+ time_step +/);
plant->DoFoo(...);
scene_graph->DoBar(...);
@endcode
This flavor is most useful when the pointers are class member fields
(and so perhaps cannot be references).
@anchor mbp_geometry_registration
#### Registering geometry with a SceneGraph
%MultibodyPlant users can register geometry with a SceneGraph for
essentially two purposes; a) visualization and, b) contact modeling.
<!--TODO(SeanCurtis-TRI): update this comment as the number of SceneGraph
roles changes. -->
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. Users must connect this input port to the output
port for geometric queries of the SceneGraph used for registration, which
can be obtained with SceneGraph::get_query_output_port(). In summary, if
%MultibodyPlant registers collision geometry, 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 SceneGraph::get_query_output_port() to
get_geometry_query_input_port().
Refer to the documentation provided in each of the methods above for further
details.
@anchor accessing_contact_properties
#### 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 | Penalty method stiffness. |
| material | hunt_crossley_dissipation | no² | T | Penalty method dissipation. |
¹ 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 exeception.
² If the property is missing, %MultibodyPlant will use
a heuristic value as the default. Refer to the
section @ref mbp_penalty_method "Penalty method point contact" for further
details.
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:
@code
// For a SceneGraph<T> instance called scene_graph.
const geometry::SceneGraphInspector<T>& inspector =
scene_graph.model_inspector();
@endcode
After context creation, an inspector can be retrieved from the state
stored in the context by the plant's geometry query input port:
@code
// For a MultibodyPlant<T> instance called mbp and a
// Context<T> called context.
const geometry::QueryObject<T>& query_object =
mbp.get_geometry_query_input_port()
.template Eval<geometry::QueryObject<T>>(context);
const geometry::SceneGraphInspector<T>& inspector =
query_object.inspector();
@endcode
Once an inspector is available, proximity properties can be retrieved as:
@code
// For a body with GeometryId called geometry_id
const geometry::ProximityProperties* props =
inspector.GetProximityProperties(geometry_id);
const CoulombFriction<T>& geometry_friction =
props->GetProperty<CoulombFriction<T>>("material",
"coulomb_friction");
@endcode
@anchor mbp_parameters
### 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 docmentation 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:
@code
MultibodyPlant<double> plant;
// ... Code to add bodies, finalize plant, and to obtain a context.
const RigidBody<double>& body =
plant.GetRigidBodyByName("BodyName");
const SpatialInertia<double> M_BBo_B =
body.GetSpatialInertiaInBodyFrame(context);
// .. logic to determine a new SpatialInertia parameter for body.
const SpatialInertia<double>& M_BBo_B_new = ....
// Modify the body parameter for spatial inertia.
body.SetSpatialInertiaInBodyFrame(&context, M_BBo_B_new);
@endcode
Another example, working with automatic differentiation in order to take
derivatives with respect to one of the bodies' masses:
@code
MultibodyPlant<double> plant;
// ... Code to add bodies, finalize plant, and to obtain a
// context and a body's spatial inertia M_BBo_B.
// Scalar convert the plant.
unique_ptr<MultibodyPlant<AutoDiffXd>> plant_autodiff =
systems::System<double>::ToAutoDiffXd(plant);
unique_ptr<Context<AutoDiffXd>> context_autodiff =
plant_autodiff->CreateDefaultContext();
context_autodiff->SetTimeStateAndParametersFrom(context);
const RigidBody<AutoDiffXd>& body =
plant_autodiff->GetRigidBodyByName("BodyName");
// Modify the body parameter for mass.
const AutoDiffXd mass_autodiff(mass, Vector1d(1));
body.SetMass(context_autodiff.get(), mass_autodiff);
// M_autodiff(i, j).derivatives()(0), contains the derivatives of
// M(i, j) with respect to the body's mass.
MatrixX<AutoDiffXd> M_autodiff(plant_autodiff->num_velocities(),
plant_autodiff->num_velocities());
plant_autodiff->CalcMassMatrix(*context_autodiff, &M_autodiff);
@endcode
@anchor mbp_adding_elements
### Adding modeling elements
<!-- TODO(amcastro-tri): Update this section to add force elements and
constraints. -->
Add multibody elements to a %MultibodyPlant with methods like:
- Bodies: AddRigidBody()
- Joints: AddJoint()
- see @ref mbp_construction "Construction" for more.
All modeling elements **must** be added before Finalize() is called.
See @ref mbp_finalize_stage "Finalize stage" for a discussion.
@anchor mbp_modeling_contact
### Modeling contact
Please refer to @ref drake_contacts "Contact Modeling in Drake" for details
on the available approximations, setup, and considerations for a multibody
simulation with frictional contact.
@anchor mbp_energy_and_power
### Energy and Power
<!-- TODO(sherm1) Update this as issue #12942 gets resolved. -->
%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.
@anchor mbp_finalize_stage
### %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 MultibodyTree topology, see MultibodyTree::Finalize()
for details,
- declare the plant's state,
- declare the plant's input and output ports,
- declare input and output ports for communication with a SceneGraph.
<!-- TODO(amcastro-tri): Consider making the actual geometry registration
with GS AFTER Finalize() so that we can tell if there are any bodies
welded to the world to which we could just assign anchored geometry
instead of dynamic geometry. This is an optimization and the API, and
pre/post-finalize conditions should not change. -->
@anchor mbp_table_of_contents
@anchor mbp_references
### 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.
@tparam_default_scalar
@ingroup systems */
template <typename T>
class MultibodyPlant : public internal::MultibodyTreeSystem<T> {
public:
DRAKE_NO_COPY_NO_MOVE_NO_ASSIGN(MultibodyPlant)
/// @anchor mbp_input_and_output_ports
/// @name Input and output ports
/// These methods provide access to the Drake
/// @ref systems::System "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 (in the case where only a
/// single model instance has actuated dofs), or through multiple input ports
/// which each provide the actuation values for a specific model instance.
/// See AddJointActuator() and num_actuators().
///
/// Output ports provide information about the entire %MultibodyPlant
/// or its individual model instances.
/// @{
/// 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:
/// @code
/// const auto& X_WB_all = plant.get_body_poses_output_port().
/// .Eval<std::vector<math::RigidTransform<double>>>(plant_context);
/// const BodyIndex arm_body_index = plant.GetBodyByName("arm").index();
/// const math::RigidTransform<double>& X_WArm = X_WB_all[arm_body_index];
/// @endcode
/// 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.
/// @throws std::exception if called pre-finalize.
const systems::OutputPort<T>& get_body_poses_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:
/// @code
/// const auto& V_WB_all = plant.get_body_spatial_velocities_output_port().
/// .Eval<std::vector<SpatialVelocity<double>>>(plant_context);
/// const BodyIndex arm_body_index = plant.GetBodyByName("arm").index();
/// const SpatialVelocity<double>& V_WArm = V_WB_all[arm_body_index];
/// @endcode
/// 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.
/// @throws std::exception if called pre-finalize.
const systems::OutputPort<T>& get_body_spatial_velocities_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 in the
/// world frame W with:
/// @code
/// const auto& A_WB_all =
/// plant.get_body_spatial_accelerations_output_port().
/// .Eval<std::vector<SpatialAcceleration<double>>>(plant_context);
/// const BodyIndex arm_body_index = plant.GetBodyByName("arm").index();
/// const SpatialVelocity<double>& A_WArm = A_WB_all[arm_body_index];
/// @endcode
/// 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.
/// @throws std::exception if called pre-finalize.
const systems::OutputPort<T>& get_body_spatial_accelerations_output_port()
const;
/// Returns a constant reference to the input port for external actuation for
/// a specific model instance. This input port is a vector valued port, which
/// can be set with JointActuator::set_actuation_vector().
/// @pre Finalize() was already called on `this` plant.
/// @throws std::exception if called before Finalize().
/// @throws std::exception if the model instance does not exist.
const systems::InputPort<T>& get_actuation_input_port(
ModelInstanceIndex model_instance) const;
/// Returns a constant reference to the input port for external actuation for
/// the case where only one model instance has actuated dofs. This input
/// port is a vector valued port, which can be set with
/// JointActuator::set_actuation_vector().
/// @pre Finalize() was already called on `this` plant.
/// @throws std::exception if called before Finalize(), if the model does not
/// contain any actuators, or if multiple model instances have actuated dofs.
const systems::InputPort<T>& get_actuation_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
/// @ref mbp_equations_of_motion "System dynamics"). This vector is ordered
/// using the same convention as the plant velocities: you can set the
/// generalized forces that will be applied to model instance i using, e.g.,
/// `SetVelocitiesInArray(i, model_forces, &force_array)`.
/// @throws std::exception if called before Finalize().
const systems::InputPort<T>& get_applied_generalized_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.
const systems::InputPort<T>& get_applied_spatial_force_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 @ref mbp_geometry "Geometry" of this class's
/// documentation for further details on collision geometry registration and
/// connection with a SceneGraph.
const systems::InputPort<T>& get_geometry_query_input_port() const;
/// Returns a constant reference to the output port for the multibody state
/// x = [q, v] of the model.
/// @pre Finalize() was already called on `this` plant.
/// @throws std::exception if called before Finalize().
const systems::OutputPort<T>& get_state_output_port() 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.)
/// @pre Finalize() was already called on `this` plant.
/// @throws std::exception if called before Finalize().
/// @throws std::exception if the model instance does not exist.
const systems::OutputPort<T>& get_state_output_port(
ModelInstanceIndex model_instance) const;
/// Returns a constant reference to the output port for generalized
/// accelerations v̇ of the model.
/// @pre Finalize() was already called on `this` plant.
/// @throws std::exception if called before Finalize().
const systems::OutputPort<T>& get_generalized_acceleration_output_port()
const;
/// Returns a constant reference to the output port for the generalized
/// accelerations v̇ᵢ ⊆ v̇ for model instance i.
/// @pre Finalize() was already called on `this` plant.
/// @throws std::exception if called before Finalize().
/// @throws std::exception if the model instance does not exist.
const systems::OutputPort<T>& get_generalized_acceleration_output_port(
ModelInstanceIndex model_instance) const;
/// Returns a constant reference to the output port of generalized contact
/// forces for a specific model instance.
///
/// @pre Finalize() was already called on `this` plant.
/// @throws std::exception if called before Finalize().
/// @throws std::exception if the model instance does not exist.
const systems::OutputPort<T>& get_generalized_contact_forces_output_port(
ModelInstanceIndex model_instance) 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`.
///
/// @throws std::exception if called pre-finalize.
const systems::OutputPort<T>& get_reaction_forces_output_port() const;
/// Returns a constant reference to the port that outputs ContactResults.
/// @throws std::exception if called pre-finalize, see Finalize().
const systems::OutputPort<T>& get_contact_results_output_port() const;
/// Returns the output port of frames' poses to communicate with a
/// SceneGraph.
const systems::OutputPort<T>& get_geometry_poses_output_port() const;
/// @} <!-- Input and output ports -->
/// @anchor mbp_construction
/// @name 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.
/// @{
/// 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 @ref time_advancement_strategy
/// "Choice of Time Advancement Strategy" 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.
///
/// <!-- TODO(amcastro-tri): Update the @warning messages in these docs if the
/// best practices advice changes as our solvers evolve. -->
///
/// @param[in] time_step
/// Indicates 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 @ref time_advancement_strategy
/// "Choice of Time Advancement Strategy" 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.
///
/// @throws std::exception if `time_step` is negative.
explicit MultibodyPlant(double time_step);
/// Scalar-converting copy constructor. See @ref system_scalar_conversion.
template <typename U>
explicit MultibodyPlant(const MultibodyPlant<U>& other)
: internal::MultibodyTreeSystem<T>(
systems::SystemTypeTag<MultibodyPlant>{},
other.internal_tree().template CloneToScalar<T>(),
other.is_discrete()) {
DRAKE_THROW_UNLESS(other.is_finalized());
time_step_ = other.time_step_;
// Copy of all members related with geometry registration.
source_id_ = other.source_id_;
body_index_to_frame_id_ = other.body_index_to_frame_id_;
frame_id_to_body_index_ = other.frame_id_to_body_index_;
geometry_id_to_body_index_ = other.geometry_id_to_body_index_;
geometry_id_to_visual_index_ = other.geometry_id_to_visual_index_;
geometry_id_to_collision_index_ = other.geometry_id_to_collision_index_;
default_coulomb_friction_ = other.default_coulomb_friction_;
visual_geometries_ = other.visual_geometries_;
collision_geometries_ = other.collision_geometries_;
X_WB_default_list_ = other.X_WB_default_list_;
contact_model_ = other.contact_model_;
penetration_allowance_ = other.penetration_allowance_;
DeclareSceneGraphPorts();
// Do accounting for MultibodyGraph
for (BodyIndex index(0); index < num_bodies(); ++index) {
const Body<T>& body = get_body(index);
multibody_graph_.AddBody(body.name(), body.model_instance());
}
for (JointIndex index(0); index < num_joints(); ++index) {
RegisterJointInGraph(get_joint(index));
}
// MultibodyTree::CloneToScalar() already called MultibodyTree::Finalize()
// on the new MultibodyTree on U. Therefore we only Finalize the plant's
// internals (and not the MultibodyTree).
FinalizePlantOnly();
}
/// 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:
/// @code
/// MultibodyPlant<T> plant;
/// // ... Code to define spatial_inertia, a SpatialInertia<T> object ...
/// ModelInstanceIndex model_instance = plant.AddModelInstance("instance");
/// const RigidBody<T>& body =
/// plant.AddRigidBody("BodyName", model_instance, spatial_inertia);
/// @endcode
///
/// @param[in] name
/// A 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
/// @p model_instance. See HasBodyNamed(), Body::name().
/// @param[in] model_instance
/// A model instance index which this body is part of.
/// @param[in] M_BBo_B
/// The 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.
/// @returns A constant reference to the new RigidBody just added, which will
/// remain valid for the lifetime of `this` %MultibodyPlant.
const RigidBody<T>& AddRigidBody(
const std::string& name, ModelInstanceIndex model_instance,
const SpatialInertia<double>& M_BBo_B) {
DRAKE_MBP_THROW_IF_FINALIZED();
// Make note in the graph.
multibody_graph_.AddBody(name, model_instance);
// Add the actual rigid body to the model.
const RigidBody<T>& body = this->mutable_tree().AddRigidBody(
name, model_instance, M_BBo_B);
// Each entry of visual_geometries_, ordered by body index, contains a
// std::vector of geometry ids for that body. The emplace_back() below
// resizes visual_geometries_ to store the geometry ids for the body we
// just added.
// Similarly for the collision_geometries_ vector.
DRAKE_DEMAND(visual_geometries_.size() == body.index());
visual_geometries_.emplace_back();
DRAKE_DEMAND(collision_geometries_.size() == body.index());
collision_geometries_.emplace_back();
DRAKE_DEMAND(X_WB_default_list_.size() == body.index());
X_WB_default_list_.emplace_back();
RegisterRigidBodyWithSceneGraph(body);
return body;
}
/// 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
/// (@ref model_instance "more on model instances").
///
/// Example of usage:
/// @code
/// MultibodyPlant<T> plant;
/// // ... Code to define spatial_inertia, a SpatialInertia<T> object ...
/// const RigidBody<T>& body =
/// plant.AddRigidBody("BodyName", spatial_inertia);
/// @endcode
///
/// @param[in] name
/// A 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(),
/// Body::name().
/// @param[in] M_BBo_B
/// The 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.
/// @returns A constant reference to the new RigidBody just added, which will
/// remain valid for the lifetime of `this` %MultibodyPlant.
/// @throws std::logic_error if additional model instances have been created
/// beyond the world and default instances.
const RigidBody<T>& AddRigidBody(
const std::string& name, const SpatialInertia<double>& M_BBo_B) {
if (num_model_instances() != 2) {
throw std::logic_error(
"This model has more model instances than the default. Please "
"call AddRigidBody with an explicit model instance.");
}
return AddRigidBody(name, default_model_instance(), M_BBo_B);
}
/// This method adds a Frame of type `FrameType<T>`. For more information,
/// please see the corresponding constructor of `FrameType`.
/// @tparam FrameType Template which will be instantiated on `T`.
/// @param frame Unique pointer frame instance.
/// @returns A constant reference to the new Frame just added, which will
/// remain valid for the lifetime of `this` %MultibodyPlant.
template <template<typename> class FrameType>
const FrameType<T>& AddFrame(std::unique_ptr<FrameType<T>> frame) {
return this->mutable_tree().AddFrame(std::move(frame));
}
/// This method adds a Joint of type `JointType` between two bodies.
/// For more information, see the below overload of `AddJoint<>`.
template <template<typename Scalar> class JointType>
const JointType<T>& AddJoint(std::unique_ptr<JointType<T>> joint) {
DRAKE_MBP_THROW_IF_FINALIZED();
static_assert(std::is_convertible<JointType<T>*, Joint<T>*>::value,
"JointType must be a sub-class of Joint<T>.");
RegisterJointInGraph(*joint);
return this->mutable_tree().AddJoint(std::move(joint));
}
/// 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.
/// @image html multibody/plant/images/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.
///
/// @param name
/// A 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().
/// @param[in] parent
/// The parent body connected by the new joint.
/// @param[in] X_PF
/// The 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.
/// @param[in] child
/// The child body connected by the new joint.
/// @param[in] X_BM
/// The 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.
/// @param[in] args
/// Zero 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.
/// @tparam JointType The 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:
/// @code
/// 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>(...));
/// // Body 1 serves as parent, Body 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 */
/// @endcode
///
/// @throws std::exception if `this` %MultibodyPlant already contains a joint
/// with the given `name`. See HasJointNamed(), Joint::name().
///
/// @see The Joint class's documentation for further details on how a Joint
/// is defined.
template <template <typename> class JointType, typename... Args>
const JointType<T>& AddJoint(
const std::string& name, const Body<T>& parent,
const std::optional<math::RigidTransform<double>>& X_PF,
const Body<T>& child,
const std::optional<math::RigidTransform<double>>& X_BM, Args&&... args) {
// TODO(Mitiguy) Per discussion in PR# 13961 and issues #12789 and #13040,
// consider changing frame F to frame Jp and changing frame M to frame Jc.
static_assert(std::is_base_of<Joint<T>, JointType<T>>::value,
"JointType<T> must be a sub-class of Joint<T>.");
const Frame<T>* frame_on_parent{nullptr};
if (X_PF) {
frame_on_parent = &this->AddFrame(
std::make_unique<FixedOffsetFrame<T>>(parent, *X_PF));