forked from RobotLocomotion/drake
-
Notifications
You must be signed in to change notification settings - Fork 0
/
Copy pathdiagram.cc
1567 lines (1361 loc) · 59.2 KB
/
diagram.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/systems/framework/diagram.h"
#include <limits>
#include <set>
#include <stdexcept>
#include "drake/common/drake_assert.h"
#include "drake/common/text_logging.h"
#include "drake/systems/framework/subvector.h"
#include "drake/systems/framework/system_constraint.h"
#include "drake/systems/framework/system_visitor.h"
namespace drake {
namespace systems {
template <typename T>
Diagram<T>::~Diagram() {}
template <typename T>
std::vector<const systems::System<T>*> Diagram<T>::GetSystems() const {
std::vector<const systems::System<T>*> result;
result.reserve(registered_systems_.size());
for (const auto& system : registered_systems_) {
result.push_back(system.get());
}
return result;
}
template <typename T>
void Diagram<T>::Accept(SystemVisitor<T>* v) const {
DRAKE_DEMAND(v);
v->VisitDiagram(*this);
}
template <typename T>
const std::map<typename Diagram<T>::InputPortLocator,
typename Diagram<T>::OutputPortLocator>&
Diagram<T>::connection_map() const {
return connection_map_;
}
template <typename T>
std::vector<typename Diagram<T>::InputPortLocator>
Diagram<T>::GetInputPortLocators(
InputPortIndex port_index) const {
DRAKE_DEMAND(port_index >= 0 && port_index < this->num_input_ports());
std::vector<typename Diagram<T>::InputPortLocator> result;
for (const auto& map_pair : input_port_map_) {
if (map_pair.second == port_index) {
result.push_back(map_pair.first);
}
}
return result;
}
template <typename T>
typename Diagram<T>::InputPortLocator
Diagram<T>::GetArbitraryInputPortLocator(InputPortIndex port_index) const {
DRAKE_DEMAND(port_index >= 0 && port_index < this->num_input_ports());
const auto ids = GetInputPortLocators(port_index);
DRAKE_ASSERT(!ids.empty());
return ids[0];
}
template <typename T>
typename Diagram<T>::InputPortLocator
Diagram<T>::get_input_port_locator(InputPortIndex port_index) const {
return GetArbitraryInputPortLocator(port_index);
}
template <typename T>
const typename Diagram<T>::OutputPortLocator&
Diagram<T>::get_output_port_locator(OutputPortIndex port_index) const {
DRAKE_DEMAND(port_index >= 0 &&
port_index < static_cast<int>(output_port_ids_.size()));
return output_port_ids_[port_index];
}
template <typename T>
std::multimap<int, int> Diagram<T>::GetDirectFeedthroughs() const {
std::multimap<int, int> pairs;
for (InputPortIndex u(0); u < this->num_input_ports(); ++u) {
for (OutputPortIndex v(0); v < this->num_output_ports(); ++v) {
if (DiagramHasDirectFeedthrough(u, v)) {
pairs.emplace(u, v);
}
}
}
return pairs;
}
template <typename T>
std::unique_ptr<CompositeEventCollection<T>>
Diagram<T>::AllocateCompositeEventCollection() const {
const int num_systems = num_subsystems();
std::vector<std::unique_ptr<CompositeEventCollection<T>>> subevents(
num_systems);
for (SubsystemIndex i(0); i < num_systems; ++i) {
subevents[i] = registered_systems_[i]->AllocateCompositeEventCollection();
}
return std::make_unique<DiagramCompositeEventCollection<T>>(
std::move(subevents));
}
template <typename T>
void Diagram<T>::SetDefaultState(const Context<T>& context,
State<T>* state) const {
this->ValidateContext(context);
auto diagram_context = dynamic_cast<const DiagramContext<T>*>(&context);
DRAKE_DEMAND(diagram_context != nullptr);
auto diagram_state = dynamic_cast<DiagramState<T>*>(state);
DRAKE_DEMAND(diagram_state != nullptr);
// Set default state of each constituent system.
for (SubsystemIndex i(0); i < num_subsystems(); ++i) {
auto& subcontext = diagram_context->GetSubsystemContext(i);
auto& substate = diagram_state->get_mutable_substate(i);
registered_systems_[i]->SetDefaultState(subcontext, &substate);
}
}
template <typename T>
void Diagram<T>::SetDefaultParameters(const Context<T>& context,
Parameters<T>* params) const {
this->ValidateContext(context);
auto diagram_context = dynamic_cast<const DiagramContext<T>*>(&context);
DRAKE_DEMAND(diagram_context != nullptr);
int numeric_parameter_offset = 0;
int abstract_parameter_offset = 0;
// Set default parameters of each constituent system.
for (SubsystemIndex i(0); i < num_subsystems(); ++i) {
auto& subcontext = diagram_context->GetSubsystemContext(i);
if (!subcontext.num_numeric_parameter_groups() &&
!subcontext.num_abstract_parameters()) {
// Then there is no work to do for this subcontext.
continue;
}
// Make a new Parameters<T> structure with pointers to the mutable
// subsystem parameter values. This does not make a copy of the
// underlying data.
// TODO(russt): Consider implementing a DiagramParameters, analogous to
// DiagramState, to avoid these dynamic allocations if they prove
// expensive.
std::vector<BasicVector<T>*> numeric_params;
for (int j = 0; j < subcontext.num_numeric_parameter_groups(); ++j) {
numeric_params.push_back(¶ms->get_mutable_numeric_parameter(
numeric_parameter_offset + j));
}
numeric_parameter_offset += subcontext.num_numeric_parameter_groups();
std::vector<AbstractValue*> abstract_params;
for (int j = 0; j < subcontext.num_abstract_parameters(); ++j) {
abstract_params.push_back(¶ms->get_mutable_abstract_parameter(
abstract_parameter_offset + j));
}
abstract_parameter_offset += subcontext.num_abstract_parameters();
Parameters<T> subparameters;
subparameters.set_numeric_parameters(
std::make_unique<DiscreteValues<T>>(numeric_params));
subparameters.set_abstract_parameters(
std::make_unique<AbstractValues>(abstract_params));
registered_systems_[i]->SetDefaultParameters(subcontext, &subparameters);
}
}
template <typename T>
void Diagram<T>::SetRandomState(const Context<T>& context, State<T>* state,
RandomGenerator* generator) const {
this->ValidateContext(context);
auto diagram_context = dynamic_cast<const DiagramContext<T>*>(&context);
DRAKE_DEMAND(diagram_context != nullptr);
auto diagram_state = dynamic_cast<DiagramState<T>*>(state);
DRAKE_DEMAND(diagram_state != nullptr);
// Set state of each constituent system.
for (SubsystemIndex i(0); i < num_subsystems(); ++i) {
auto& subcontext = diagram_context->GetSubsystemContext(i);
auto& substate = diagram_state->get_mutable_substate(i);
registered_systems_[i]->SetRandomState(subcontext, &substate, generator);
}
}
template <typename T>
void Diagram<T>::SetRandomParameters(const Context<T>& context,
Parameters<T>* params,
RandomGenerator* generator) const {
this->ValidateContext(context);
auto diagram_context = dynamic_cast<const DiagramContext<T>*>(&context);
DRAKE_DEMAND(diagram_context != nullptr);
int numeric_parameter_offset = 0;
int abstract_parameter_offset = 0;
// Set parameters of each constituent system.
for (SubsystemIndex i(0); i < num_subsystems(); ++i) {
auto& subcontext = diagram_context->GetSubsystemContext(i);
if (!subcontext.num_numeric_parameter_groups() &&
!subcontext.num_abstract_parameters()) {
// Then there is no work to do for this subcontext.
continue;
}
// Make a new Parameters<T> structure with pointers to the mutable
// subsystem parameter values. This does not make a copy of the
// underlying data.
// TODO(russt): This code is duplicated from SetDefaultParameters.
// Consider extracting it to a helper method (waiting for the rule of
// three).
std::vector<BasicVector<T>*> numeric_params;
std::vector<AbstractValue*> abstract_params;
for (int j = 0; j < subcontext.num_numeric_parameter_groups(); ++j) {
numeric_params.push_back(¶ms->get_mutable_numeric_parameter(
numeric_parameter_offset + j));
}
numeric_parameter_offset += subcontext.num_numeric_parameter_groups();
for (int j = 0; j < subcontext.num_abstract_parameters(); ++j) {
abstract_params.push_back(¶ms->get_mutable_abstract_parameter(
abstract_parameter_offset + j));
}
abstract_parameter_offset += subcontext.num_abstract_parameters();
Parameters<T> subparameters;
subparameters.set_numeric_parameters(
std::make_unique<DiscreteValues<T>>(numeric_params));
subparameters.set_abstract_parameters(
std::make_unique<AbstractValues>(abstract_params));
registered_systems_[i]->SetRandomParameters(subcontext, &subparameters,
generator);
}
}
template <typename T>
std::unique_ptr<EventCollection<PublishEvent<T>>>
Diagram<T>::AllocateForcedPublishEventCollection() const {
return AllocateForcedEventCollection<PublishEvent<T>>(
&System<T>::AllocateForcedPublishEventCollection);
}
template <typename T>
std::unique_ptr<EventCollection<DiscreteUpdateEvent<T>>>
Diagram<T>::AllocateForcedDiscreteUpdateEventCollection() const {
return AllocateForcedEventCollection<DiscreteUpdateEvent<T>>(
&System<T>::AllocateForcedDiscreteUpdateEventCollection);
}
template <typename T>
std::unique_ptr<EventCollection<UnrestrictedUpdateEvent<T>>>
Diagram<T>::AllocateForcedUnrestrictedUpdateEventCollection() const {
return AllocateForcedEventCollection<UnrestrictedUpdateEvent<T>>(
&System<T>::AllocateForcedUnrestrictedUpdateEventCollection);
}
template <typename T>
std::unique_ptr<ContinuousState<T>> Diagram<T>::AllocateTimeDerivatives()
const {
std::vector<std::unique_ptr<ContinuousState<T>>> sub_derivatives;
for (const auto& system : registered_systems_) {
sub_derivatives.push_back(system->AllocateTimeDerivatives());
}
auto result = std::make_unique<DiagramContinuousState<T>>(
std::move(sub_derivatives));
result->set_system_id(this->get_system_id());
return result;
}
template <typename T>
std::unique_ptr<DiscreteValues<T>> Diagram<T>::AllocateDiscreteVariables()
const {
std::vector<std::unique_ptr<DiscreteValues<T>>> sub_discretes;
for (const auto& system : registered_systems_) {
sub_discretes.push_back(system->AllocateDiscreteVariables());
}
return std::make_unique<DiagramDiscreteValues<T>>(std::move(sub_discretes));
}
template <typename T>
void Diagram<T>::DoCalcTimeDerivatives(const Context<T>& context,
ContinuousState<T>* derivatives) const {
auto diagram_context = dynamic_cast<const DiagramContext<T>*>(&context);
DRAKE_DEMAND(diagram_context != nullptr);
auto diagram_derivatives =
dynamic_cast<DiagramContinuousState<T>*>(derivatives);
DRAKE_DEMAND(diagram_derivatives != nullptr);
const int n = diagram_derivatives->num_substates();
DRAKE_DEMAND(num_subsystems() == n);
// Evaluate the derivatives of each constituent system.
for (SubsystemIndex i(0); i < n; ++i) {
const Context<T>& subcontext = diagram_context->GetSubsystemContext(i);
ContinuousState<T>& subderivatives =
diagram_derivatives->get_mutable_substate(i);
registered_systems_[i]->CalcTimeDerivatives(subcontext, &subderivatives);
}
}
template <typename T>
void Diagram<T>::DoCalcImplicitTimeDerivativesResidual(
const Context<T>& context, const ContinuousState<T>& proposed_derivatives,
EigenPtr<VectorX<T>> residual) const {
// Check that the arguments are at least structurally compatible with
// this Diagram.
auto diagram_context = dynamic_cast<const DiagramContext<T>*>(&context);
DRAKE_DEMAND(diagram_context != nullptr);
const auto* diagram_derivatives =
dynamic_cast<const DiagramContinuousState<T>*>(&proposed_derivatives);
DRAKE_DEMAND(diagram_derivatives != nullptr);
const int n = diagram_derivatives->num_substates();
DRAKE_DEMAND(num_subsystems() == n);
// The public method has already verified that the output vector is the right
// length.
// Evaluate the residuals from each constituent system.
int next = 0; // Next available slot in residual vector.
for (SubsystemIndex i(0); i < n; ++i) {
const Context<T>& subcontext = diagram_context->GetSubsystemContext(i);
const ContinuousState<T>& subderivatives =
diagram_derivatives->get_substate(i);
const System<T>& subsystem = *registered_systems_[i];
const int num_sub_residuals =
subsystem.implicit_time_derivatives_residual_size();
// The "const" here is for the returned object; the data to which it
// refers is still mutable because residual is.
const auto segment = residual->segment(next, num_sub_residuals);
subsystem.CalcImplicitTimeDerivativesResidual(subcontext, subderivatives,
&segment);
next += num_sub_residuals;
}
// Make sure we wrote to every element.
DRAKE_DEMAND(next == residual->size());
}
template <typename T>
const System<T>& Diagram<T>::GetSubsystemByName(const std::string& name) const {
for (const auto& child : registered_systems_) {
if (child->get_name() == name) {
return *child;
}
}
throw std::logic_error("System " + this->GetSystemName() +
" does not have a subsystem named " + name);
}
template <typename T>
const ContinuousState<T>& Diagram<T>::GetSubsystemDerivatives(
const System<T>& subsystem,
const ContinuousState<T>& derivatives) const {
auto diagram_derivatives =
dynamic_cast<const DiagramContinuousState<T>*>(&derivatives);
DRAKE_DEMAND(diagram_derivatives != nullptr);
const SubsystemIndex i = GetSystemIndexOrAbort(&subsystem);
return diagram_derivatives->get_substate(i);
}
template <typename T>
const DiscreteValues<T>& Diagram<T>::GetSubsystemDiscreteValues(
const System<T>& subsystem,
const DiscreteValues<T>& discrete_values) const {
auto diagram_discrete_state =
dynamic_cast<const DiagramDiscreteValues<T>*>(&discrete_values);
DRAKE_DEMAND(diagram_discrete_state != nullptr);
const SubsystemIndex i = GetSystemIndexOrAbort(&subsystem);
return diagram_discrete_state->get_subdiscrete(i);
}
template <typename T>
const CompositeEventCollection<T>&
Diagram<T>::GetSubsystemCompositeEventCollection(const System<T>& subsystem,
const CompositeEventCollection<T>& events) const {
auto ret = DoGetTargetSystemCompositeEventCollection(subsystem, &events);
DRAKE_DEMAND(ret != nullptr);
return *ret;
}
template <typename T>
CompositeEventCollection<T>&
Diagram<T>::GetMutableSubsystemCompositeEventCollection(
const System<T>& subsystem, CompositeEventCollection<T>* events) const {
auto ret = DoGetMutableTargetSystemCompositeEventCollection(
subsystem, events);
DRAKE_DEMAND(ret != nullptr);
return *ret;
}
template <typename T>
State<T>& Diagram<T>::GetMutableSubsystemState(const System<T>& subsystem,
Context<T>* context) const {
this->ValidateContext(context);
Context<T>& subcontext = GetMutableSubsystemContext(subsystem, context);
return subcontext.get_mutable_state();
}
template <typename T>
State<T>& Diagram<T>::GetMutableSubsystemState(const System<T>& subsystem,
State<T>* state) const {
auto ret = DoGetMutableTargetSystemState(subsystem, state);
DRAKE_DEMAND(ret != nullptr);
return *ret;
}
template <typename T>
const State<T>& Diagram<T>::GetSubsystemState(const System<T>& subsystem,
const State<T>& state) const {
auto ret = DoGetTargetSystemState(subsystem, &state);
DRAKE_DEMAND(ret != nullptr);
return *ret;
}
template <typename T>
void Diagram<T>::GetGraphvizFragment(int max_depth,
std::stringstream* dot) const {
const int64_t id = this->GetGraphvizId();
std::string name = this->get_name();
if (name.empty()) name = std::to_string(id);
if (max_depth == 0) {
// Open the attributes and label.
*dot << id << " [shape=record, label=\"" << name << "|{";
// Append input ports to the label.
*dot << "{";
for (int i = 0; i < this->num_input_ports(); ++i) {
if (i != 0) *dot << "|";
*dot << "<u" << i << ">" << this->get_input_port(i).get_name();
}
*dot << "}";
// Append output ports to the label.
*dot << " | {";
for (int i = 0; i < this->num_output_ports(); ++i) {
if (i != 0) *dot << "|";
*dot << "<y" << i << ">" << this->get_output_port(i).get_name();
}
*dot << "}";
// Close the label and attributes.
*dot << "}\"];" << std::endl;
return;
}
// Open the Diagram.
*dot << "subgraph cluster" << id << "diagram" " {" << std::endl;
*dot << "color=black" << std::endl;
*dot << "concentrate=true" << std::endl;
*dot << "label=\"" << name << "\";" << std::endl;
// Add a cluster for the input port nodes.
*dot << "subgraph cluster" << id << "inputports" << " {" << std::endl;
*dot << "rank=same" << std::endl;
*dot << "color=lightgrey" << std::endl;
*dot << "style=filled" << std::endl;
*dot << "label=\"input ports\"" << std::endl;
for (int i = 0; i < this->num_input_ports(); ++i) {
this->GetGraphvizInputPortToken(this->get_input_port(i), max_depth,
dot);
*dot << "[color=blue, label=\"" << this->get_input_port(i).get_name()
<< "\"];" << std::endl;
}
*dot << "}" << std::endl;
// Add a cluster for the output port nodes.
*dot << "subgraph cluster" << id << "outputports" << " {" << std::endl;
*dot << "rank=same" << std::endl;
*dot << "color=lightgrey" << std::endl;
*dot << "style=filled" << std::endl;
*dot << "label=\"output ports\"" << std::endl;
for (int i = 0; i < this->num_output_ports(); ++i) {
this->GetGraphvizOutputPortToken(this->get_output_port(i), max_depth,
dot);
*dot << "[color=green, label=\"" << this->get_output_port(i).get_name()
<< "\"];" << std::endl;
}
*dot << "}" << std::endl;
// Add a cluster for the subsystems.
*dot << "subgraph cluster" << id << "subsystems" << " {" << std::endl;
*dot << "color=white" << std::endl;
*dot << "label=\"\"" << std::endl;
// -- Add the subsystems themselves.
for (const auto& subsystem : registered_systems_) {
subsystem->GetGraphvizFragment(max_depth - 1, dot);
}
// -- Add the connections as edges.
for (const auto& edge : connection_map_) {
const OutputPortLocator& src = edge.second;
const System<T>* src_sys = src.first;
const InputPortLocator& dest = edge.first;
const System<T>* dest_sys = dest.first;
src_sys->GetGraphvizOutputPortToken(src_sys->get_output_port(src.second),
max_depth - 1, dot);
*dot << " -> ";
dest_sys->GetGraphvizInputPortToken(dest_sys->get_input_port(dest.second),
max_depth - 1, dot);
*dot << ";" << std::endl;
}
// -- Add edges from the input and output port nodes to the subsystems that
// actually service that port. These edges are highlighted in blue
// (input) and green (output), matching the port nodes.
for (int i = 0; i < this->num_input_ports(); ++i) {
for (const auto& port_id : GetInputPortLocators(InputPortIndex(i))) {
this->GetGraphvizInputPortToken(this->get_input_port(i), max_depth,
dot);
*dot << " -> ";
port_id.first->GetGraphvizInputPortToken(
port_id.first->get_input_port(port_id.second), max_depth - 1, dot);
*dot << " [color=blue];" << std::endl;
}
}
for (int i = 0; i < this->num_output_ports(); ++i) {
const auto& port_id = output_port_ids_[i];
port_id.first->GetGraphvizOutputPortToken(
port_id.first->get_output_port(port_id.second), max_depth - 1, dot);
*dot << " -> ";
this->GetGraphvizOutputPortToken(this->get_output_port(i),
max_depth, dot);
*dot << " [color=green];" << std::endl;
}
*dot << "}" << std::endl;
// Close the diagram.
*dot << "}" << std::endl;
}
template <typename T>
void Diagram<T>::GetGraphvizInputPortToken(const InputPort<T>& port,
int max_depth,
std::stringstream* dot) const {
DRAKE_DEMAND(&port.get_system() == this);
// Note: ports are rendered in a fundamentally different way depending on
// max_depth.
if (max_depth > 0) {
// Ports are rendered as nodes in the "input ports" subgraph.
*dot << "_" << this->GetGraphvizId() << "_u" << port.get_index();
} else {
// Ports are rendered as a part of the system label.
*dot << this->GetGraphvizId() << ":u" << port.get_index();
}
}
template <typename T>
void Diagram<T>::GetGraphvizOutputPortToken(const OutputPort<T>& port,
int max_depth,
std::stringstream* dot) const {
DRAKE_DEMAND(&port.get_system() == this);
// Note: ports are rendered in a fundamentally different way depending on
// max_depth.
if (max_depth > 0) {
// Ports are rendered as nodes in the "input ports" subgraph.
*dot << "_" << this->GetGraphvizId() << "_y" << port.get_index();
} else {
// Ports are rendered as a part of the system label.
*dot << this->GetGraphvizId() << ":y" << port.get_index();
}
}
template <typename T>
SubsystemIndex Diagram<T>::GetSystemIndexOrAbort(const System<T>* sys) const {
auto it = system_index_map_.find(sys);
DRAKE_DEMAND(it != system_index_map_.end());
return it->second;
}
template <typename T>
bool Diagram<T>::AreConnected(const OutputPort<T>& output,
const InputPort<T>& input) const {
InputPortLocator in{&input.get_system(), input.get_index()};
OutputPortLocator out{&output.get_system(), output.get_index()};
const auto range = connection_map_.equal_range(in);
for (auto iter = range.first; iter != range.second; ++iter) {
if (iter->second == out) return true;
}
return false;
}
template <typename T>
Diagram<T>::Diagram() : System<T>(
SystemScalarConverter(
SystemTypeTag<Diagram>{},
SystemScalarConverter::GuaranteedSubtypePreservation::kDisabled)) {}
template <typename T>
Diagram<T>::Diagram(SystemScalarConverter converter)
: System<T>(std::move(converter)) {}
template <typename T>
T Diagram<T>::DoCalcWitnessValue(const Context<T>& context,
const WitnessFunction<T>& witness_func) const {
const System<T>& system = witness_func.get_system();
const Context<T>& subcontext = GetSubsystemContext(system, context);
return witness_func.CalcWitnessValue(subcontext);
}
template <typename T>
void Diagram<T>::AddTriggeredWitnessFunctionToCompositeEventCollection(
Event<T>* event,
CompositeEventCollection<T>* events) const {
DRAKE_DEMAND(events);
DRAKE_DEMAND(event);
DRAKE_DEMAND(event->get_event_data());
// Get the event data- it will need to be modified.
auto data = dynamic_cast<WitnessTriggeredEventData<T>*>(
event->get_mutable_event_data());
DRAKE_DEMAND(data);
// Get the vector of events corresponding to the subsystem.
const System<T>& subsystem = data->triggered_witness()->get_system();
CompositeEventCollection<T>& subevents =
GetMutableSubsystemCompositeEventCollection(subsystem, events);
// Get the continuous states at both window endpoints.
auto diagram_xc0 = dynamic_cast<const DiagramContinuousState<T>*>(
data->xc0());
DRAKE_DEMAND(diagram_xc0 != nullptr);
auto diagram_xcf = dynamic_cast<const DiagramContinuousState<T>*>(
data->xcf());
DRAKE_DEMAND(diagram_xcf != nullptr);
// Modify the pointer to the event data to point to the sub-system
// continuous states.
data->set_xc0(DoGetTargetSystemContinuousState(subsystem, diagram_xc0));
data->set_xcf(DoGetTargetSystemContinuousState(subsystem, diagram_xcf));
// Add the event to the collection.
event->AddToComposite(&subevents);
}
template <typename T>
void Diagram<T>::DoGetWitnessFunctions(
const Context<T>& context,
std::vector<const WitnessFunction<T>*>* witnesses) const {
// A temporary vector is necessary since the vector of witnesses is
// declared to be empty on entry to DoGetWitnessFunctions().
std::vector<const WitnessFunction<T>*> temp_witnesses;
auto diagram_context = dynamic_cast<const DiagramContext<T>*>(&context);
DRAKE_DEMAND(diagram_context != nullptr);
SubsystemIndex index(0);
for (const auto& system : registered_systems_) {
DRAKE_ASSERT(index == GetSystemIndexOrAbort(system.get()));
temp_witnesses.clear();
system->GetWitnessFunctions(diagram_context->GetSubsystemContext(index),
&temp_witnesses);
witnesses->insert(witnesses->end(), temp_witnesses.begin(),
temp_witnesses.end());
++index;
}
}
template <typename T>
const Context<T>* Diagram<T>::DoGetTargetSystemContext(
const System<T>& target_system, const Context<T>* context) const {
if (&target_system == this)
return context;
return GetSubsystemStuff<const Context<T>, const DiagramContext<T>>(
target_system, context,
&System<T>::DoGetTargetSystemContext,
&DiagramContext<T>::GetSubsystemContext);
}
template <typename T>
State<T>* Diagram<T>::DoGetMutableTargetSystemState(
const System<T>& target_system, State<T>* state) const {
if (&target_system == this)
return state;
return GetSubsystemStuff<State<T>, DiagramState<T>>(
target_system, state,
&System<T>::DoGetMutableTargetSystemState,
&DiagramState<T>::get_mutable_substate);
}
template <typename T>
const ContinuousState<T>* Diagram<T>::DoGetTargetSystemContinuousState(
const System<T>& target_system,
const ContinuousState<T>* xc) const {
if (&target_system == this)
return xc;
return GetSubsystemStuff<const ContinuousState<T>,
const DiagramContinuousState<T>>(
target_system, xc,
&System<T>::DoGetTargetSystemContinuousState,
&DiagramContinuousState<T>::get_substate);
}
template <typename T>
const State<T>* Diagram<T>::DoGetTargetSystemState(
const System<T>& target_system, const State<T>* state) const {
if (&target_system == this)
return state;
return GetSubsystemStuff<const State<T>, const DiagramState<T>>(
target_system, state,
&System<T>::DoGetTargetSystemState,
&DiagramState<T>::get_substate);
}
template <typename T>
CompositeEventCollection<T>*
Diagram<T>::DoGetMutableTargetSystemCompositeEventCollection(
const System<T>& target_system,
CompositeEventCollection<T>* events) const {
if (&target_system == this)
return events;
return GetSubsystemStuff<CompositeEventCollection<T>,
DiagramCompositeEventCollection<T>>(
target_system, events,
&System<T>::DoGetMutableTargetSystemCompositeEventCollection,
&DiagramCompositeEventCollection<T>::get_mutable_subevent_collection);
}
template <typename T>
const CompositeEventCollection<T>*
Diagram<T>::DoGetTargetSystemCompositeEventCollection(
const System<T>& target_system,
const CompositeEventCollection<T>* events) const {
if (&target_system == this)
return events;
return GetSubsystemStuff<const CompositeEventCollection<T>,
const DiagramCompositeEventCollection<T>>(
target_system, events,
&System<T>::DoGetTargetSystemCompositeEventCollection,
&DiagramCompositeEventCollection<T>::get_subevent_collection);
}
template <typename T>
void Diagram<T>::DoMapVelocityToQDot(
const Context<T>& context,
const Eigen::Ref<const VectorX<T>>& generalized_velocity,
VectorBase<T>* qdot) const {
// Check that the dimensions of the continuous state in the context match
// the dimensions of the provided generalized velocity and configuration
// derivatives.
const ContinuousState<T>& xc = context.get_continuous_state();
const int nq = xc.get_generalized_position().size();
const int nv = xc.get_generalized_velocity().size();
DRAKE_DEMAND(nq == qdot->size());
DRAKE_DEMAND(nv == generalized_velocity.size());
auto diagram_context = dynamic_cast<const DiagramContext<T>*>(&context);
DRAKE_DEMAND(diagram_context != nullptr);
// Iterate over the subsystems, asking each subsystem to map its subslice of
// velocity to configuration derivatives. This approach is valid because the
// DiagramContinuousState guarantees that the subsystem states are
// concatenated in order.
int v_index = 0; // The next index to read in generalized_velocity.
int q_index = 0; // The next index to write in qdot.
for (SubsystemIndex i(0); i < num_subsystems(); ++i) {
// Find the continuous state of subsystem i.
const Context<T>& subcontext = diagram_context->GetSubsystemContext(i);
const ContinuousState<T>& sub_xc = subcontext.get_continuous_state();
// Select the chunk of generalized_velocity belonging to subsystem i.
const int num_v = sub_xc.get_generalized_velocity().size();
if (num_v == 0) continue;
const Eigen::Ref<const VectorX<T>>& v_slice =
generalized_velocity.segment(v_index, num_v);
// Select the chunk of qdot belonging to subsystem i.
const int num_q = sub_xc.get_generalized_position().size();
Subvector<T> dq_slice(qdot, q_index, num_q);
// Delegate the actual mapping to subsystem i itself.
registered_systems_[i]->MapVelocityToQDot(subcontext, v_slice, &dq_slice);
// Advance the indices.
v_index += num_v;
q_index += num_q;
}
}
template <typename T>
void Diagram<T>::DoMapQDotToVelocity(
const Context<T>& context,
const Eigen::Ref<const VectorX<T>>& qdot,
VectorBase<T>* generalized_velocity) const {
// Check that the dimensions of the continuous state in the context match
// the dimensions of the provided generalized velocity and configuration
// derivatives.
const ContinuousState<T>& xc = context.get_continuous_state();
const int nq = xc.get_generalized_position().size();
const int nv = xc.get_generalized_velocity().size();
DRAKE_DEMAND(nq == qdot.size());
DRAKE_DEMAND(nv == generalized_velocity->size());
auto diagram_context = dynamic_cast<const DiagramContext<T>*>(&context);
DRAKE_DEMAND(diagram_context != nullptr);
// Iterate over the subsystems, asking each subsystem to map its subslice of
// configuration derivatives to velocity. This approach is valid because the
// DiagramContinuousState guarantees that the subsystem states are
// concatenated in order.
int q_index = 0; // The next index to read in qdot.
int v_index = 0; // The next index to write in generalized_velocity.
for (SubsystemIndex i(0); i < num_subsystems(); ++i) {
// Find the continuous state of subsystem i.
const Context<T>& subcontext = diagram_context->GetSubsystemContext(i);
const ContinuousState<T>& sub_xc = subcontext.get_continuous_state();
// Select the chunk of qdot belonging to subsystem i.
const int num_q = sub_xc.get_generalized_position().size();
if (num_q == 0) continue;
const Eigen::Ref<const VectorX<T>>& dq_slice =
qdot.segment(q_index, num_q);
// Select the chunk of generalized_velocity belonging to subsystem i.
const int num_v = sub_xc.get_generalized_velocity().size();
Subvector<T> v_slice(generalized_velocity, v_index, num_v);
// Delegate the actual mapping to subsystem i itself.
registered_systems_[i]->MapQDotToVelocity(subcontext, dq_slice, &v_slice);
// Advance the indices.
v_index += num_v;
q_index += num_q;
}
}
template <typename T>
void Diagram<T>::DoCalcNextUpdateTime(const Context<T>& context,
CompositeEventCollection<T>* event_info,
T* next_update_time) const {
auto diagram_context = dynamic_cast<const DiagramContext<T>*>(&context);
auto info = dynamic_cast<DiagramCompositeEventCollection<T>*>(event_info);
DRAKE_DEMAND(diagram_context != nullptr);
DRAKE_DEMAND(info != nullptr);
*next_update_time = std::numeric_limits<double>::infinity();
// Iterate over the subsystems, and harvest the most imminent updates.
std::vector<T> times(num_subsystems());
for (SubsystemIndex i(0); i < num_subsystems(); ++i) {
const Context<T>& subcontext = diagram_context->GetSubsystemContext(i);
CompositeEventCollection<T>& subinfo =
info->get_mutable_subevent_collection(i);
const T sub_time =
registered_systems_[i]->CalcNextUpdateTime(subcontext, &subinfo);
times[i] = sub_time;
if (sub_time < *next_update_time) {
*next_update_time = sub_time;
}
}
// For all the subsystems whose next update time is bigger than
// next_update_time, clear their event collections.
for (SubsystemIndex i(0); i < num_subsystems(); ++i) {
if (times[i] > *next_update_time)
info->get_mutable_subevent_collection(i).Clear();
}
}
template <typename T>
std::unique_ptr<AbstractValue> Diagram<T>::DoAllocateInput(
const InputPort<T>& input_port) const {
// Ask an arbitrary connected subsystem to perform the allocation.
const auto id = GetArbitraryInputPortLocator(input_port.get_index());
const System<T>* subsystem = id.first;
const InputPortIndex subindex = id.second;
return subsystem->AllocateInputAbstract(
subsystem->get_input_port(subindex));
}
template <typename T>
std::unique_ptr<ContextBase> Diagram<T>::DoAllocateContext() const {
// Reserve inputs as specified during Diagram initialization.
auto context = std::make_unique<DiagramContext<T>>(num_subsystems());
this->InitializeContextBase(&*context);
// Recursively construct each constituent system and its subsystems,
// then add to this diagram Context.
for (SubsystemIndex i(0); i < num_subsystems(); ++i) {
const System<T>& system = *registered_systems_[i];
auto subcontext = dynamic_pointer_cast_or_throw<Context<T>>(
system.AllocateContext());
context->AddSystem(i, std::move(subcontext));
}
// Creates this diagram's composite data structures that collect its
// subsystems' resources, which must have already been allocated above.
// No dependencies are set up in these two calls.
context->MakeParameters();
context->MakeState();
// Subscribe each of the Diagram's composite-entity dependency trackers to
// the trackers for the corresponding constituent entities in the child
// subsystems. This ensures that changes made at the subcontext level are
// propagated correctly to the diagram context level. That includes state
// and parameter changes, as well as local changes that affect composite
// diagram-level computations like xcdot and pe.
context->SubscribeDiagramCompositeTrackersToChildrens();
// Peer-to-peer connections wire a child subsystem's input port to a
// child subsystem's output port. Subscribe each child input port to the
// child output port on which it depends.
for (const auto& connection : connection_map_) {
const OutputPortLocator& src = connection.second;
const InputPortLocator& dest = connection.first;
context->SubscribeInputPortToOutputPort(
ConvertToContextPortIdentifier(src),
ConvertToContextPortIdentifier(dest));
}
// Diagram-external input ports are exported from child subsystems (meaning
// the Diagram input is fed into the input of one of its children.
// Subscribe the child subsystem's input port to its parent Diagram's input
// port on which it depends.
for (InputPortIndex i(0); i < this->num_input_ports(); ++i) {
for (const auto& id : GetInputPortLocators(i)) {
context->SubscribeExportedInputPortToDiagramPort(
i, ConvertToContextPortIdentifier(id));
}
}
// Diagram-external output ports are exported from child subsystem output
// ports. Subscribe each Diagram-level output to the child-level output on
// which it depends.
for (OutputPortIndex i(0); i < this->num_output_ports(); ++i) {
const OutputPortLocator& id = output_port_ids_[i];
context->SubscribeDiagramPortToExportedOutputPort(
i, ConvertToContextPortIdentifier(id));
}
return context;
}
template <typename T>
const AbstractValue* Diagram<T>::EvalConnectedSubsystemInputPort(
const ContextBase& context_base,
const InputPortBase& input_port_base) const {
auto& diagram_context =
dynamic_cast<const DiagramContext<T>&>(context_base);
auto& system =
dynamic_cast<const System<T>&>(input_port_base.get_system_interface());
const InputPortLocator id{&system, input_port_base.get_index()};
// Find if this input port is exported (connected to an input port of this
// containing diagram).
const auto external_it = input_port_map_.find(id);
const bool is_exported = (external_it != input_port_map_.end());
// Find if this input port is connected to an output port.
// TODO(sherm1) Fix this. Shouldn't have to search.
const auto upstream_it = connection_map_.find(id);
const bool is_connected = (upstream_it != connection_map_.end());
if (!(is_exported || is_connected))
return nullptr;
DRAKE_DEMAND(is_exported ^ is_connected);
if (is_exported) {
// The upstream source is an input to this whole Diagram; evaluate that
// input port and use the result as the value for this one.
const InputPortIndex i = external_it->second;
return this->EvalAbstractInput(diagram_context, i);
}
// The upstream source is an output port of one of this Diagram's child
// subsystems; evaluate it.
// TODO(david-german-tri): Add online algebraic loop detection here.
DRAKE_ASSERT(is_connected);
const OutputPortLocator& prerequisite = upstream_it->second;
return &this->EvalSubsystemOutputPort(diagram_context, prerequisite);
}
template <typename T>
std::string Diagram<T>::GetParentPathname() const {
return this->GetSystemPathname();
}
template <typename T>
const SystemBase& Diagram<T>::GetRootSystemBase() const {