-
Notifications
You must be signed in to change notification settings - Fork 1.3k
/
Copy pathmultibody_plant_test.cc
5186 lines (4527 loc) · 229 KB
/
multibody_plant_test.cc
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
#include "drake/multibody/plant/multibody_plant.h"
#include <functional>
#include <limits>
#include <memory>
#include <regex>
#include <set>
#include <tuple>
#include <utility>
#include <gmock/gmock.h>
#include <gtest/gtest.h>
#include "drake/common/nice_type_name.h"
#include "drake/common/test_utilities/eigen_matrix_compare.h"
#include "drake/common/test_utilities/expect_no_throw.h"
#include "drake/common/test_utilities/expect_throws_message.h"
#include "drake/common/test_utilities/limit_malloc.h"
#include "drake/geometry/geometry_frame.h"
#include "drake/geometry/geometry_roles.h"
#include "drake/geometry/proximity_properties.h"
#include "drake/geometry/query_object.h"
#include "drake/geometry/scene_graph.h"
#include "drake/geometry/test_utilities/dummy_render_engine.h"
#include "drake/geometry/test_utilities/geometry_set_tester.h"
#include "drake/math/autodiff_gradient.h"
#include "drake/math/rigid_transform.h"
#include "drake/math/roll_pitch_yaw.h"
#include "drake/math/rotation_matrix.h"
#include "drake/multibody/benchmarks/acrobot/acrobot.h"
#include "drake/multibody/benchmarks/acrobot/make_acrobot_plant.h"
#include "drake/multibody/benchmarks/pendulum/make_pendulum_plant.h"
#include "drake/multibody/parsing/parser.h"
#include "drake/multibody/plant/discrete_contact_pair.h"
#include "drake/multibody/plant/externally_applied_spatial_force.h"
#include "drake/multibody/plant/test_utilities/multibody_plant_remodeling.h"
#include "drake/multibody/test_utilities/add_fixed_objects_to_plant.h"
#include "drake/multibody/tree/door_hinge.h"
#include "drake/multibody/tree/planar_joint.h"
#include "drake/multibody/tree/prismatic_joint.h"
#include "drake/multibody/tree/prismatic_spring.h"
#include "drake/multibody/tree/quaternion_floating_joint.h"
#include "drake/multibody/tree/revolute_joint.h"
#include "drake/multibody/tree/revolute_spring.h"
#include "drake/multibody/tree/rigid_body.h"
#include "drake/systems/framework/context.h"
#include "drake/systems/framework/continuous_state.h"
#include "drake/systems/framework/diagram_builder.h"
#include "drake/systems/primitives/constant_vector_source.h"
#include "drake/systems/primitives/linear_system.h"
#include "drake/systems/primitives/pass_through.h"
namespace drake {
using Eigen::AngleAxisd;
using Eigen::Matrix2d;
using Eigen::Translation3d;
using Eigen::Vector2d;
using Eigen::Vector3d;
using Eigen::VectorXd;
using geometry::FrameId;
using geometry::FramePoseVector;
using geometry::GeometryId;
using geometry::IllustrationProperties;
using geometry::PenetrationAsPointPair;
using geometry::QueryObject;
using geometry::SceneGraph;
using geometry::SceneGraphInspector;
using geometry::internal::DummyRenderEngine;
using math::RigidTransform;
using math::RigidTransformd;
using math::RollPitchYawd;
using math::RotationMatrix;
using math::RotationMatrixd;
using multibody::MultibodyForces;
using multibody::Parser;
using multibody::benchmarks::Acrobot;
using multibody::benchmarks::acrobot::AcrobotParameters;
using multibody::benchmarks::acrobot::MakeAcrobotPlant;
using multibody::benchmarks::pendulum::MakePendulumPlant;
using multibody::benchmarks::pendulum::PendulumParameters;
using std::make_pair;
using std::pair;
using std::tie;
using std::unique_ptr;
using systems::BasicVector;
using systems::ConstantVectorSource;
using systems::Context;
using systems::ContinuousState;
using systems::Diagram;
using systems::DiagramBuilder;
using systems::Linearize;
using systems::LinearSystem;
using systems::OutputPortIndex;
using systems::VectorBase;
namespace multibody {
class MultibodyPlantTester {
public:
MultibodyPlantTester() = delete;
template <typename T>
static BodyIndex FindBodyByGeometryId(const MultibodyPlant<T>& plant,
GeometryId id) {
return plant.FindBodyByGeometryId(id);
}
template <typename T>
static void AddJointActuationForces(const MultibodyPlant<T>& plant,
const systems::Context<T>& context,
VectorX<T>* forces) {
plant.AddJointActuationForces(context, forces);
}
};
namespace {
// Verifies that fresh-constructed plants are using the default contact surface
// representation.
GTEST_TEST(MultibodyPlant, GetDefaultContactSurfaceRepresentation) {
std::array<double, 2> time_steps{0.0, 0.1};
for (const auto& time_step : time_steps) {
MultibodyPlant<double> plant{time_step};
EXPECT_EQ(plant.get_contact_surface_representation(),
MultibodyPlant<double>::GetDefaultContactSurfaceRepresentation(
time_step));
}
}
// This test creates a simple model for an acrobot using MultibodyPlant and
// verifies a number of invariants such as that body and joint models were
// properly added and the model sizes.
GTEST_TEST(MultibodyPlant, SimpleModelCreation) {
const std::string kInvalidName = "InvalidName";
const AcrobotParameters parameters;
unique_ptr<MultibodyPlant<double>> plant =
MakeAcrobotPlant(parameters, false /* Don't make a finalized plant. */);
// Model Size. Counting the world body, there should be three bodies.
EXPECT_EQ(plant->num_bodies(), 3);
EXPECT_EQ(plant->num_joints(), 2);
EXPECT_EQ(plant->num_actuators(), 1);
EXPECT_EQ(plant->num_actuated_dofs(), 1);
// We expect to see the default and world model instances.
EXPECT_EQ(plant->num_model_instances(), 2);
// Add a split pendulum to the plant.
const ModelInstanceIndex pendulum_model_instance =
Parser(plant.get())
.AddModelsFromUrl(
"package://drake/multibody/plant/test/split_pendulum.sdf")
.at(0);
EXPECT_EQ(plant->num_model_instances(), 3);
plant->Finalize();
// We should throw an exception if finalize is called twice. Verify this.
EXPECT_THROW(plant->Finalize(), std::logic_error);
// Verify that a non-positive penetration_allowance throws an exception.
DRAKE_EXPECT_THROWS_MESSAGE(
plant->set_penetration_allowance(-1),
"set_penetration_allowance\\(\\): penetration_allowance must be strictly "
"positive.");
DRAKE_EXPECT_THROWS_MESSAGE(
plant->set_penetration_allowance(0),
"set_penetration_allowance\\(\\): penetration_allowance must be strictly "
"positive.");
// Verify the final model size for the model as a whole and for each instance.
EXPECT_EQ(plant->num_bodies(), 5);
EXPECT_EQ(plant->num_joints(), 4);
EXPECT_EQ(plant->num_actuators(), 2);
EXPECT_EQ(plant->num_actuated_dofs(), 2);
// World accessors.
EXPECT_EQ(&plant->world_body(), &plant->world_body());
EXPECT_EQ(&plant->world_frame(), &plant->world_frame());
// State size.
EXPECT_EQ(plant->num_positions(), 3);
EXPECT_EQ(plant->num_velocities(), 3);
EXPECT_EQ(plant->num_multibody_states(), 6);
// Acrobot is in the default model instance.
EXPECT_EQ(plant->num_actuators(default_model_instance()), 1);
EXPECT_EQ(plant->num_actuated_dofs(default_model_instance()), 1);
EXPECT_EQ(plant->num_positions(default_model_instance()), 2);
EXPECT_EQ(plant->num_velocities(default_model_instance()), 2);
// Pendulum model instance.
EXPECT_EQ(plant->num_actuators(pendulum_model_instance), 1);
EXPECT_EQ(plant->num_actuated_dofs(pendulum_model_instance), 1);
EXPECT_EQ(plant->num_positions(pendulum_model_instance), 1);
EXPECT_EQ(plant->num_velocities(pendulum_model_instance), 1);
// Check that the input/output ports have the appropriate geometry.
EXPECT_EQ(plant->get_actuation_input_port(default_model_instance()).size(),
1);
EXPECT_EQ(plant->get_actuation_input_port(pendulum_model_instance).size(), 1);
EXPECT_EQ(plant->get_actuation_input_port().size(), 2);
EXPECT_EQ(plant->get_state_output_port().size(), 6);
EXPECT_EQ(plant->get_state_output_port(default_model_instance()).size(), 4);
EXPECT_EQ(plant->get_state_output_port(pendulum_model_instance).size(), 2);
// Check that model-instance ports get named properly.
EXPECT_TRUE(plant->HasModelInstanceNamed("DefaultModelInstance"));
EXPECT_TRUE(plant->HasModelInstanceNamed("SplitPendulum"));
EXPECT_EQ(
plant->get_actuation_input_port(default_model_instance()).get_name(),
"DefaultModelInstance_actuation");
EXPECT_EQ(plant->get_state_output_port(default_model_instance()).get_name(),
"DefaultModelInstance_state");
EXPECT_EQ(plant->get_state_output_port(pendulum_model_instance).get_name(),
"SplitPendulum_state");
// Query if elements exist in the model.
EXPECT_TRUE(plant->HasBodyNamed(parameters.link1_name()));
EXPECT_TRUE(plant->HasBodyNamed(parameters.link2_name()));
EXPECT_FALSE(plant->HasBodyNamed(kInvalidName));
// Indicator that the plant is calling the tree's method correctly.
EXPECT_EQ(plant->NumBodiesWithName(parameters.link1_name()), 1);
EXPECT_EQ(plant->NumBodiesWithName(kInvalidName), 0);
EXPECT_TRUE(plant->HasJointNamed(parameters.shoulder_joint_name()));
EXPECT_TRUE(plant->HasJointNamed(parameters.elbow_joint_name()));
EXPECT_FALSE(plant->HasJointNamed(kInvalidName));
EXPECT_TRUE(plant->HasJointActuatorNamed(parameters.actuator_name()));
EXPECT_FALSE(plant->HasJointActuatorNamed(kInvalidName));
// Get links by name.
const RigidBody<double>& link1 =
plant->GetBodyByName(parameters.link1_name());
EXPECT_EQ(link1.name(), parameters.link1_name());
EXPECT_EQ(link1.model_instance(), default_model_instance());
const RigidBody<double>& link2 =
plant->GetBodyByName(parameters.link2_name());
EXPECT_EQ(link2.name(), parameters.link2_name());
EXPECT_EQ(link2.model_instance(), default_model_instance());
const RigidBody<double>& upper = plant->GetBodyByName("upper_section");
EXPECT_EQ(upper.model_instance(), pendulum_model_instance);
const RigidBody<double>& lower = plant->GetBodyByName("lower_section");
EXPECT_EQ(lower.model_instance(), pendulum_model_instance);
// Attempting to retrieve a link that is not part of the model should throw
// an exception.
EXPECT_THROW(plant->GetBodyByName(kInvalidName), std::logic_error);
// Get body indices by model_instance.
const std::vector<BodyIndex> acrobot_indices =
plant->GetBodyIndices(default_model_instance());
EXPECT_EQ(acrobot_indices.size(), 2);
EXPECT_EQ(acrobot_indices[0], link1.index());
EXPECT_EQ(acrobot_indices[1], link2.index());
const std::vector<BodyIndex> pendulum_indices =
plant->GetBodyIndices(pendulum_model_instance);
EXPECT_EQ(pendulum_indices.size(), 2);
EXPECT_EQ(pendulum_indices[0], upper.index());
EXPECT_EQ(pendulum_indices[1], lower.index());
// Get joints by name.
const Joint<double>& shoulder_joint =
plant->GetJointByName(parameters.shoulder_joint_name());
EXPECT_EQ(shoulder_joint.name(), parameters.shoulder_joint_name());
EXPECT_EQ(shoulder_joint.model_instance(), default_model_instance());
Joint<double>& mutable_shoulder_joint =
plant->GetMutableJointByName(parameters.shoulder_joint_name());
EXPECT_EQ(&mutable_shoulder_joint, &shoulder_joint);
const Joint<double>& elbow_joint =
plant->GetJointByName(parameters.elbow_joint_name());
EXPECT_EQ(elbow_joint.name(), parameters.elbow_joint_name());
EXPECT_EQ(elbow_joint.model_instance(), default_model_instance());
const Joint<double>& pin_joint = plant->GetJointByName("pin");
EXPECT_EQ(pin_joint.model_instance(), pendulum_model_instance);
const Joint<double>& weld_joint = plant->GetJointByName("weld");
EXPECT_EQ(weld_joint.model_instance(), pendulum_model_instance);
EXPECT_THROW(plant->GetJointByName(kInvalidName), std::logic_error);
// Get force elements by index. In this case the default gravity field.
const ForceElementIndex gravity_field_index(0);
EXPECT_EQ(
&plant->gravity_field(),
&plant->GetForceElement<UniformGravityFieldElement>(gravity_field_index));
DRAKE_EXPECT_THROWS_MESSAGE(
plant->GetForceElement<RevoluteSpring>(gravity_field_index),
".*not of type .*RevoluteSpring.* but of type "
".*UniformGravityFieldElement.*");
const ForceElementIndex invalid_force_index(plant->num_force_elements() + 1);
EXPECT_ANY_THROW(plant->GetForceElement<RevoluteSpring>(invalid_force_index));
// Get joint indices by model instance.
const std::vector<JointIndex> acrobot_joint_indices =
plant->GetJointIndices(default_model_instance());
EXPECT_EQ(acrobot_joint_indices.size(), 2);
EXPECT_EQ(acrobot_joint_indices[0], shoulder_joint.index());
EXPECT_EQ(acrobot_joint_indices[1], elbow_joint.index());
const std::vector<JointIndex> pendulum_joint_indices =
plant->GetJointIndices(pendulum_model_instance);
EXPECT_EQ(pendulum_joint_indices.size(), 2); // pin joint + weld joint.
EXPECT_EQ(pendulum_joint_indices[0], pin_joint.index());
EXPECT_EQ(pendulum_joint_indices[1], weld_joint.index());
// Get actuated joint indices only, by model instance.
const std::vector<JointIndex> acrobot_actuated_joint_indices =
plant->GetActuatedJointIndices(default_model_instance());
EXPECT_EQ(acrobot_actuated_joint_indices.size(), 1);
EXPECT_EQ(acrobot_actuated_joint_indices[0], elbow_joint.index());
const std::vector<JointIndex> pendulum_actuated_joint_indices =
plant->GetActuatedJointIndices(pendulum_model_instance);
EXPECT_EQ(pendulum_actuated_joint_indices.size(), 1); // pin joint
EXPECT_EQ(pendulum_actuated_joint_indices[0], pin_joint.index());
// Get actuated joint actuator indices by model instance.
const std::vector<JointActuatorIndex> acrobot_joint_actuator_indices =
plant->GetJointActuatorIndices(default_model_instance());
EXPECT_EQ(acrobot_joint_actuator_indices.size(), 1);
EXPECT_EQ(plant->get_joint_actuator(acrobot_joint_actuator_indices[0])
.joint()
.index(),
elbow_joint.index());
const std::vector<JointActuatorIndex> pendulum_joint_actuator_indices =
plant->GetJointActuatorIndices(pendulum_model_instance);
EXPECT_EQ(pendulum_joint_actuator_indices.size(), 1); // pin joint
EXPECT_EQ(plant->get_joint_actuator(pendulum_joint_actuator_indices[0])
.joint()
.index(),
pin_joint.index());
// Templatized version to obtain retrieve a particular known type of joint.
const RevoluteJoint<double>& shoulder =
plant->GetJointByName<RevoluteJoint>(parameters.shoulder_joint_name());
EXPECT_EQ(shoulder.name(), parameters.shoulder_joint_name());
const RevoluteJoint<double>& elbow =
plant->GetJointByName<RevoluteJoint>(parameters.elbow_joint_name());
EXPECT_EQ(elbow.name(), parameters.elbow_joint_name());
const RevoluteJoint<double>& pin =
plant->GetJointByName<RevoluteJoint>("pin");
EXPECT_EQ(pin.name(), "pin");
EXPECT_THROW(plant->GetJointByName(kInvalidName), std::logic_error);
// Templatized version throws when the requested joint doesn't have the
// expected type.
DRAKE_EXPECT_THROWS_MESSAGE(
plant->GetJointByName<PrismaticJoint>(parameters.shoulder_joint_name(),
shoulder.model_instance()),
".*not of type .*PrismaticJoint.* but of type "
".*RevoluteJoint.*");
// MakeAcrobotPlant() has already called Finalize() on the acrobot model.
// Therefore no more modeling elements can be added. Verify this.
DRAKE_EXPECT_THROWS_MESSAGE(
plant->AddRigidBody("AnotherBody", default_model_instance(),
SpatialInertia<double>::NaN()),
"Post-finalize calls to '.*' are not allowed; "
"calls to this method must happen before Finalize\\(\\).");
DRAKE_EXPECT_THROWS_MESSAGE(
plant->AddJoint<RevoluteJoint>("AnotherJoint", link1, std::nullopt, link2,
std::nullopt, Vector3d::UnitZ()),
"Post-finalize calls to '.*' are not allowed; "
"calls to this method must happen before Finalize\\(\\).");
// Test API for simplified `AddJoint` method.
DRAKE_EXPECT_THROWS_MESSAGE(
plant->AddJoint(std::make_unique<RevoluteJoint<double>>(
"AnotherJoint", link1.body_frame(), link2.body_frame(),
Vector3d::UnitZ())),
"Post-finalize calls to '.*' are not allowed; "
"calls to this method must happen before Finalize\\(\\).");
// TODO(amcastro-tri): add test to verify that requesting a joint of the wrong
// type throws an exception. We need another joint type to do so.
// Get frame indices by model_instance
const std::vector<FrameIndex> acrobot_frame_indices =
plant->GetFrameIndices(default_model_instance());
ASSERT_EQ(acrobot_frame_indices.size(), 3);
EXPECT_EQ(acrobot_frame_indices[0], link1.body_frame().index());
EXPECT_EQ(acrobot_frame_indices[1], link2.body_frame().index());
EXPECT_EQ(acrobot_frame_indices[2], elbow_joint.frame_on_parent().index());
const Frame<double>& model_frame = plant->GetFrameByName("__model__");
EXPECT_EQ(model_frame.model_instance(), pendulum_model_instance);
const std::vector<FrameIndex> pendulum_frame_indices =
plant->GetFrameIndices(pendulum_model_instance);
ASSERT_EQ(pendulum_frame_indices.size(), 6);
EXPECT_EQ(pendulum_frame_indices[0], upper.body_frame().index());
EXPECT_EQ(pendulum_frame_indices[1], lower.body_frame().index());
EXPECT_EQ(pendulum_frame_indices[2], model_frame.index());
EXPECT_EQ(pendulum_frame_indices[3], pin_joint.frame_on_child().index());
EXPECT_EQ(pendulum_frame_indices[4], weld_joint.frame_on_parent().index());
EXPECT_EQ(pendulum_frame_indices[5], weld_joint.frame_on_child().index());
}
GTEST_TEST(MultibodyPlantTest, AddJointActuator) {
MultibodyPlant<double> plant(0.0);
ModelInstanceIndex model_instance = plant.AddModelInstance("instance");
const auto M_B = SpatialInertia<double>::NaN();
auto body = &plant.AddRigidBody("body", model_instance, M_B);
const Joint<double>& planar_joint =
plant.AddJoint(std::make_unique<PlanarJoint<double>>(
"planar", plant.world_body().body_frame(), body->body_frame(),
Eigen::Vector3d{0, 0, 0.1}));
DRAKE_EXPECT_THROWS_MESSAGE(
plant.AddJointActuator("planar_actuator", planar_joint),
".*3 degrees of freedom.*");
}
GTEST_TEST(MultibodyPlantTest, AddMultibodyPlantSceneGraph) {
systems::DiagramBuilder<double> builder;
auto pair = AddMultibodyPlantSceneGraph(&builder, 0.0);
MultibodyPlant<double>* plant{};
geometry::SceneGraph<double>* scene_graph{};
// Check `tie` assignment.
std::tie(plant, scene_graph) = pair;
EXPECT_NE(plant, nullptr);
EXPECT_NE(scene_graph, nullptr);
// Check referencing.
MultibodyPlant<double>& plant_ref = pair;
EXPECT_EQ(&plant_ref, plant);
// Check support for C++ structured binding.
auto [first_element, second_element] =
AddMultibodyPlantSceneGraph(&builder, 0.0);
// Verify the expected types.
EXPECT_EQ(drake::NiceTypeName::Get(first_element),
drake::NiceTypeName::Get<MultibodyPlant<double>>());
EXPECT_EQ(drake::NiceTypeName::Get(second_element),
drake::NiceTypeName::Get<SceneGraph<double>>());
// These should fail:
// AddMultibodyPlantSceneGraphResult<double> extra(plant, scene_graph);
// AddMultibodyPlantSceneGraphResult<double> extra{*plant, *scene_graph};
}
// Verifies that string-based queries allocate no heap.
//
// NOTE: Every querying API that takes strings as parameters should conform to
// this non-allocating convention. As such, they should be invoked in this
// test to show that they adhere to that expectation. It should be considered
// to be a defect if such an API exists and is omitted here (for whatever
// historical reason).
GTEST_TEST(MultibodyPlantTest, NoHeapAllocOnStringQueries) {
// Construct a plant with an Iiwa.
const char kSdfUrl[] =
"package://drake_models/iiwa_description/sdf/iiwa14_no_collision.sdf";
auto plant =
std::make_unique<MultibodyPlant<double>>(0 /* plant type irrelevant */);
Parser parser(plant.get());
multibody::ModelInstanceIndex iiwa_instance =
parser.AddModelsFromUrl(kSdfUrl).at(0);
plant->Finalize();
// Use string to ensure that there is no heap allocation in the implicit
// conversion to string_view.
const std::string kLinkName = "iiwa_link_0";
const std::string kJointName = "iiwa_joint_1";
// Note that failed queries cause exceptions to be thrown (which allocates
// heap).
drake::test::LimitMalloc dummy;
// Check the HasX versions first. Note that functions that take no model
// instance argument delegate to model instance argument versions.
EXPECT_TRUE(plant->HasModelInstanceNamed("iiwa14"));
EXPECT_TRUE(plant->HasBodyNamed(kLinkName, iiwa_instance));
EXPECT_TRUE(plant->HasFrameNamed(kLinkName, iiwa_instance));
EXPECT_TRUE(plant->HasJointNamed(kJointName, iiwa_instance));
EXPECT_TRUE(plant->HasJointActuatorNamed(kJointName, iiwa_instance));
// Check the GetX versions now.
plant->GetModelInstanceByName("iiwa14");
plant->GetBodyByName(kLinkName, iiwa_instance);
plant->GetFrameByName(kLinkName, iiwa_instance);
plant->GetJointByName(kJointName, iiwa_instance);
plant->GetJointActuatorByName(kJointName, iiwa_instance);
}
// This test creates an empty model and checks simple invariants on model
// elements. We test the contracts here, not in MultibodyTree, to test
// behavior from public API perspective.
GTEST_TEST(MultibodyPlant, EmptyWorldElements) {
const double time_step = 0.0;
MultibodyPlant<double> plant(time_step);
// Model instances.
EXPECT_EQ(plant.num_model_instances(), 2);
// Bodies.
EXPECT_EQ(plant.num_bodies(), 1);
const RigidBody<double>& world_body = plant.world_body();
EXPECT_EQ(world_body.index(), world_index());
EXPECT_EQ(world_body.model_instance(), world_model_instance());
// Frames.
EXPECT_EQ(plant.num_frames(), 1);
const Frame<double>& world_frame = plant.world_frame();
EXPECT_EQ(world_frame.index(), world_frame_index());
EXPECT_EQ(world_frame.model_instance(), world_model_instance());
EXPECT_EQ(&world_body.body_frame(), &world_frame);
// Remaining elements.
EXPECT_EQ(plant.num_joints(), 0);
EXPECT_EQ(plant.num_actuators(), 0);
EXPECT_EQ(plant.num_constraints(), 0);
EXPECT_EQ(plant.num_coupler_constraints(), 0);
EXPECT_EQ(plant.num_distance_constraints(), 0);
EXPECT_EQ(plant.num_ball_constraints(), 0);
EXPECT_EQ(plant.num_force_elements(), 1);
}
GTEST_TEST(MultibodyPlantTest, EmptyWorldDiscrete) {
const double discrete_update_period = 1.0e-3;
MultibodyPlant<double> plant(discrete_update_period);
plant.Finalize();
EXPECT_EQ(plant.num_velocities(), 0);
EXPECT_EQ(plant.num_positions(), 0);
EXPECT_EQ(plant.num_multibody_states(), 0);
EXPECT_EQ(plant.num_actuated_dofs(), 0);
// Compute discrete update.
auto context = plant.CreateDefaultContext();
auto& discrete_state_vector = context->get_discrete_state_vector();
EXPECT_EQ(discrete_state_vector.size(), 0);
auto new_discrete_state = plant.AllocateDiscreteVariables();
const systems::VectorBase<double>& new_discrete_state_vector =
new_discrete_state->get_vector();
EXPECT_EQ(new_discrete_state_vector.size(), 0);
DRAKE_EXPECT_NO_THROW(plant.CalcForcedDiscreteVariableUpdate(
*context, new_discrete_state.get()));
}
GTEST_TEST(MultibodyPlantTest, EmptyWorldContinuous) {
MultibodyPlant<double> plant(0.0);
plant.Finalize();
EXPECT_EQ(plant.num_velocities(), 0);
EXPECT_EQ(plant.num_positions(), 0);
EXPECT_EQ(plant.num_multibody_states(), 0);
EXPECT_EQ(plant.num_actuated_dofs(), 0);
// Compute continuous derivatives.
auto context = plant.CreateDefaultContext();
auto& continuous_state_vector = context->get_continuous_state_vector();
EXPECT_EQ(continuous_state_vector.size(), 0);
auto new_derivatives = plant.AllocateTimeDerivatives();
EXPECT_EQ(new_derivatives->size(), 0);
DRAKE_EXPECT_NO_THROW(
plant.CalcTimeDerivatives(*context, new_derivatives.get()));
VectorXd residual = plant.AllocateImplicitTimeDerivativesResidual();
EXPECT_EQ(residual.size(), 0);
DRAKE_EXPECT_NO_THROW(plant.CalcImplicitTimeDerivativesResidual(
*context, *new_derivatives, &residual));
}
GTEST_TEST(MultibodyPlantTest, EmptyWorldContactErrors) {
MultibodyPlant<double> plant(0.0);
DRAKE_EXPECT_THROWS_MESSAGE(
MultibodyPlantTester::FindBodyByGeometryId(plant, GeometryId{}),
".* contact results for a null GeometryId.*");
const GeometryId unknown_id = GeometryId::get_new_id();
DRAKE_EXPECT_THROWS_MESSAGE(
MultibodyPlantTester::FindBodyByGeometryId(plant, unknown_id),
".* contact results for GeometryId .* but that ID is not known.*");
}
GTEST_TEST(ActuationPortsTest, CheckActuation) {
// Create a MultibodyPlant consisting of two model instances, one actuated
// and the other unactuated.
MultibodyPlant<double> plant(0.0);
const std::string acrobot_url =
"package://drake/multibody/benchmarks/acrobot/acrobot.sdf";
const std::string cylinder_url =
"package://drake/multibody/benchmarks/free_body/"
"uniform_solid_cylinder.urdf";
Parser parser(&plant);
auto acrobot_instance = parser.AddModelsFromUrl(acrobot_url).at(0);
auto cylinder_instance = parser.AddModelsFromUrl(cylinder_url).at(0);
plant.Finalize();
// Verify the number of actuators.
EXPECT_EQ(plant.num_actuated_dofs(acrobot_instance), 1);
EXPECT_EQ(plant.num_actuated_dofs(cylinder_instance), 0);
// Verify which bodies are free and modeled with quaternions.
EXPECT_FALSE(plant.GetBodyByName("Link1").is_floating());
EXPECT_FALSE(plant.GetBodyByName("Link1").has_quaternion_dofs());
EXPECT_FALSE(plant.GetBodyByName("Link2").is_floating());
EXPECT_FALSE(plant.GetBodyByName("Link2").has_quaternion_dofs());
EXPECT_TRUE(plant.GetBodyByName("uniformSolidCylinder").is_floating());
EXPECT_TRUE(
plant.GetBodyByName("uniformSolidCylinder").has_quaternion_dofs());
// Verify that we can get the actuation input ports.
DRAKE_EXPECT_NO_THROW(plant.get_actuation_input_port());
DRAKE_EXPECT_NO_THROW(plant.get_actuation_input_port(acrobot_instance));
DRAKE_EXPECT_NO_THROW(plant.get_actuation_input_port(cylinder_instance));
// Compute the derivatives without connecting the acrobot_instance port.
// Actuation defaults to zero.
std::unique_ptr<Context<double>> context = plant.CreateDefaultContext();
std::unique_ptr<ContinuousState<double>> xdot_no_input =
plant.AllocateTimeDerivatives();
plant.CalcTimeDerivatives(*context, xdot_no_input.get());
// Compute derivatives after fixing the acrobot actuation input port
// explicitly to a zero value of actuation.
plant.get_actuation_input_port(acrobot_instance).FixValue(context.get(), 0.0);
std::unique_ptr<ContinuousState<double>> xdot_zero_input =
plant.AllocateTimeDerivatives();
plant.CalcTimeDerivatives(*context, xdot_zero_input.get());
// Verify that both derivatives are the same since no input defaults to zero
// actuation.
constexpr double kEps = std::numeric_limits<double>::epsilon();
EXPECT_TRUE(CompareMatrices(xdot_no_input->CopyToVector(),
xdot_zero_input->CopyToVector(), kEps,
MatrixCompareType::relative));
// Verify that derivatives can be computed after fixing the cylinder actuation
// input port with an empty vector.
plant.get_actuation_input_port(cylinder_instance)
.FixValue(context.get(), VectorXd(0));
std::unique_ptr<ContinuousState<double>> xdot =
plant.AllocateTimeDerivatives();
plant.CalcTimeDerivatives(*context, xdot.get());
// Non-zero actuation for the acrobot.
plant.get_actuation_input_port(acrobot_instance).FixValue(context.get(), 5.0);
plant.CalcTimeDerivatives(*context, xdot.get());
// Distribute the actuation value of 5.0 between the two input ports.
plant.get_actuation_input_port(acrobot_instance).FixValue(context.get(), 3.5);
plant.get_actuation_input_port().FixValue(context.get(), 1.5);
std::unique_ptr<ContinuousState<double>> xdot_sum =
plant.AllocateTimeDerivatives();
plant.CalcTimeDerivatives(*context, xdot_sum.get());
// Verify that the contribution from per model instance actuation and full
// plant actuation is additive.
EXPECT_TRUE(CompareMatrices(xdot_sum->CopyToVector(), xdot->CopyToVector(),
kEps, MatrixCompareType::relative));
}
GTEST_TEST(MultibodyPlant, UniformGravityFieldElementTest) {
MultibodyPlant<double> plant(0.0);
DRAKE_EXPECT_THROWS_MESSAGE(
plant.AddForceElement<UniformGravityFieldElement>(Vector3d(-1, 0, 0)),
"This model already contains a gravity field element.*");
}
// Fixture to perform a number of computational tests on an acrobot model.
class AcrobotPlantTests : public ::testing::Test {
public:
// Creates MultibodyPlant for an acrobot model.
void SetUp() override {
systems::DiagramBuilder<double> builder;
// Make a non-finalized plant so that we can tests methods with pre/post
// Finalize() conditions.
const std::string url =
"package://drake/multibody/benchmarks/acrobot/acrobot.sdf";
std::tie(plant_, scene_graph_) = AddMultibodyPlantSceneGraph(&builder, 0.0);
Parser(plant_).AddModelsFromUrl(url);
// Sanity check on the availability of the optional source id before using
// it.
DRAKE_DEMAND(plant_->get_source_id() != std::nullopt);
// Ensure that we can access the geometry ports pre-finalize.
DRAKE_EXPECT_NO_THROW(plant_->get_geometry_query_input_port());
DRAKE_EXPECT_NO_THROW(plant_->get_geometry_pose_output_port());
// Also sanity check the deprecated getter (2024-10-01).
#pragma GCC diagnostic push
#pragma GCC diagnostic ignored "-Wdeprecated-declarations"
DRAKE_EXPECT_NO_THROW(plant_->get_geometry_poses_output_port());
#pragma GCC diagnostic push
DRAKE_EXPECT_THROWS_MESSAGE(
plant_->get_state_output_port(),
/* Verify this method is throwing for the right reasons. */
"Pre-finalize calls to '.*' are not allowed; "
"you must call Finalize\\(\\) first.");
link1_ = &plant_->GetBodyByName(parameters_.link1_name());
link2_ = &plant_->GetBodyByName(parameters_.link2_name());
// Test we can call these methods pre-finalize.
const FrameId link1_frame_id =
plant_->GetBodyFrameIdOrThrow(link1_->index());
EXPECT_EQ(link1_frame_id, *plant_->GetBodyFrameIdIfExists(link1_->index()));
EXPECT_EQ(plant_->GetBodyFromFrameId(link1_frame_id), link1_);
// Finalize() the plant.
plant_->Finalize();
// And build the Diagram:
diagram_ = builder.Build();
shoulder_ = &plant_->GetMutableJointByName<RevoluteJoint>(
parameters_.shoulder_joint_name());
elbow_ = &plant_->GetMutableJointByName<RevoluteJoint>(
parameters_.elbow_joint_name());
context_ = diagram_->CreateDefaultContext();
derivatives_ = diagram_->AllocateTimeDerivatives();
plant_context_ =
&diagram_->GetMutableSubsystemContext(*plant_, context_.get());
ASSERT_GT(plant_->num_actuators(), 0);
input_port_ =
&plant_->get_actuation_input_port().FixValue(plant_context_, 0.0);
}
void SetUpDiscreteAcrobotPlant(double time_step, bool sampled) {
systems::DiagramBuilder<double> builder;
const std::string url =
"package://drake/multibody/benchmarks/acrobot/acrobot.sdf";
discrete_plant_ = std::make_unique<MultibodyPlant<double>>(time_step);
discrete_plant_->SetUseSampledOutputPorts(sampled);
Parser(discrete_plant_.get()).AddModelsFromUrl(url);
discrete_plant_->Finalize();
discrete_context_ = discrete_plant_->CreateDefaultContext();
ASSERT_EQ(discrete_plant_->num_actuators(), 1);
discrete_plant_->get_actuation_input_port().FixValue(
discrete_context_.get(), 0.0);
ASSERT_EQ(discrete_plant_->num_positions(), 2);
ASSERT_EQ(discrete_plant_->num_velocities(), 2);
ASSERT_EQ(discrete_plant_->GetPositions(*discrete_context_).size(), 2);
ASSERT_EQ(discrete_plant_->GetVelocities(*discrete_context_).size(), 2);
}
// Computes the vector of generalized forces due to gravity.
// This test is mostly to verify MultibodyPlant provides the proper APIs to
// perform this computations.
void VerifyCalcGravityGeneralizedForces(double theta1, double theta2) {
const double kTolerance = 5 * std::numeric_limits<double>::epsilon();
// Set the state:
shoulder_->set_angle(plant_context_, theta1);
elbow_->set_angle(plant_context_, theta2);
// Set arbitrary non-zero velocities to test they do not affect the results.
shoulder_->set_angular_rate(plant_context_, 10.0);
elbow_->set_angular_rate(plant_context_, 10.0);
// Calculate the generalized forces due to gravity.
const VectorX<double> tau_g =
plant_->CalcGravityGeneralizedForces(*plant_context_);
// Calculate a benchmark value.
const Vector2d tau_g_expected =
acrobot_benchmark_.CalcGravityVector(theta1, theta2);
EXPECT_TRUE(CompareMatrices(tau_g, tau_g_expected, kTolerance,
MatrixCompareType::relative));
// Alternatively, we can use CalcForceElementsContribution().
MultibodyForces<double> forces(*plant_);
plant_->CalcForceElementsContribution(*plant_context_, &forces);
// N.B. For this particular model we know `forces` only includes generalized
// forces due to dissipation at the joints and spatial forces due to
// gravity. In general after this call, MultibodyForces will contain a soup
// of all forces stemming from a ForceElement making it impossible to
// discern separate contributions. Therefore we should always use
// ForceElement's API to retrieve the specific component we are interested
// in. Here we access the internal data in MultibodyForces directly for
// testing purposes only, a pattern not to be followed.
// We verify first the body spatial forces include gravity. For this case,
// it is all they should include. Skip the world, index = 0.
const Vector3<double> gacc = plant_->gravity_field().gravity_vector();
for (BodyIndex body_index(1); body_index < plant_->num_bodies();
++body_index) {
const RigidBody<double>& body = plant_->get_body(body_index);
const SpatialForce<double>& F_Bo_W =
body.GetForceInWorld(*plant_context_, forces);
const double mass = body.default_mass();
// TODO(amcastro-tri): provide RigidBody::EvalCOMInWorld().
const Vector3<double> p_BoBcm_B =
body.CalcCenterOfMassInBodyFrame(*plant_context_);
const RigidTransform<double> X_WB =
plant_->EvalBodyPoseInWorld(*plant_context_, body);
const RotationMatrix<double> R_WB = X_WB.rotation();
const Vector3<double> p_BoBcm_W = R_WB * p_BoBcm_B;
const Vector3<double> f_Bo_W_expected = mass * gacc;
const Vector3<double> t_Bo_W_expected = p_BoBcm_W.cross(f_Bo_W_expected);
EXPECT_TRUE(CompareMatrices(F_Bo_W.translational(), f_Bo_W_expected,
kTolerance, MatrixCompareType::relative));
EXPECT_TRUE(CompareMatrices(F_Bo_W.rotational(), t_Bo_W_expected,
kTolerance, MatrixCompareType::relative));
}
// Now we'll use inverse dynamics to obtain the generalized forces
// contribution due to gravity.
// Zero generalized forces due to joint dissipation.
forces.mutable_generalized_forces().setZero();
// Zero accelerations.
const VectorX<double> zero_vdot =
VectorX<double>::Zero(plant_->num_velocities());
// Zero velocities.
shoulder_->set_angular_rate(plant_context_, 0.0);
elbow_->set_angular_rate(plant_context_, 0.0);
const VectorX<double> tau_g_id =
-plant_->CalcInverseDynamics(*plant_context_, zero_vdot, forces);
EXPECT_TRUE(CompareMatrices(tau_g_id, tau_g_expected, kTolerance,
MatrixCompareType::relative));
}
// Verifies the computation performed by MultibodyPlant::CalcTimeDerivatives()
// for the acrobot model. The comparison is carried out against a benchmark
// with hand written dynamics.
void VerifyCalcTimeDerivatives(double theta1, double theta2, double theta1dot,
double theta2dot, double input_torque) {
const double kTolerance = 5 * std::numeric_limits<double>::epsilon();
// Set the state:
shoulder_->set_angle(plant_context_, theta1);
elbow_->set_angle(plant_context_, theta2);
shoulder_->set_angular_rate(plant_context_, theta1dot);
elbow_->set_angular_rate(plant_context_, theta2dot);
// Fix input port to a value before computing anything. In this case, zero
// actuation.
input_port_->GetMutableVectorData<double>()->SetAtIndex(0, input_torque);
diagram_->CalcTimeDerivatives(*context_, derivatives_.get());
const VectorXd xdot = derivatives_->CopyToVector();
// Now compute inverse dynamics using our benchmark:
const Vector2d C_expected = acrobot_benchmark_.CalcCoriolisVector(
theta1, theta2, theta1dot, theta2dot);
const Vector2d tau_g_expected =
acrobot_benchmark_.CalcGravityVector(theta1, theta2);
const Vector2d tau_damping(-parameters_.b1() * theta1dot,
-parameters_.b2() * theta2dot);
// Verify the computation of the contribution due to joint damping.
MultibodyForces<double> forces(*plant_);
shoulder_->AddInDamping(*plant_context_, &forces);
elbow_->AddInDamping(*plant_context_, &forces);
EXPECT_TRUE(CompareMatrices(forces.generalized_forces(), tau_damping,
kTolerance, MatrixCompareType::relative));
// Verify the computation of xdot.
const Vector2d rhs =
tau_g_expected + tau_damping - C_expected + Vector2d(0.0, input_torque);
const Matrix2d M_expected = acrobot_benchmark_.CalcMassMatrix(theta2);
const Vector2d vdot_expected = M_expected.inverse() * rhs;
VectorXd xdot_expected(4);
xdot_expected << Vector2d(theta1dot, theta2dot), vdot_expected;
EXPECT_TRUE(CompareMatrices(xdot, xdot_expected, kTolerance,
MatrixCompareType::relative));
// Verify that the implicit dynamics match the continuous ones.
VectorXd residual = diagram_->AllocateImplicitTimeDerivativesResidual();
diagram_->CalcImplicitTimeDerivativesResidual(*context_, *derivatives_,
&residual);
EXPECT_TRUE(CompareMatrices(residual, VectorXd::Zero(4), 1e-14));
}
// Verifies the computation performed by
// MultibodyPlant::CalcDiscreteVariableUpdates(). For this simple model
// without contact, we verify that this method performs the periodic update
// of the state using a semi-explicit Euler strategy, that is:
// vⁿ⁺¹ = vⁿ + dt v̇ⁿ
// qⁿ⁺¹ = qⁿ + dt N(qⁿ) vⁿ⁺¹
// To perform this verification, we compute v̇ⁿ using
// MultibodyPlant::CalcTimeDerivatives().
void VerifyDoCalcDiscreteVariableUpdates(double theta1, double theta2,
double theta1dot, double theta2dot) {
DRAKE_DEMAND(plant_ != nullptr);
DRAKE_DEMAND(discrete_plant_ != nullptr);
const double kTolerance = 5 * std::numeric_limits<double>::epsilon();
const double time_step = discrete_plant_->time_step();
// Set the state for the continuous model:
shoulder_->set_angle(plant_context_, theta1);
elbow_->set_angle(plant_context_, theta2);
shoulder_->set_angular_rate(plant_context_, theta1dot);
elbow_->set_angular_rate(plant_context_, theta2dot);
// Set the state for the discrete model:
const RevoluteJoint<double>& discrete_shoulder =
discrete_plant_->GetJointByName<RevoluteJoint>(
parameters_.shoulder_joint_name());
const RevoluteJoint<double>& discrete_elbow =
discrete_plant_->GetJointByName<RevoluteJoint>(
parameters_.elbow_joint_name());
discrete_shoulder.set_angle(discrete_context_.get(), theta1);
discrete_elbow.set_angle(discrete_context_.get(), theta2);
discrete_shoulder.set_angular_rate(discrete_context_.get(), theta1dot);
discrete_elbow.set_angular_rate(discrete_context_.get(), theta2dot);
diagram_->CalcTimeDerivatives(*context_, derivatives_.get());
auto updates = discrete_plant_->AllocateDiscreteVariables();
discrete_plant_->CalcForcedDiscreteVariableUpdate(*discrete_context_,
updates.get());
// Copies to plain Eigen vectors to verify the math.
const VectorXd x0 = context_->get_continuous_state_vector().CopyToVector();
const VectorXd xdot = derivatives_->CopyToVector();
const VectorXd xnext = updates->get_vector().CopyToVector();
// Verify that xnext is updated using a semi-explicit strategy, that is:
// vnext = v0 + dt * vdot
// qnext = q0 + dt * vnext
VectorXd xnext_expected(plant_->num_multibody_states());
const int nv = plant_->num_velocities();
const int nq = plant_->num_positions();
xnext_expected.segment(nq, nv) =
x0.segment(nq, nv) + time_step * xdot.segment(nq, nv);
// We use the fact that nq = nv for this case.
xnext_expected.segment(0, nq) =
x0.segment(0, nq) + time_step * xnext_expected.segment(nq, nv);
EXPECT_TRUE(CompareMatrices(xnext, xnext_expected, kTolerance,
MatrixCompareType::relative));
}
protected:
// The parameters of the model:
const AcrobotParameters parameters_;
// The model plant:
MultibodyPlant<double>* plant_{nullptr}; // Owned by diagram_ below.
std::unique_ptr<MultibodyPlant<double>> discrete_plant_;
// A SceneGraph so that we can test geometry registration.
SceneGraph<double>* scene_graph_{nullptr};
// The Diagram containing both the MultibodyPlant and the SceneGraph.
unique_ptr<Diagram<double>> diagram_;
// Workspace including diagram context and derivatives vector:
unique_ptr<Context<double>> context_;
unique_ptr<Context<double>> discrete_context_;
unique_ptr<ContinuousState<double>> derivatives_;
// Non-owning pointer to the plant context.
Context<double>* plant_context_{nullptr};
// Non-owning pointers to the model's elements:
const RigidBody<double>* link1_{nullptr};
const RigidBody<double>* link2_{nullptr};
RevoluteJoint<double>* shoulder_{nullptr};
RevoluteJoint<double>* elbow_{nullptr};
// Input port for the actuation:
systems::FixedInputPortValue* input_port_{nullptr};
// Reference benchmark for verification.
Acrobot<double> acrobot_benchmark_{Vector3d::UnitZ() /* Plane normal */,
Vector3d::UnitY() /* Up vector */,
parameters_.m1(),
parameters_.m2(),
parameters_.l1(),
parameters_.l2(),
parameters_.lc1(),
parameters_.lc2(),
parameters_.Ic1(),
parameters_.Ic2(),
parameters_.b1(),
parameters_.b2(),
parameters_.g()};
};
// Verifies we can compute the vector of generalized forces due to gravity on a
// model of an acrobot.
TEST_F(AcrobotPlantTests, VerifyCalcGravityGeneralizedForces) {
// Some arbitrary values of non-zero state:
VerifyCalcGravityGeneralizedForces(-M_PI / 5.0,
M_PI / 2.0 /* joint's angles */);
VerifyCalcGravityGeneralizedForces(M_PI / 3.0,
-M_PI / 5.0 /* joint's angles */);
VerifyCalcGravityGeneralizedForces(M_PI / 4.0,
-M_PI / 3.0 /* joint's angles */);
VerifyCalcGravityGeneralizedForces(-M_PI, -M_PI / 2.0 /* joint's angles */);
}
// Verifies the correctness of MultibodyPlant::CalcTimeDerivatives() on a model
// of an acrobot.
TEST_F(AcrobotPlantTests, CalcTimeDerivatives) {
// Some random tests with non-zero state:
VerifyCalcTimeDerivatives(-M_PI / 5.0, M_PI / 2.0, /* joint's angles */
0.5, 1.0, /* joint's angular rates */
-1.0); /* Actuation torque */
VerifyCalcTimeDerivatives(M_PI / 3.0, -M_PI / 5.0, /* joint's angles */
0.7, -1.0, /* joint's angular rates */
1.0); /* Actuation torque */
VerifyCalcTimeDerivatives(M_PI / 4.0, -M_PI / 3.0, /* joint's angles */
-0.5, 2.0, /* joint's angular rates */
-1.5); /* Actuation torque */
VerifyCalcTimeDerivatives(-M_PI, -M_PI / 2.0, /* joint's angles */
-1.5, -2.5, /* joint's angular rates */
2.0); /* Actuation torque */
}