-
Notifications
You must be signed in to change notification settings - Fork 1.2k
/
leaf_system.cc
1180 lines (1046 loc) · 45.1 KB
/
leaf_system.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/leaf_system.h"
#include <cmath>
#include <limits>
#include "absl/container/inlined_vector.h"
#include "drake/common/drake_deprecated.h"
#include "drake/common/pointer_cast.h"
#include "drake/systems/framework/system_symbolic_inspector.h"
#include "drake/systems/framework/value_checker.h"
namespace drake {
namespace systems {
namespace {
// Returns the next sample time for the given @p attribute.
template <typename T>
T GetNextSampleTime(
const PeriodicEventData& attribute,
const T& current_time_sec) {
const double period = attribute.period_sec();
DRAKE_ASSERT(period > 0);
const double offset = attribute.offset_sec();
DRAKE_ASSERT(offset >= 0);
// If the first sample time hasn't arrived yet, then that is the next
// sample time.
if (current_time_sec < offset) {
return offset;
}
// Compute the index in the sequence of samples for the next time to sample,
// which should be greater than the present time.
using std::ceil;
const T offset_time = current_time_sec - offset;
const T next_k = ceil(offset_time / period);
T next_t = offset + next_k * period;
if (next_t <= current_time_sec) {
next_t = offset + (next_k + 1) * period;
}
DRAKE_ASSERT(next_t > current_time_sec);
return next_t;
}
} // namespace
template <typename T>
LeafSystem<T>::~LeafSystem() {}
template <typename T>
std::unique_ptr<CompositeEventCollection<T>>
LeafSystem<T>::DoAllocateCompositeEventCollection() const {
return std::make_unique<LeafCompositeEventCollection<T>>();
}
template <typename T>
std::unique_ptr<LeafContext<T>> LeafSystem<T>::AllocateContext() const {
return dynamic_pointer_cast_or_throw<LeafContext<T>>(
System<T>::AllocateContext());
}
template <typename T>
std::unique_ptr<EventCollection<PublishEvent<T>>>
LeafSystem<T>::AllocateForcedPublishEventCollection() const {
auto collection =
LeafEventCollection<PublishEvent<T>>::MakeForcedEventCollection();
if (this->forced_publish_events_exist())
collection->SetFrom(this->get_forced_publish_events());
return collection;
}
template <typename T>
std::unique_ptr<EventCollection<DiscreteUpdateEvent<T>>>
LeafSystem<T>::AllocateForcedDiscreteUpdateEventCollection() const {
auto collection =
LeafEventCollection<
DiscreteUpdateEvent<T>>::MakeForcedEventCollection();
if (this->forced_discrete_update_events_exist())
collection->SetFrom(this->get_forced_discrete_update_events());
return collection;
}
template <typename T>
std::unique_ptr<EventCollection<UnrestrictedUpdateEvent<T>>>
LeafSystem<T>::AllocateForcedUnrestrictedUpdateEventCollection() const {
auto collection =
LeafEventCollection<
UnrestrictedUpdateEvent<T>>::MakeForcedEventCollection();
if (this->forced_unrestricted_update_events_exist())
collection->SetFrom(this->get_forced_unrestricted_update_events());
return collection;
}
template <typename T>
std::unique_ptr<ContextBase> LeafSystem<T>::DoAllocateContext() const {
std::unique_ptr<LeafContext<T>> context = DoMakeLeafContext();
this->InitializeContextBase(&*context);
// Reserve parameters via delegation to subclass.
context->init_parameters(this->AllocateParameters());
// Reserve state via delegation to subclass.
context->init_continuous_state(this->AllocateContinuousState());
context->init_discrete_state(this->AllocateDiscreteState());
context->init_abstract_state(this->AllocateAbstractState());
// At this point this LeafContext is complete except possibly for
// inter-Context dependencies involving port connections to peers or
// parent. We can now perform some final sanity checks.
// The numeric vectors used for parameters and state must be contiguous,
// i.e., valid BasicVectors. In general, a Context's numeric vectors can be
// any kind of VectorBase including scatter-gather implementations like
// Supervector. But for a LeafContext, we only allow BasicVectors, which are
// guaranteed to have a contiguous storage layout.
// If xc is not BasicVector, the dynamic_cast will yield nullptr, and the
// invariant-checker will complain.
const VectorBase<T>* const xc = &context->get_continuous_state_vector();
internal::CheckBasicVectorInvariants(
dynamic_cast<const BasicVector<T>*>(xc));
// The discrete state must all be valid BasicVectors.
for (const BasicVector<T>* group :
context->get_state().get_discrete_state().get_data()) {
internal::CheckBasicVectorInvariants(group);
}
// The numeric parameters must all be valid BasicVectors.
const int num_numeric_parameters =
context->num_numeric_parameter_groups();
for (int i = 0; i < num_numeric_parameters; ++i) {
const BasicVector<T>& group = context->get_numeric_parameter(i);
internal::CheckBasicVectorInvariants(&group);
}
// Allow derived LeafSystem to validate allocated Context.
DoValidateAllocatedLeafContext(*context);
return context;
}
template <typename T>
void LeafSystem<T>::SetDefaultState(
const Context<T>& context, State<T>* state) const {
this->ValidateContext(context);
DRAKE_DEMAND(state != nullptr);
this->ValidateCreatedForThisSystem(state);
ContinuousState<T>& xc = state->get_mutable_continuous_state();
xc.SetFromVector(model_continuous_state_vector_->get_value());
DiscreteValues<T>& xd = state->get_mutable_discrete_state();
// Check that _if_ we have models, there is one for each group.
DRAKE_DEMAND(model_discrete_state_.num_groups() == 0 ||
model_discrete_state_.num_groups() == xd.num_groups());
if (model_discrete_state_.num_groups() > 0) {
xd.SetFrom(model_discrete_state_);
} else {
// With no model vector, we just zero all the discrete variables.
for (int i = 0; i < xd.num_groups(); i++) {
BasicVector<T>& s = xd.get_mutable_vector(i);
s.SetFromVector(VectorX<T>::Zero(s.size()));
}
}
AbstractValues& xa = state->get_mutable_abstract_state();
xa.SetFrom(AbstractValues(model_abstract_states_.CloneAllModels()));
}
template <typename T>
void LeafSystem<T>::SetDefaultParameters(
const Context<T>& context, Parameters<T>* parameters) const {
this->ValidateContext(context);
this->ValidateCreatedForThisSystem(parameters);
for (int i = 0; i < parameters->num_numeric_parameter_groups(); i++) {
BasicVector<T>& p = parameters->get_mutable_numeric_parameter(i);
auto model_vector = model_numeric_parameters_.CloneVectorModel<T>(i);
if (model_vector != nullptr) {
p.SetFrom(*model_vector);
} else {
p.SetFromVector(VectorX<T>::Constant(p.size(), 1.0));
}
}
for (int i = 0; i < parameters->num_abstract_parameters(); i++) {
AbstractValue& p = parameters->get_mutable_abstract_parameter(i);
auto model_value = model_abstract_parameters_.CloneModel(i);
p.SetFrom(*model_value);
}
}
template <typename T>
std::unique_ptr<ContinuousState<T>> LeafSystem<T>::AllocateTimeDerivatives()
const {
return AllocateContinuousState();
}
template <typename T>
std::unique_ptr<DiscreteValues<T>> LeafSystem<T>::AllocateDiscreteVariables()
const {
return AllocateDiscreteState();
}
namespace {
template <typename T>
std::unique_ptr<SystemSymbolicInspector> MakeSystemSymbolicInspector(
const System<T>& system) {
using symbolic::Expression;
// We use different implementations when T = Expression or not.
if constexpr (std::is_same_v<T, Expression>) {
return std::make_unique<SystemSymbolicInspector>(system);
} else {
std::unique_ptr<System<Expression>> converted = system.ToSymbolicMaybe();
if (converted) {
return std::make_unique<SystemSymbolicInspector>(*converted);
} else {
return nullptr;
}
}
}
} // namespace
template <typename T>
std::multimap<int, int> LeafSystem<T>::GetDirectFeedthroughs() const {
// The input -> output feedthrough result we'll return to the user.
std::multimap<int, int> feedthrough;
// The set of pairs for which we don't know an answer yet; currently all.
std::set<std::pair<InputPortIndex, OutputPortIndex>> unknown;
for (InputPortIndex u{0}; u < this->num_input_ports(); ++u) {
for (OutputPortIndex v{0}; v < this->num_output_ports(); ++v) {
unknown.emplace(std::make_pair(u, v));
}
}
// A System with no input ports or no output ports has no feedthrough!
if (unknown.empty())
return feedthrough; // Also empty.
// A helper function that removes an item from `unknown`.
const auto remove_unknown = [&unknown](const auto& in_out_pair) {
const auto num_erased = unknown.erase(in_out_pair);
DRAKE_DEMAND(num_erased == 1);
};
// A helper function that adds this in/out pair to the feedthrough result.
const auto add_to_feedthrough = [&feedthrough](const auto& in_out_pair) {
feedthrough.emplace(in_out_pair.first, in_out_pair.second);
};
// Ask the dependency graph if it can provide definitive information about
// the input/output pairs. If so remove those pairs from the `unknown` set.
auto context = this->AllocateContext();
const auto orig_unknown = unknown;
for (const auto& input_output : orig_unknown) {
// Get the CacheEntry associated with the output port in this pair.
const OutputPortBase& output = this->GetOutputPortBaseOrThrow(
__func__, input_output.second, /* warn_deprecated = */ false);
DRAKE_ASSERT(typeid(output) == typeid(LeafOutputPort<T>));
const auto& leaf_output = static_cast<const LeafOutputPort<T>&>(output);
const auto& cache_entry = leaf_output.cache_entry();
// If the user left the output prerequisites unspecified, then the cache
// entry tells us nothing useful about feedthrough for this pair.
if (cache_entry.has_default_prerequisites())
continue; // Leave this one "unknown".
// Probe the dependency path and believe the result.
const InputPortBase& input = this->GetInputPortBaseOrThrow(
__func__, input_output.first, /* warn_deprecated = */ false);
const auto& input_tracker = context->get_tracker(input.ticket());
auto& value = cache_entry.get_mutable_cache_entry_value(*context);
value.mark_up_to_date();
const int64_t change_event = context->start_new_change_event();
input_tracker.NoteValueChange(change_event);
if (value.is_out_of_date())
add_to_feedthrough(input_output);
// Regardless of the result we have all we need to know now.
remove_unknown(input_output);
// Undo the mark_up_to_date() we just did a few lines up. It shouldn't
// matter at all on this throwaway context, but perhaps it's best not
// to leave garbage values marked valid for longer than required.
value.mark_out_of_date();
}
// If the dependency graph resolved all pairs, no need for symbolic analysis.
if (unknown.empty())
return feedthrough;
// Otherwise, see if we can get a symbolic inspector to analyze them.
// If not, we have to assume they are feedthrough.
auto inspector = MakeSystemSymbolicInspector(*this);
for (const auto& input_output : unknown) {
if (!inspector || inspector->IsConnectedInputToOutput(
input_output.first, input_output.second)) {
add_to_feedthrough(input_output);
}
// No need to clean up the `unknown` set here.
}
return feedthrough;
}
template <typename T>
LeafSystem<T>::LeafSystem() : LeafSystem(SystemScalarConverter{}) {}
template <typename T>
LeafSystem<T>::LeafSystem(SystemScalarConverter converter)
: System<T>(std::move(converter)) {
this->set_forced_publish_events(
AllocateForcedPublishEventCollection());
this->set_forced_discrete_update_events(
AllocateForcedDiscreteUpdateEventCollection());
this->set_forced_unrestricted_update_events(
AllocateForcedUnrestrictedUpdateEventCollection());
per_step_events_.set_system_id(this->get_system_id());
initialization_events_.set_system_id(this->get_system_id());
model_discrete_state_.set_system_id(this->get_system_id());
}
template <typename T>
std::unique_ptr<LeafContext<T>> LeafSystem<T>::DoMakeLeafContext() const {
return std::make_unique<LeafContext<T>>();
}
template <typename T>
T LeafSystem<T>::DoCalcWitnessValue(
const Context<T>& context, const WitnessFunction<T>& witness_func) const {
DRAKE_DEMAND(this == &witness_func.get_system());
return witness_func.CalcWitnessValue(context);
}
template <typename T>
void LeafSystem<T>::AddTriggeredWitnessFunctionToCompositeEventCollection(
Event<T>* event, CompositeEventCollection<T>* events) const {
DRAKE_DEMAND(event != nullptr);
DRAKE_DEMAND(event->template has_event_data<WitnessTriggeredEventData<T>>());
DRAKE_DEMAND(events != nullptr);
event->AddToComposite(events);
}
template <typename T>
void LeafSystem<T>::DoCalcNextUpdateTime(
const Context<T>& context,
CompositeEventCollection<T>* events, T* time) const {
T min_time = std::numeric_limits<double>::infinity();
if (!periodic_events_.HasEvents()) {
*time = min_time;
return;
}
// Calculate which events to fire. Use an InlinedVector so that small-ish
// numbers of events can be processed without heap allocations. Our threshold
// for "small" is the same amount that would cause an EventCollection to
// grow beyond its pre-allocated size.
using NextEventsVector = absl::InlinedVector<
const Event<T>*, LeafEventCollection<PublishEvent<T>>::kDefaultCapacity>;
NextEventsVector next_events;
// Find the minimum next sample time across all declared periodic events,
// and store the set of declared events that will occur at that time.
// There are three lists to run through in a CompositeEventCollection.
// We give absl hidden visibility in Drake so can't capture the absl vector
// (otherwise we suffer a warning). Works as a parameter though.
auto scan_events = [&context, &min_time](const auto& typed_events,
NextEventsVector* event_list) {
for (const auto* event : typed_events.get_events()) {
const PeriodicEventData* event_data =
event->template get_event_data<PeriodicEventData>();
DRAKE_DEMAND(event_data != nullptr);
const T t = GetNextSampleTime(*event_data, context.get_time());
if (t < min_time) {
min_time = t;
*event_list = {event};
} else if (t == min_time) {
event_list->push_back(event);
}
}
};
scan_events(periodic_events_.get_publish_events(), &next_events);
scan_events(periodic_events_.get_discrete_update_events(), &next_events);
scan_events(periodic_events_.get_unrestricted_update_events(), &next_events);
// Write out the events that fire at min_time.
*time = min_time;
for (const Event<T>* event : next_events) {
event->AddToComposite(events);
}
}
#pragma GCC diagnostic push
#pragma GCC diagnostic ignored "-Wdeprecated-declarations"
template <typename T>
void LeafSystem<T>::GetGraphvizInputPortToken(
const InputPort<T>& port, int max_depth, std::stringstream* dot) const {
unused(max_depth);
DRAKE_DEMAND(&port.get_system() == this);
// N.B. Calling GetGraphvizId() will print the deprecation console warning.
*dot << this->GetGraphvizId() << ":u" << port.get_index();
}
#pragma GCC diagnostic pop
#pragma GCC diagnostic push
#pragma GCC diagnostic ignored "-Wdeprecated-declarations"
template <typename T>
void LeafSystem<T>::GetGraphvizOutputPortToken(
const OutputPort<T>& port, int max_depth, std::stringstream* dot) const {
unused(max_depth);
DRAKE_DEMAND(&port.get_system() == this);
// N.B. Calling GetGraphvizId() will print the deprecation console warning.
*dot << this->GetGraphvizId() << ":y" << port.get_index();
}
#pragma GCC diagnostic pop
template <typename T>
std::unique_ptr<ContinuousState<T>> LeafSystem<T>::AllocateContinuousState()
const {
DRAKE_DEMAND(model_continuous_state_vector_->size() ==
this->num_continuous_states());
const SystemBase::ContextSizes& sizes = this->get_context_sizes();
auto result = std::make_unique<ContinuousState<T>>(
model_continuous_state_vector_->Clone(),
sizes.num_generalized_positions, sizes.num_generalized_velocities,
sizes.num_misc_continuous_states);
result->set_system_id(this->get_system_id());
return result;
}
template <typename T>
std::unique_ptr<DiscreteValues<T>> LeafSystem<T>::AllocateDiscreteState()
const {
return model_discrete_state_.Clone();
}
template <typename T>
std::unique_ptr<AbstractValues> LeafSystem<T>::AllocateAbstractState() const {
return std::make_unique<AbstractValues>(
model_abstract_states_.CloneAllModels());
}
template <typename T>
std::unique_ptr<Parameters<T>> LeafSystem<T>::AllocateParameters() const {
std::vector<std::unique_ptr<BasicVector<T>>> numeric_params;
numeric_params.reserve(model_numeric_parameters_.size());
for (int i = 0; i < model_numeric_parameters_.size(); ++i) {
auto param = model_numeric_parameters_.CloneVectorModel<T>(i);
DRAKE_ASSERT(param != nullptr);
numeric_params.emplace_back(std::move(param));
}
std::vector<std::unique_ptr<AbstractValue>> abstract_params;
abstract_params.reserve(model_abstract_parameters_.size());
for (int i = 0; i < model_abstract_parameters_.size(); ++i) {
auto param = model_abstract_parameters_.CloneModel(i);
DRAKE_ASSERT(param != nullptr);
abstract_params.emplace_back(std::move(param));
}
auto result = std::make_unique<Parameters<T>>(std::move(numeric_params),
std::move(abstract_params));
result->set_system_id(this->get_system_id());
return result;
}
template <typename T>
int LeafSystem<T>::DeclareNumericParameter(const BasicVector<T>& model_vector) {
const NumericParameterIndex index(model_numeric_parameters_.size());
model_numeric_parameters_.AddVectorModel(index, model_vector.Clone());
MaybeDeclareVectorBaseInequalityConstraint(
"parameter " + std::to_string(index), model_vector,
[index](const Context<T>& context) -> const VectorBase<T>& {
const BasicVector<T>& result = context.get_numeric_parameter(index);
return result;
});
this->AddNumericParameter(index);
return index;
}
template <typename T>
int LeafSystem<T>::DeclareAbstractParameter(const AbstractValue& model_value) {
const AbstractParameterIndex index(model_abstract_parameters_.size());
model_abstract_parameters_.AddModel(index, model_value.Clone());
this->AddAbstractParameter(index);
return index;
}
template <typename T>
void LeafSystem<T>::DeclarePeriodicPublishNoHandler(
double period_sec, double offset_sec) {
DeclarePeriodicEvent(period_sec, offset_sec, PublishEvent<T>());
}
template <typename T>
void LeafSystem<T>::DeclarePeriodicDiscreteUpdateNoHandler(
double period_sec, double offset_sec) {
DeclarePeriodicEvent(period_sec, offset_sec, DiscreteUpdateEvent<T>());
}
template <typename T>
void LeafSystem<T>::DeclarePeriodicUnrestrictedUpdateNoHandler(
double period_sec, double offset_sec) {
DeclarePeriodicEvent(period_sec, offset_sec, UnrestrictedUpdateEvent<T>());
}
template <typename T>
ContinuousStateIndex LeafSystem<T>::DeclareContinuousState(
int num_state_variables) {
const int num_q = 0, num_v = 0;
return DeclareContinuousState(num_q, num_v, num_state_variables);
}
template <typename T>
ContinuousStateIndex LeafSystem<T>::DeclareContinuousState(
int num_q, int num_v, int num_z) {
const int n = num_q + num_v + num_z;
return DeclareContinuousState(
BasicVector<T>(VectorX<T>::Zero(n)), num_q, num_v, num_z);
}
template <typename T>
ContinuousStateIndex LeafSystem<T>::DeclareContinuousState(
const BasicVector<T>& model_vector) {
const int num_q = 0, num_v = 0;
const int num_z = model_vector.size();
return DeclareContinuousState(model_vector, num_q, num_v, num_z);
}
template <typename T>
ContinuousStateIndex LeafSystem<T>::DeclareContinuousState(
const BasicVector<T>& model_vector, int num_q, int num_v, int num_z) {
DRAKE_DEMAND(model_vector.size() == num_q + num_v + num_z);
model_continuous_state_vector_ = model_vector.Clone();
// Note that only the last DeclareContinuousState() takes effect;
// we're not accumulating these as we do for discrete & abstract states.
SystemBase::ContextSizes& context_sizes =
this->get_mutable_context_sizes();
context_sizes.num_generalized_positions = num_q;
context_sizes.num_generalized_velocities = num_v;
context_sizes.num_misc_continuous_states = num_z;
MaybeDeclareVectorBaseInequalityConstraint(
"continuous state", model_vector,
[](const Context<T>& context) -> const VectorBase<T>& {
const ContinuousState<T>& state = context.get_continuous_state();
return state.get_vector();
});
return ContinuousStateIndex(0);
}
template <typename T>
DiscreteStateIndex LeafSystem<T>::DeclareDiscreteState(
const BasicVector<T>& model_vector) {
const DiscreteStateIndex index(model_discrete_state_.num_groups());
model_discrete_state_.AppendGroup(model_vector.Clone());
this->AddDiscreteStateGroup(index);
MaybeDeclareVectorBaseInequalityConstraint(
"discrete state", model_vector,
[index](const Context<T>& context) -> const VectorBase<T>& {
const BasicVector<T>& state = context.get_discrete_state(index);
return state;
});
return index;
}
template <typename T>
DiscreteStateIndex LeafSystem<T>::DeclareDiscreteState(
const Eigen::Ref<const VectorX<T>>& vector) {
return DeclareDiscreteState(BasicVector<T>(vector));
}
template <typename T>
DiscreteStateIndex LeafSystem<T>::DeclareDiscreteState(
int num_state_variables) {
DRAKE_DEMAND(num_state_variables >= 0);
return DeclareDiscreteState(VectorX<T>::Zero(num_state_variables));
}
template <typename T>
AbstractStateIndex LeafSystem<T>::DeclareAbstractState(
const AbstractValue& model_value) {
const AbstractStateIndex index(model_abstract_states_.size());
model_abstract_states_.AddModel(index, model_value.Clone());
this->AddAbstractState(index);
return index;
}
template <typename T>
InputPort<T>& LeafSystem<T>::DeclareVectorInputPort(
std::variant<std::string, UseDefaultName> name,
const BasicVector<T>& model_vector,
std::optional<RandomDistribution> random_type) {
const int size = model_vector.size();
const int index = this->num_input_ports();
model_input_values_.AddVectorModel(index, model_vector.Clone());
MaybeDeclareVectorBaseInequalityConstraint(
"input " + std::to_string(index), model_vector,
[this, index](const Context<T>& context) -> const VectorBase<T>& {
return this->get_input_port(index).
template Eval<BasicVector<T>>(context);
});
return this->DeclareInputPort(NextInputPortName(std::move(name)),
kVectorValued, size, random_type);
}
template <typename T>
InputPort<T>& LeafSystem<T>::DeclareVectorInputPort(
std::variant<std::string, UseDefaultName> name, int size,
std::optional<RandomDistribution> random_type) {
return DeclareVectorInputPort(std::move(name), BasicVector<T>(size),
random_type);
}
template <typename T>
InputPort<T>& LeafSystem<T>::DeclareAbstractInputPort(
std::variant<std::string, UseDefaultName> name,
const AbstractValue& model_value) {
const int next_index = this->num_input_ports();
model_input_values_.AddModel(next_index, model_value.Clone());
return this->DeclareInputPort(NextInputPortName(std::move(name)),
kAbstractValued, 0 /* size */);
}
template <typename T>
void LeafSystem<T>::DeprecateInputPort(
const InputPort<T>& port, std::string message) {
InputPort<T>& mutable_port = const_cast<InputPort<T>&>(
this->get_input_port(port.get_index()));
DRAKE_THROW_UNLESS(&mutable_port == &port);
DRAKE_THROW_UNLESS(mutable_port.get_deprecation() == std::nullopt);
mutable_port.set_deprecation({std::move(message)});
}
template <typename T>
LeafOutputPort<T>& LeafSystem<T>::DeclareVectorOutputPort(
std::variant<std::string, UseDefaultName> name,
const BasicVector<T>& model_vector,
typename LeafOutputPort<T>::CalcVectorCallback vector_calc_function,
std::set<DependencyTicket> prerequisites_of_calc) {
auto& port = CreateVectorLeafOutputPort(NextOutputPortName(std::move(name)),
model_vector.size(), MakeAllocateCallback(model_vector),
std::move(vector_calc_function), std::move(prerequisites_of_calc));
return port;
}
template <typename T>
LeafOutputPort<T>& LeafSystem<T>::DeclareAbstractOutputPort(
std::variant<std::string, UseDefaultName> name,
typename LeafOutputPort<T>::AllocCallback alloc_function,
typename LeafOutputPort<T>::CalcCallback calc_function,
std::set<DependencyTicket> prerequisites_of_calc) {
auto calc = [captured_calc = std::move(calc_function)](
const ContextBase& context_base, AbstractValue* result) {
const Context<T>& context = dynamic_cast<const Context<T>&>(context_base);
return captured_calc(context, result);
};
auto& port = CreateAbstractLeafOutputPort(
NextOutputPortName(std::move(name)),
ValueProducer(std::move(alloc_function), std::move(calc)),
std::move(prerequisites_of_calc));
return port;
}
template <typename T>
LeafOutputPort<T>& LeafSystem<T>::DeclareStateOutputPort(
std::variant<std::string, UseDefaultName> name,
ContinuousStateIndex state_index) {
DRAKE_THROW_UNLESS(state_index.is_valid());
DRAKE_THROW_UNLESS(state_index == 0);
return DeclareVectorOutputPort(
std::move(name), *model_continuous_state_vector_,
[](const Context<T>& context, BasicVector<T>* output) {
output->SetFrom(context.get_continuous_state_vector());
},
{this->xc_ticket()});
}
template <typename T>
LeafOutputPort<T>& LeafSystem<T>::DeclareStateOutputPort(
std::variant<std::string, UseDefaultName> name,
DiscreteStateIndex state_index) {
// DiscreteValues::get_vector already bounds checks the index, so we don't
// need to guard it here.
return DeclareVectorOutputPort(
std::move(name), this->model_discrete_state_.get_vector(state_index),
[state_index](const Context<T>& context, BasicVector<T>* output) {
output->SetFrom(context.get_discrete_state(state_index));
},
{this->discrete_state_ticket(state_index)});
}
template <typename T>
LeafOutputPort<T>& LeafSystem<T>::DeclareStateOutputPort(
std::variant<std::string, UseDefaultName> name,
AbstractStateIndex state_index) {
DRAKE_THROW_UNLESS(state_index.is_valid());
DRAKE_THROW_UNLESS(state_index >= 0);
DRAKE_THROW_UNLESS(state_index < this->model_abstract_states_.size());
return DeclareAbstractOutputPort(
std::move(name),
[this, state_index]() {
return this->model_abstract_states_.CloneModel(state_index);
},
[state_index](const Context<T>& context, AbstractValue* output) {
output->SetFrom(context.get_abstract_state().get_value(state_index));
},
{this->abstract_state_ticket(state_index)});
}
template <typename T>
void LeafSystem<T>::DeprecateOutputPort(
const OutputPort<T>& port, std::string message) {
OutputPort<T>& mutable_port = const_cast<OutputPort<T>&>(
this->get_output_port(port.get_index()));
DRAKE_THROW_UNLESS(&mutable_port == &port);
DRAKE_THROW_UNLESS(mutable_port.get_deprecation() == std::nullopt);
mutable_port.set_deprecation({std::move(message)});
}
template <typename T>
std::unique_ptr<WitnessFunction<T>> LeafSystem<T>::MakeWitnessFunction(
const std::string& description,
const WitnessFunctionDirection& direction_type,
std::function<T(const Context<T>&)> calc) const {
return std::make_unique<WitnessFunction<T>>(
this, this, description, direction_type, calc);
}
template <typename T>
std::unique_ptr<WitnessFunction<T>> LeafSystem<T>::MakeWitnessFunction(
const std::string& description,
const WitnessFunctionDirection& direction_type,
std::function<T(const Context<T>&)> calc,
const Event<T>& e) const {
return std::make_unique<WitnessFunction<T>>(
this, this, description, direction_type, calc, e.Clone());
}
template <typename T>
SystemConstraintIndex LeafSystem<T>::DeclareEqualityConstraint(
ContextConstraintCalc<T> calc, int count,
std::string description) {
return DeclareInequalityConstraint(
std::move(calc), SystemConstraintBounds::Equality(count),
std::move(description));
}
template <typename T>
SystemConstraintIndex LeafSystem<T>::DeclareInequalityConstraint(
ContextConstraintCalc<T> calc,
SystemConstraintBounds bounds,
std::string description) {
return this->AddConstraint(std::make_unique<SystemConstraint<T>>(
this, std::move(calc), std::move(bounds), std::move(description)));
}
template <typename T>
void LeafSystem<T>::DoPublish(
const Context<T>& context,
const std::vector<const PublishEvent<T>*>&) const {
// Sets this flag to indicate that the derived System did not override
// our default method. See DispatchPublishHandler() for how this is used.
context.set_use_default_implementation(true);
}
template <typename T>
void LeafSystem<T>::DoCalcDiscreteVariableUpdates(
const Context<T>& context,
const std::vector<const DiscreteUpdateEvent<T>*>&,
DiscreteValues<T>*) const {
// Sets this flag to indicate that the derived System did not override
// our default method. See DispatchDiscreteVariableUpdateHandler() for how
// this is used.
context.set_use_default_implementation(true);
}
template <typename T>
void LeafSystem<T>::DoCalcUnrestrictedUpdate(
const Context<T>& context,
const std::vector<const UnrestrictedUpdateEvent<T>*>&,
State<T>*) const {
// Sets this flag to indicate that the derived System did not override
// our default method. See DispatchUnrestrictedUpdateHandler() for how
// this is used.
context.set_use_default_implementation(true);
}
template <typename T>
std::unique_ptr<AbstractValue> LeafSystem<T>::DoAllocateInput(
const InputPort<T>& input_port) const {
std::unique_ptr<AbstractValue> model_result =
model_input_values_.CloneModel(input_port.get_index());
if (model_result) {
return model_result;
}
if (input_port.get_data_type() == kVectorValued) {
return std::make_unique<Value<BasicVector<T>>>(input_port.size());
}
throw std::logic_error(fmt::format(
"System::AllocateInputAbstract(): a System with abstract input ports "
"must pass a model_value to DeclareAbstractInputPort; the port[{}] "
"named '{}' did not do so (System {})",
input_port.get_index(), input_port.get_name(),
this->GetSystemPathname()));
}
template <typename T>
std::map<PeriodicEventData, std::vector<const Event<T>*>,
PeriodicEventDataComparator>
LeafSystem<T>::DoMapPeriodicEventsByTiming(const Context<T>&) const {
std::map<PeriodicEventData, std::vector<const Event<T>*>,
PeriodicEventDataComparator>
periodic_events_map;
// Build a mapping from (offset,period) to the periodic events sharing
// that trigger. There are three lists of different types in a
// CompositeEventCollection; we use this generic lambda for all.
auto map_events = [&periodic_events_map](const auto& typed_events) {
for (const auto* event : typed_events.get_events()) {
const PeriodicEventData* event_data =
event->template get_event_data<PeriodicEventData>();
DRAKE_DEMAND(event_data != nullptr);
periodic_events_map[*event_data].push_back(event);
}
};
map_events(periodic_events_.get_publish_events());
map_events(periodic_events_.get_discrete_update_events());
map_events(periodic_events_.get_unrestricted_update_events());
return periodic_events_map;
}
template <typename T>
EventStatus LeafSystem<T>::DispatchPublishHandler(
const Context<T>& context,
const EventCollection<PublishEvent<T>>& events) const {
const LeafEventCollection<PublishEvent<T>>& leaf_events =
dynamic_cast<const LeafEventCollection<PublishEvent<T>>&>(events);
// This function shouldn't have been called if no publish events.
DRAKE_DEMAND(leaf_events.HasEvents());
// Determine whether the derived System overloaded DoPublish(). If so, this
// flag will remain false; the default implementation sets it to true.
context.set_use_default_implementation(false);
#pragma GCC diagnostic push
#pragma GCC diagnostic ignored "-Wdeprecated-declarations"
this->DoPublish(context, leaf_events.get_events());
#pragma GCC diagnostic pop
if (!context.get_use_default_implementation()) {
static const drake::internal::WarnDeprecated warn_once(
"2024-02-01",
"Overriding LeafSystem::DoPublish is deprecated.");
// Derived system overrode the dispatcher and did not invoke the base class
// implementation so there is nothing else to do.
return EventStatus::Succeeded();
}
// Use our default dispatch policy.
EventStatus overall_status = EventStatus::DidNothing();
for (const PublishEvent<T>* event : leaf_events.get_events()) {
const EventStatus per_event_status = event->handle(*this, context);
overall_status.KeepMoreSevere(per_event_status);
// Unlike the discrete & unrestricted event policy, we don't stop
// handling publish events when one fails; we just report the first failure
// after all the publishes are done.
}
return overall_status;
}
template <typename T>
EventStatus LeafSystem<T>::DispatchDiscreteVariableUpdateHandler(
const Context<T>& context,
const EventCollection<DiscreteUpdateEvent<T>>& events,
DiscreteValues<T>* discrete_state) const {
const LeafEventCollection<DiscreteUpdateEvent<T>>& leaf_events =
dynamic_cast<const LeafEventCollection<DiscreteUpdateEvent<T>>&>(
events);
// This function shouldn't have been called if no discrete update events.
DRAKE_DEMAND(leaf_events.HasEvents());
// Must initialize the output argument with current discrete state contents.
discrete_state->SetFrom(context.get_discrete_state());
// Determine whether the derived System overloaded
// DoCalcDiscreteVariableUpdates(). If so, this flag will remain false; the
// default implementation sets it to true.
context.set_use_default_implementation(false);
#pragma GCC diagnostic push
#pragma GCC diagnostic ignored "-Wdeprecated-declarations"
this->DoCalcDiscreteVariableUpdates(context, leaf_events.get_events(),
discrete_state); // in/out
#pragma GCC diagnostic pop
if (!context.get_use_default_implementation()) {
static const drake::internal::WarnDeprecated warn_once(
"2024-02-01",
"Overriding LeafSystem::DoCalcDiscreteVariableUpdates is deprecated.");
// Derived system overrode the dispatcher and did not invoke the base class
// implementation so there is nothing else to do.
return EventStatus::Succeeded();
}
// Use our default dispatch policy.
EventStatus overall_status = EventStatus::DidNothing();
for (const DiscreteUpdateEvent<T>* event : leaf_events.get_events()) {
const EventStatus per_event_status =
event->handle(*this, context, discrete_state);
overall_status.KeepMoreSevere(per_event_status);
if (overall_status.failed()) break; // Stop at the first disaster.
}
return overall_status;
}
template <typename T>
void LeafSystem<T>::DoApplyDiscreteVariableUpdate(
const EventCollection<DiscreteUpdateEvent<T>>& events,
DiscreteValues<T>* discrete_state, Context<T>* context) const {
DRAKE_ASSERT(
dynamic_cast<const LeafEventCollection<DiscreteUpdateEvent<T>>*>(
&events) != nullptr);
DRAKE_DEMAND(events.HasEvents());
// TODO(sherm1) Should swap rather than copy.
context->get_mutable_discrete_state().SetFrom(*discrete_state);
}
template <typename T>
EventStatus LeafSystem<T>::DispatchUnrestrictedUpdateHandler(
const Context<T>& context,
const EventCollection<UnrestrictedUpdateEvent<T>>& events,
State<T>* state) const {
const LeafEventCollection<UnrestrictedUpdateEvent<T>>& leaf_events =
dynamic_cast<const LeafEventCollection<UnrestrictedUpdateEvent<T>>&>(
events);
// This function shouldn't have been called if no unrestricted update events.
DRAKE_DEMAND(leaf_events.HasEvents());
// Must initialize the output argument with current state contents.
state->SetFrom(context.get_state());
// Determine whether the derived System overloaded
// DoCalcUnrestrictedUpdate(). If so, this flag will remain false; the
// default implementation sets it to true.
context.set_use_default_implementation(false);
#pragma GCC diagnostic push
#pragma GCC diagnostic ignored "-Wdeprecated-declarations"
this->DoCalcUnrestrictedUpdate(context, leaf_events.get_events(),
state); // in/out
#pragma GCC diagnostic pop
if (!context.get_use_default_implementation()) {
static const drake::internal::WarnDeprecated warn_once(
"2024-02-01",
"Overriding LeafSystem::DoCalcUnrestrictedUpdate is deprecated.");
// Derived system overrode the dispatcher and did not invoke the base class
// implementation so there is nothing else to do.
return EventStatus::Succeeded();
}
// Use our default dispatch policy.
EventStatus overall_status = EventStatus::DidNothing();
for (const UnrestrictedUpdateEvent<T>* event : leaf_events.get_events()) {
const EventStatus per_event_status = event->handle(*this, context, state);
overall_status.KeepMoreSevere(per_event_status);
if (overall_status.failed()) break; // Stop at the first disaster.
}
return overall_status;
}
template <typename T>
void LeafSystem<T>::DoApplyUnrestrictedUpdate(
const EventCollection<UnrestrictedUpdateEvent<T>>& events,
State<T>* state, Context<T>* context) const {
DRAKE_ASSERT(
dynamic_cast<const LeafEventCollection<UnrestrictedUpdateEvent<T>>*>(
&events) != nullptr);
DRAKE_DEMAND(events.HasEvents());
// TODO(sherm1) Should swap rather than copy.
context->get_mutable_state().SetFrom(*state);
}
// The Diagram implementation of this method recursively visits sub-Diagrams
// until we get to this LeafSystem implementation, where we can actually look
// at the periodic discrete update Events. When no timing has yet been
// established (`timing` parameter is empty), the first LeafSystem
// to find a periodic discrete update event sets the timing for all the rest.
// After that every periodic discrete update event must have the same timing
// or this method throws an error message. If the timing is good, we return
// all the periodic discrete update events we find in this LeafSystem.
//
// Unit testing for this method is in diagram_test.cc where it is used in
// the leaf computation for the Diagram EvalUniquePeriodicDiscreteUpdate()