Skip to content

Commit

Permalink
Allow specific cache entries to be initially disabled (RobotLocomotio…
Browse files Browse the repository at this point in the history
  • Loading branch information
sherm1 authored Mar 4, 2020
1 parent dcd794f commit f3a0980
Show file tree
Hide file tree
Showing 12 changed files with 194 additions and 99 deletions.
9 changes: 4 additions & 5 deletions bindings/pydrake/systems/framework_py_systems.cc
Original file line number Diff line number Diff line change
Expand Up @@ -293,15 +293,15 @@ struct Impl {
.def("GetOutputPort", &System<T>::GetOutputPort, py_reference_internal,
py::arg("port_name"), doc.System.GetOutputPort.doc)
.def("DeclareInputPort",
overload_cast_explicit<const InputPort<T>&,
overload_cast_explicit<InputPort<T>&,
std::variant<std::string, UseDefaultName>, PortDataType, int,
std::optional<RandomDistribution>>(&PySystem::DeclareInputPort),
py_reference_internal, py::arg("name"), py::arg("type"),
py::arg("size"), py::arg("random_type") = std::nullopt,
doc.System.DeclareInputPort.doc_4args)
.def("DeclareInputPort",
overload_cast_explicit< // BR
const InputPort<T>&, PortDataType, int,
InputPort<T>&, PortDataType, int,
std::optional<RandomDistribution>>(&PySystem::DeclareInputPort),
py_reference_internal, py::arg("type"), py::arg("size"),
py::arg("random_type") = std::nullopt)
Expand Down Expand Up @@ -480,8 +480,7 @@ Note: The above is for the C++ documentation. For Python, use
py_reference_internal, py::arg("name"), py::arg("model_value"),
doc.LeafSystem.DeclareAbstractInputPort.doc_2args)
.def("DeclareAbstractInputPort",
[](PyLeafSystem* self,
const std::string& name) -> const InputPort<T>& {
[](PyLeafSystem* self, const std::string& name) -> InputPort<T>& {
WarnDeprecated(
"`DeclareAbstractInputPort(self, name)` is deprecated. "
"Please use `(self, name, model_value)` instead.");
Expand Down Expand Up @@ -520,7 +519,7 @@ Note: The above is for the C++ documentation. For Python, use
[](PyLeafSystem* self, std::string name,
const BasicVector<T>& model_vector,
std::optional<RandomDistribution> random_type)
-> const InputPort<T>& {
-> InputPort<T>& {
return self->DeclareVectorInputPort(
name, model_vector, random_type);
},
Expand Down
38 changes: 27 additions & 11 deletions systems/framework/cache_entry.h
Original file line number Diff line number Diff line change
Expand Up @@ -71,7 +71,7 @@ class CacheEntry {
the cache entry. Instead allocation is deferred until the allocator can be
provided with a complete Context, which cannot occur until the full Diagram
containing this subsystem has been completed. That way the initial type, size,
or value can Context-dependent. The supplied prerequisite tickets are
or value can be Context-dependent. The supplied prerequisite tickets are
interpreted as belonging to the same subsystem that owns this %CacheEntry.
The list of prerequisites cannot be empty -- a cache entry that really has
Expand Down Expand Up @@ -211,30 +211,44 @@ class CacheEntry {
}

/** (Debugging) Returns `true` if caching has been disabled for this cache
entry. That means Eval() will recalculate even if the entry is marked up
to date. */
entry in the given `context`. That means Eval() will recalculate even if the
entry is marked up to date. */
bool is_cache_entry_disabled(const ContextBase& context) const {
return get_cache_entry_value(context).is_cache_entry_disabled();
}

/** (Debugging) Disables caching for this cache entry. Eval() will recompute
the cached value every time it is invoked, regardless of the state of the
out_of_date flag. That should have no effect on any computed results, other
than speed. See class documentation for ideas as to what might be wrong if you
see a change. Note that the `context` is `const` here; cache entry values
are mutable. */
/** (Debugging) Disables caching for this cache entry in the given `context`.
Eval() will recompute the cached value every time it is invoked, regardless
of the state of the out_of_date flag. That should have no effect on any
computed results, other than speed. See class documentation for ideas as to
what might be wrong if you see a change. Note that the `context` is `const`
here; cache entry values are mutable. */
void disable_caching(const ContextBase& context) const {
CacheEntryValue& value = get_mutable_cache_entry_value(context);
value.disable_caching();
}

/** (Debugging) Enables caching for this cache entry if it was previously
disabled. */
/** (Debugging) Enables caching for this cache entry in the given `context`
if it was previously disabled. */
void enable_caching(const ContextBase& context) const {
CacheEntryValue& value = get_mutable_cache_entry_value(context);
value.enable_caching();
}

/** (Debugging) Marks this cache entry so that the corresponding
CacheEntryValue object in any allocated Context is created with its
`disabled` flag initially set. This can be useful for debugging when you have
observed a difference between cached and non-cached behavior that can't be
diagnosed with the runtime disable_caching() method.
@see disable_caching() */
void disable_caching_by_default() {
is_disabled_by_default_ = true;
}

/** (Debugging) Returns the current value of this flag. It is `false` unless
a call to `disable_caching_by_default()` has previously been made. */
bool is_disabled_by_default() const { return is_disabled_by_default_; }

/** Return the human-readable description for this %CacheEntry. */
const std::string& description() const { return description_; }

Expand Down Expand Up @@ -333,6 +347,8 @@ class CacheEntry {
// prerequisites are internal to the containing subsystem, so the ticket
// alone is a unique specification of a prerequisite.
std::set<DependencyTicket> prerequisites_of_calc_;

bool is_disabled_by_default_{false};
};

} // namespace systems
Expand Down
13 changes: 11 additions & 2 deletions systems/framework/leaf_output_port.h
Original file line number Diff line number Diff line change
Expand Up @@ -65,6 +65,15 @@ class LeafOutputPort final : public OutputPort<T> {
return *cache_entry_;
}

/** (Debugging) Specifies that caching should be disabled for this output
port when a Context is first allocated. This is useful if you have observed
different behavior with caching on or off and would like to determine if
the problem is caused by this port.
@see CacheEntry::disable_caching_by_default() */
void disable_caching_by_default() {
cache_entry_->disable_caching_by_default();
}

private:
friend class internal::FrameworkFactory;

Expand All @@ -73,7 +82,7 @@ class LeafOutputPort final : public OutputPort<T> {
LeafOutputPort(const System<T>* system, SystemBase* system_base,
std::string name, OutputPortIndex index,
DependencyTicket ticket, PortDataType data_type, int size,
const CacheEntry* cache_entry)
CacheEntry* cache_entry)
: OutputPort<T>(system, system_base, std::move(name), index, ticket,
data_type, size),
cache_entry_(cache_entry) {
Expand All @@ -100,7 +109,7 @@ class LeafOutputPort final : public OutputPort<T> {
return {std::nullopt, cache_entry().ticket()};
};

const CacheEntry* const cache_entry_;
CacheEntry* const cache_entry_;
};

} // namespace systems
Expand Down
38 changes: 19 additions & 19 deletions systems/framework/leaf_system.h
Original file line number Diff line number Diff line change
Expand Up @@ -1575,7 +1575,7 @@ class LeafSystem : public System<T> {
/// DeclareInequalityConstraint()).
///
/// @see System::DeclareInputPort() for more information.
const InputPort<T>& DeclareVectorInputPort(
InputPort<T>& DeclareVectorInputPort(
std::variant<std::string, UseDefaultName> name,
const BasicVector<T>& model_vector,
std::optional<RandomDistribution> random_type = std::nullopt) {
Expand All @@ -1599,7 +1599,7 @@ class LeafSystem : public System<T> {
/// input, must provide for values whose type matches this @p model_value.
///
/// @see System::DeclareInputPort() for more information.
const InputPort<T>& DeclareAbstractInputPort(
InputPort<T>& DeclareAbstractInputPort(
std::variant<std::string, UseDefaultName> name,
const AbstractValue& model_value) {
const int next_index = this->num_input_ports();
Expand All @@ -1620,7 +1620,7 @@ class LeafSystem : public System<T> {
/// See the nearly identical signature with an additional (first) argument
/// specifying the port name. This version will be deprecated as discussed
/// in #9447.
const InputPort<T>& DeclareVectorInputPort(
InputPort<T>& DeclareVectorInputPort(
const BasicVector<T>& model_vector,
std::optional<RandomDistribution> random_type = std::nullopt) {
return DeclareVectorInputPort(kUseDefaultName, model_vector, random_type);
Expand All @@ -1629,7 +1629,7 @@ class LeafSystem : public System<T> {
/// See the nearly identical signature with an additional (first) argument
/// specifying the port name. This version will be deprecated as discussed
/// in #9447.
const InputPort<T>& DeclareAbstractInputPort(
InputPort<T>& DeclareAbstractInputPort(
const AbstractValue& model_value) {
return DeclareAbstractInputPort(kUseDefaultName, model_value);
}
Expand Down Expand Up @@ -1731,7 +1731,7 @@ class LeafSystem : public System<T> {
/// where `MySystem` is a class derived from `LeafSystem<T>`. Template
/// arguments will be deduced and do not need to be specified.
template <class MySystem, typename BasicVectorSubtype>
const OutputPort<T>& DeclareVectorOutputPort(
LeafOutputPort<T>& DeclareVectorOutputPort(
std::variant<std::string, UseDefaultName> name,
const BasicVectorSubtype& model_vector,
void (MySystem::*calc)(const Context<T>&, BasicVectorSubtype*) const,
Expand Down Expand Up @@ -1789,7 +1789,7 @@ class LeafSystem : public System<T> {
/// provide a method for the allocator to call; that method can then invoke
/// the `BasicVectorSubtype` default constructor.
template <class MySystem, typename BasicVectorSubtype>
const OutputPort<T>& DeclareVectorOutputPort(
LeafOutputPort<T>& DeclareVectorOutputPort(
std::variant<std::string, UseDefaultName> name,
void (MySystem::*calc)(const Context<T>&, BasicVectorSubtype*) const,
std::set<DependencyTicket> prerequisites_of_calc = {
Expand All @@ -1811,7 +1811,7 @@ class LeafSystem : public System<T> {
/// function in its most generic form; if you have a member function available
/// use one of the other signatures.
/// @see LeafOutputPort::CalcVectorCallback
const OutputPort<T>& DeclareVectorOutputPort(
LeafOutputPort<T>& DeclareVectorOutputPort(
std::variant<std::string, UseDefaultName> name,
const BasicVector<T>& model_vector,
typename LeafOutputPort<T>::CalcVectorCallback vector_calc_function,
Expand All @@ -1834,7 +1834,7 @@ class LeafSystem : public System<T> {
/// Template arguments will be deduced and do not need to be specified.
/// @see drake::Value
template <class MySystem, typename OutputType>
const OutputPort<T>& DeclareAbstractOutputPort(
LeafOutputPort<T>& DeclareAbstractOutputPort(
std::variant<std::string, UseDefaultName> name,
const OutputType& model_value,
void (MySystem::*calc)(const Context<T>&, OutputType*) const,
Expand Down Expand Up @@ -1873,7 +1873,7 @@ class LeafSystem : public System<T> {
/// the `OutputType` default constructor.
/// @see drake::Value
template <class MySystem, typename OutputType>
const OutputPort<T>& DeclareAbstractOutputPort(
LeafOutputPort<T>& DeclareAbstractOutputPort(
std::variant<std::string, UseDefaultName> name,
void (MySystem::*calc)(const Context<T>&, OutputType*) const,
std::set<DependencyTicket> prerequisites_of_calc = {
Expand All @@ -1900,7 +1900,7 @@ class LeafSystem : public System<T> {
/// Template arguments will be deduced and do not need to be specified.
/// @see drake::Value
template <class MySystem, typename OutputType>
const OutputPort<T>& DeclareAbstractOutputPort(
LeafOutputPort<T>& DeclareAbstractOutputPort(
std::variant<std::string, UseDefaultName> name,
OutputType (MySystem::*make)() const,
void (MySystem::*calc)(const Context<T>&, OutputType*) const,
Expand All @@ -1924,7 +1924,7 @@ class LeafSystem : public System<T> {
/// allocator and calculator functions provided in their most generic forms.
/// If you have a member function available use one of the other signatures.
/// @see LeafOutputPort::AllocCallback, LeafOutputPort::CalcCallback
const OutputPort<T>& DeclareAbstractOutputPort(
LeafOutputPort<T>& DeclareAbstractOutputPort(
std::variant<std::string, UseDefaultName> name,
typename LeafOutputPort<T>::AllocCallback alloc_function,
typename LeafOutputPort<T>::CalcCallback calc_function,
Expand All @@ -1949,7 +1949,7 @@ class LeafSystem : public System<T> {
/// specifying the port name. This version will be deprecated as discussed
/// in #9447.
template <class MySystem, typename BasicVectorSubtype>
const OutputPort<T>& DeclareVectorOutputPort(
LeafOutputPort<T>& DeclareVectorOutputPort(
const BasicVectorSubtype& model_vector,
void (MySystem::*calc)(const Context<T>&, BasicVectorSubtype*) const,
std::set<DependencyTicket> prerequisites_of_calc = {
Expand All @@ -1962,7 +1962,7 @@ class LeafSystem : public System<T> {
/// specifying the port name. This version will be deprecated as discussed
/// in #9447.
template <class MySystem, typename BasicVectorSubtype>
const OutputPort<T>& DeclareVectorOutputPort(
LeafOutputPort<T>& DeclareVectorOutputPort(
void (MySystem::*calc)(const Context<T>&, BasicVectorSubtype*) const,
std::set<DependencyTicket> prerequisites_of_calc = {
all_sources_ticket()}) {
Expand All @@ -1973,7 +1973,7 @@ class LeafSystem : public System<T> {
/// See the nearly identical signature with an additional (first) argument
/// specifying the port name. This version will be deprecated as discussed
/// in #9447.
const OutputPort<T>& DeclareVectorOutputPort(
LeafOutputPort<T>& DeclareVectorOutputPort(
const BasicVector<T>& model_vector,
typename LeafOutputPort<T>::CalcVectorCallback vector_calc_function,
std::set<DependencyTicket> prerequisites_of_calc = {
Expand All @@ -1990,7 +1990,7 @@ class LeafSystem : public System<T> {
/// case the name is required.
template <class MySystem, typename OutputType>
std::enable_if_t<!std::is_same<OutputType, std::string>::value,
const OutputPort<T>&>
LeafOutputPort<T>&>
DeclareAbstractOutputPort(const OutputType& model_value,
void (MySystem::*calc)(const Context<T>&,
OutputType*) const,
Expand All @@ -2004,7 +2004,7 @@ class LeafSystem : public System<T> {
/// specifying the port name. This version will be deprecated as discussed
/// in #9447.
template <class MySystem, typename OutputType>
const OutputPort<T>& DeclareAbstractOutputPort(
LeafOutputPort<T>& DeclareAbstractOutputPort(
void (MySystem::*calc)(const Context<T>&, OutputType*) const,
std::set<DependencyTicket> prerequisites_of_calc = {
all_sources_ticket()}) {
Expand All @@ -2016,7 +2016,7 @@ class LeafSystem : public System<T> {
/// specifying the port name. This version will be deprecated as discussed
/// in #9447.
template <class MySystem, typename OutputType>
const OutputPort<T>& DeclareAbstractOutputPort(
LeafOutputPort<T>& DeclareAbstractOutputPort(
OutputType (MySystem::*make)() const,
void (MySystem::*calc)(const Context<T>&, OutputType*) const,
std::set<DependencyTicket> prerequisites_of_calc = {
Expand All @@ -2028,7 +2028,7 @@ class LeafSystem : public System<T> {
/// See the nearly identical signature with an additional (first) argument
/// specifying the port name. This version will be deprecated as discussed
/// in #9447.
const OutputPort<T>& DeclareAbstractOutputPort(
LeafOutputPort<T>& DeclareAbstractOutputPort(
typename LeafOutputPort<T>::AllocCallback alloc_function,
typename LeafOutputPort<T>::CalcCallback calc_function,
std::set<DependencyTicket> prerequisites_of_calc = {
Expand Down Expand Up @@ -2640,7 +2640,7 @@ class LeafSystem : public System<T> {
DRAKE_DEMAND(!calc_prerequisites.empty());
// Create a cache entry for this output port.
const OutputPortIndex oport_index(this->num_output_ports());
const CacheEntry& cache_entry = this->DeclareCacheEntry(
CacheEntry& cache_entry = this->DeclareCacheEntry(
"output port " + std::to_string(oport_index) + "(" + name + ") cache",
std::move(allocator), std::move(calculator),
std::move(calc_prerequisites));
Expand Down
12 changes: 7 additions & 5 deletions systems/framework/system.h
Original file line number Diff line number Diff line change
Expand Up @@ -1836,7 +1836,7 @@ class System : public SystemBase {
/// @pre @p name must not be empty.
/// @throws std::logic_error for a duplicate port name.
/// @returns the declared port.
const InputPort<T>& DeclareInputPort(
InputPort<T>& DeclareInputPort(
std::variant<std::string, UseDefaultName> name, PortDataType type,
int size, std::optional<RandomDistribution> random_type = std::nullopt) {
const InputPortIndex port_index(num_input_ports());
Expand All @@ -1845,10 +1845,12 @@ class System : public SystemBase {
auto eval = [this, port_index](const ContextBase& context_base) {
return this->EvalAbstractInput(context_base, port_index);
};
this->AddInputPort(internal::FrameworkFactory::Make<InputPort<T>>(
auto port = internal::FrameworkFactory::Make<InputPort<T>>(
this, this, NextInputPortName(std::move(name)), port_index, port_ticket,
type, size, random_type, std::move(eval)));
return get_input_port(port_index);
type, size, random_type, std::move(eval));
InputPort<T>* port_ptr = port.get();
this->AddInputPort(std::move(port));
return *port_ptr;
}

//@}
Expand All @@ -1864,7 +1866,7 @@ class System : public SystemBase {
/// See the nearly identical signature with an additional (first) argument
/// specifying the port name. This version will be deprecated as discussed
/// in #9447.
const InputPort<T>& DeclareInputPort(
InputPort<T>& DeclareInputPort(
PortDataType type, int size,
std::optional<RandomDistribution> random_type = std::nullopt) {
return DeclareInputPort(kUseDefaultName, type, size, random_type);
Expand Down
9 changes: 6 additions & 3 deletions systems/framework/system_base.cc
Original file line number Diff line number Diff line change
Expand Up @@ -32,7 +32,7 @@ std::string SystemBase::GetSystemPathname() const {
GetSystemName();
}

const CacheEntry& SystemBase::DeclareCacheEntry(
CacheEntry& SystemBase::DeclareCacheEntry(
std::string description, CacheEntry::AllocCallback alloc_function,
CacheEntry::CalcCallback calc_function,
std::set<DependencyTicket> prerequisites_of_calc) {
Expand All @@ -42,7 +42,7 @@ const CacheEntry& SystemBase::DeclareCacheEntry(
std::move(prerequisites_of_calc));
}

const CacheEntry& SystemBase::DeclareCacheEntryWithKnownTicket(
CacheEntry& SystemBase::DeclareCacheEntryWithKnownTicket(
DependencyTicket known_ticket, std::string description,
CacheEntry::AllocCallback alloc_function,
CacheEntry::CalcCallback calc_function,
Expand All @@ -54,7 +54,7 @@ const CacheEntry& SystemBase::DeclareCacheEntryWithKnownTicket(
this, index, known_ticket, std::move(description),
std::move(alloc_function), std::move(calc_function),
std::move(prerequisites_of_calc)));
const CacheEntry& new_entry = *cache_entries_.back();
CacheEntry& new_entry = *cache_entries_.back();
return new_entry;
}

Expand Down Expand Up @@ -93,6 +93,9 @@ void SystemBase::InitializeContextBase(ContextBase* context_ptr) const {
// TODO(sherm1) Supply initial value on creation instead and get rid of
// this separate call.
cache_value.SetInitialValue(entry.Allocate());

if (entry.is_disabled_by_default())
cache_value.disable_caching();
}

// Create the output port trackers yᵢ here. Nothing in this System may
Expand Down
Loading

0 comments on commit f3a0980

Please sign in to comment.