Skip to content

Commit

Permalink
Merge pull request RobotLocomotion#9792 from jwnimmer-tri/fix-error-pr6
Browse files Browse the repository at this point in the history
framework: Deprecate abstract inputs without model values
  • Loading branch information
soonho-tri authored Oct 26, 2018
2 parents a207c64 + 88e9aef commit b855580
Show file tree
Hide file tree
Showing 8 changed files with 97 additions and 136 deletions.
12 changes: 10 additions & 2 deletions bindings/pydrake/systems/framework_py_systems.cc
Original file line number Diff line number Diff line change
Expand Up @@ -284,9 +284,17 @@ struct Impl {
optional<RandomDistribution>>(&PySystem::DeclareInputPort),
py_reference_internal, py::arg("type"),
py::arg("size"), py::arg("random_type") = nullopt)
// TODO(jwnimmer-tri) We should add pydrake bindings for the LeafSystem
// DeclareAbstractInputPort overload that takes a model_value, and then
// deprecate this System overload.
.def("_DeclareAbstractInputPort",
overload_cast_explicit<const InputPort<T>&, std::string>(
&PySystem::DeclareAbstractInputPort),
[](PySystem* self, const std::string& name)
-> const InputPort<T>& {
#pragma GCC diagnostic push
#pragma GCC diagnostic ignored "-Wdeprecated-declarations"
return self->DeclareAbstractInputPort(name);
#pragma GCC diagnostic pop // pop -Wdeprecated-declarations
},
py_reference_internal, py::arg("name"),
doc.System.DeclareAbstractInputPort.doc)
// - Feedthrough.
Expand Down
20 changes: 5 additions & 15 deletions systems/framework/diagram.h
Original file line number Diff line number Diff line change
Expand Up @@ -886,27 +886,17 @@ class Diagram : public System<T>, internal::SystemParentServiceInterface {
}
}

BasicVector<T>* DoAllocateInputVector(
const InputPort<T>& input_port) const override {
// Ask the subsystem to perform the allocation.
const InputPortLocator& id = input_port_ids_[input_port.get_index()];
const System<T>* subsystem = id.first;
const InputPortIndex subindex = id.second;
return subsystem->AllocateInputVector(subsystem->get_input_port(subindex))
.release();
}

AbstractValue* DoAllocateInputAbstract(
const InputPort<T>& input_port) const override {
private:
std::unique_ptr<AbstractValue> DoAllocateInput(
const InputPort<T>& input_port) const final {
// Ask the subsystem to perform the allocation.
const InputPortLocator& id = input_port_ids_[input_port.get_index()];
const System<T>* subsystem = id.first;
const InputPortIndex subindex = id.second;
return subsystem->AllocateInputAbstract(subsystem->get_input_port(subindex))
.release();
return subsystem->AllocateInputAbstract(
subsystem->get_input_port(subindex));
}

private:
// Allocates a default-constructed diagram context containing the complete
// diagram substructure of default-constructed subcontexts.
std::unique_ptr<ContextBase> DoAllocateContext() const final {
Expand Down
71 changes: 26 additions & 45 deletions systems/framework/leaf_system.h
Original file line number Diff line number Diff line change
Expand Up @@ -399,44 +399,6 @@ class LeafSystem : public System<T> {
}
}

/// Allocates a vector that is suitable as an input value for @p input_port.
/// The default implementation in this class either clones the model_vector
/// (if the port was declared via DeclareVectorInputPort) or else allocates a
/// BasicVector (if the port was declared via DeclareInputPort(kVectorValued,
/// size). Subclasses can override this method if the default behavior is
/// not sufficient.
BasicVector<T>* DoAllocateInputVector(
const InputPort<T>& input_port) const override {
std::unique_ptr<BasicVector<T>> model_result =
model_input_values_.CloneVectorModel<T>(input_port.get_index());
if (model_result) {
return model_result.release();
}
return new BasicVector<T>(input_port.size());
}

/// Allocates an AbstractValue suitable as an input value for @p input_port.
/// The default implementation in this class either clones the model_value
/// (if the port was declared via DeclareAbstractInputPort) or else aborts.
///
/// Subclasses with abstract input ports must either provide a model_value
/// when declaring the port, or else override this method.
AbstractValue* DoAllocateInputAbstract(
const InputPort<T>& input_port) const override {
std::unique_ptr<AbstractValue> model_result =
model_input_values_.CloneModel(input_port.get_index());
if (model_result) {
return model_result.release();
}
throw std::logic_error(fmt::format(
"System::AllocateInputAbstract(): a System with abstract input ports "
"should pass a model_value to DeclareAbstractInputPort, or else must "
"override DoAllocateInputAbstract; the input port[{}] named '{}' did "
"not do either one (System {})",
input_port.get_index(), input_port.get_name(),
this->GetSystemPathname()));
}

/// Emits a graphviz fragment for this System. Leaf systems are visualized as
/// records. For instance, a leaf system with 2 inputs and 1 output is:
///
Expand Down Expand Up @@ -856,9 +818,8 @@ class LeafSystem : public System<T> {

/// Declares a vector-valued input port using the given @p model_vector.
/// This is the best way to declare LeafSystem input ports that require
/// subclasses of BasicVector. The port's size will be model_vector.size(),
/// and LeafSystem's default implementation of DoAllocateInputVector will be
/// model_vector.Clone(). If the port is intended to model a random noise or
/// subclasses of BasicVector. The port's size and type will be the same as
/// model_vector. If the port is intended to model a random noise or
/// disturbance input, @p random_type can (optionally) be used to label it
/// as such. If the @p model_vector declares any
/// VectorBase::CalcInequalityConstraint() constraints, they will be
Expand All @@ -883,20 +844,20 @@ class LeafSystem : public System<T> {
kVectorValued, size, random_type);
}

// Avoid shadowing out the no-arg DeclareAbstractInputPort().
// Avoid shadowing out the no-arg DeclareAbstractInputPort(). (This line
// should be removed when the deprecated base class methods disappear.)
using System<T>::DeclareAbstractInputPort;

/// Declares an abstract-valued input port using the given @p model_value.
/// This is the best way to declare LeafSystem abstract input ports.
/// LeafSystem's default implementation of DoAllocateInputAbstract will be
/// model_value.Clone().
///
/// @see System::DeclareInputPort() for more information.
const InputPort<T>& DeclareAbstractInputPort(
std::string name, const AbstractValue& model_value) {
const int next_index = this->get_num_input_ports();
model_input_values_.AddModel(next_index, model_value.Clone());
return this->DeclareAbstractInputPort(NextInputPortName(std::move(name)));
return this->DeclareInputPort(NextInputPortName(std::move(name)),
kAbstractValued, 0 /* size */);
}
//@}

Expand Down Expand Up @@ -1643,6 +1604,26 @@ class LeafSystem : public System<T> {
using SystemBase::NextInputPortName;
using SystemBase::NextOutputPortName;

// Either clones the model_value, or else for vector ports allocates a
// BasicVector, or else for abstract ports throws an exception.
std::unique_ptr<AbstractValue> DoAllocateInput(
const InputPort<T>& input_port) const final {
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()));
}

std::map<PeriodicEventData, std::vector<const Event<T>*>,
PeriodicEventDataComparator> DoGetPeriodicEvents() const override {
std::map<PeriodicEventData, std::vector<const Event<T>*>,
Expand Down
65 changes: 24 additions & 41 deletions systems/framework/system.h
Original file line number Diff line number Diff line change
Expand Up @@ -104,31 +104,25 @@ class System : public SystemBase {
virtual std::unique_ptr<CompositeEventCollection<T>>
AllocateCompositeEventCollection() const = 0;

/// Given an input port, allocates the vector storage. The default
/// implementation in this class allocates a BasicVector. Subclasses must
/// override the NVI implementation of this function, DoAllocateInputVector,
/// to return input vector types other than BasicVector. The @p input_port
/// Given an input port, allocates the vector storage. The @p input_port
/// must match a port declared via DeclareInputPort.
std::unique_ptr<BasicVector<T>> AllocateInputVector(
const InputPort<T>& input_port) const {
DRAKE_ASSERT(input_port.get_data_type() == kVectorValued);
DRAKE_THROW_UNLESS(input_port.get_data_type() == kVectorValued);
const int index = input_port.get_index();
DRAKE_ASSERT(index >= 0 && index < get_num_input_ports());
DRAKE_ASSERT(get_input_port(index).get_data_type() == kVectorValued);
return std::unique_ptr<BasicVector<T>>(DoAllocateInputVector(input_port));
std::unique_ptr<AbstractValue> value = DoAllocateInput(input_port);
return value->GetMutableValue<BasicVector<T>>().Clone();
}

/// Given an input port, allocates the abstract storage. Subclasses with a
/// abstract input ports must override the NVI implementation of this
/// function, DoAllocateInputAbstract, to return an appropriate AbstractValue.
/// The @p input_port must match a port declared via DeclareInputPort.
/// Given an input port, allocates the abstract storage. The @p input_port
/// must match a port declared via DeclareInputPort.
std::unique_ptr<AbstractValue> AllocateInputAbstract(
const InputPort<T>& input_port) const {
DRAKE_ASSERT(input_port.get_data_type() == kAbstractValued);
const int index = input_port.get_index();
DRAKE_ASSERT(index >= 0 && index < get_num_input_ports());
DRAKE_ASSERT(get_input_port(index).get_data_type() == kAbstractValued);
return std::unique_ptr<AbstractValue>(DoAllocateInputAbstract(input_port));
return DoAllocateInput(input_port);
}

/// Returns a container that can hold the values of all of this System's
Expand Down Expand Up @@ -1696,13 +1690,6 @@ class System : public SystemBase {
return get_input_port(port_index);
}

/// Adds an abstract-valued port to the input topology.
/// @returns the declared port.
/// @see DeclareInputPort() for more information.
const InputPort<T>& DeclareAbstractInputPort(std::string name) {
return DeclareInputPort(std::move(name),
kAbstractValued, 0 /* size */);
}
//@}

// =========================================================================
Expand All @@ -1721,13 +1708,21 @@ class System : public SystemBase {
optional<RandomDistribution> random_type = nullopt) {
return DeclareInputPort(kUseDefaultName, type, size, random_type);
}
//@}

/// See the nearly identical signature with an argument specifying the port
/// name. This version will be deprecated as discussed in #9447.
#ifndef DRAKE_DOXYGEN_CXX
// Remove this overload on or about 2018-12-01.
DRAKE_DEPRECATED("Use one of the other overloads.")
const InputPort<T>& DeclareAbstractInputPort() {
return DeclareAbstractInputPort(kUseDefaultName);
return DeclareInputPort(kUseDefaultName, kAbstractValued, 0 /* size */);
}
//@}

// Remove this overload on or about 2018-12-01.
DRAKE_DEPRECATED("Use one of the other overloads.")
const InputPort<T>& DeclareAbstractInputPort(std::string name) {
return DeclareInputPort(std::move(name), kAbstractValued, 0 /* size */);
}
#endif

/// Adds an already-created constraint to the list of constraints for this
/// System. Ownership of the SystemConstraint is transferred to this system.
Expand All @@ -1738,23 +1733,6 @@ class System : public SystemBase {
return SystemConstraintIndex(constraints_.size() - 1);
}

//----------------------------------------------------------------------------
/// @name Virtual methods for input allocation
/// Authors of derived %Systems should override these methods to self-describe
/// acceptable inputs to the %System.
//@{

/// Allocates an input vector of the leaf type that the System requires on
/// the port specified by @p input_port. Caller owns the returned memory.
virtual BasicVector<T>* DoAllocateInputVector(
const InputPort<T>& input_port) const = 0;

/// Allocates an abstract input of the leaf type that the System requires on
/// the port specified by @p input_port. Caller owns the returned memory.
virtual AbstractValue* DoAllocateInputAbstract(
const InputPort<T>& input_port) const = 0;
//@}

//----------------------------------------------------------------------------
/// @name Virtual methods for calculations
/// These virtuals allow concrete systems to implement the calculations
Expand Down Expand Up @@ -2108,6 +2086,11 @@ class System : public SystemBase {
// Refer to SystemImpl comments for details.
friend class SystemImpl;

// Allocates an input of the leaf type that the System requires on the port
// specified by @p input_port. This is final in LeafSystem and Diagram.
virtual std::unique_ptr<AbstractValue> DoAllocateInput(
const InputPort<T>& input_port) const = 0;

// SystemBase override checks a Context of same type T.
void DoCheckValidContext(const ContextBase& context_base) const final {
const Context<T>* context = dynamic_cast<const Context<T>*>(&context_base);
Expand Down
16 changes: 12 additions & 4 deletions systems/framework/test/leaf_system_test.cc
Original file line number Diff line number Diff line change
Expand Up @@ -848,10 +848,19 @@ GTEST_TEST(ModelLeafSystemTest, ModelPortsTopology) {
}

// A system that incorrectly declares an input port.
//
// At some point, the deprecated DeclareAbstractInputPort overload used by this
// System will be removed. At that point, this entire test case should be
// removed, along with the code under test that its covering, because then all
// abstract input declarations require a model value, so it'll be impossible
// not to have one, so we won't need missing-model-value error handling.
class MissingModelAbstractInputSystem : public LeafSystem<double> {
public:
MissingModelAbstractInputSystem() {
#pragma GCC diagnostic push
#pragma GCC diagnostic ignored "-Wdeprecated-declarations"
this->DeclareAbstractInputPort("no_model_input");
#pragma GCC diagnostic pop // pop -Wdeprecated-declarations
}
};

Expand All @@ -862,9 +871,8 @@ GTEST_TEST(ModelLeafSystemTest, MissingModelAbstractInput) {
dut.AllocateInputAbstract(dut.get_input_port(0)),
std::exception,
"System::AllocateInputAbstract\\(\\): a System with abstract input "
"ports should pass a model_value to DeclareAbstractInputPort, or else "
"must override DoAllocateInputAbstract; the input port\\[0\\] named "
"'no_model_input' did not do either one \\(System ::dut\\)");
"ports must pass a model_value to DeclareAbstractInputPort; the "
"port\\[0\\] named 'no_model_input' did not do so \\(System ::dut\\)");
}

// Check that model inputs place validity checks on FixInput calls. (This is
Expand Down Expand Up @@ -1447,7 +1455,7 @@ class DefaultFeedthroughSystem : public LeafSystem<double> {
~DefaultFeedthroughSystem() override {}

void AddAbstractInputPort() {
this->DeclareAbstractInputPort(kUseDefaultName);
this->DeclareAbstractInputPort(kUseDefaultName, Value<std::string>{});
}

void AddAbstractOutputPort() {
Expand Down
4 changes: 3 additions & 1 deletion systems/framework/test/system_symbolic_inspector_test.cc
Original file line number Diff line number Diff line change
Expand Up @@ -35,7 +35,9 @@ class SparseSystem : public LeafSystem<symbolic::Expression> {
"inequality constraint");
}

void AddAbstractInputPort() { this->DeclareAbstractInputPort(); }
void AddAbstractInputPort() {
this->DeclareAbstractInputPort(kUseDefaultName, Value<std::string>{});
}

~SparseSystem() override {}

Expand Down
Loading

0 comments on commit b855580

Please sign in to comment.