Skip to content

Commit

Permalink
[systems] Add DiagramBuilder overloads for shared_ptr
Browse files Browse the repository at this point in the history
  • Loading branch information
jwnimmer-tri committed Dec 23, 2024
1 parent 6848228 commit c8d03fb
Show file tree
Hide file tree
Showing 8 changed files with 135 additions and 62 deletions.
18 changes: 13 additions & 5 deletions bindings/pydrake/systems/framework_py_semantics.cc
Original file line number Diff line number Diff line change
Expand Up @@ -598,26 +598,34 @@ void DoDefineFrameworkDiagramBuilder(py::module m) {
.def(py::init<>(), doc.DiagramBuilder.ctor.doc)
.def(
"AddSystem",
[](DiagramBuilder<T>* self, unique_ptr<System<T>> system) {
[](DiagramBuilder<T>* self, System<T>& system) {
// Using BuilderLifeSupport::stash makes the builder
// temporarily immortal (uncollectible self cycle). This will be
// resolved by the Build() step. See BuilderLifeSupport for
// rationale.
BuilderLifeSupport<T>::stash(self);
return self->AddSystem(std::move(system));
// The ref_cycle is responsible for object lifetime, so we'll give
// the DiagramBuilder an unowned pointer.
return self->AddSystem(std::shared_ptr<System<T>>(
/* managed object = */ std::shared_ptr<void>{},
/* stored pointer = */ &system));
},
py::arg("system"), internal::ref_cycle<1, 2>(),
doc.DiagramBuilder.AddSystem.doc)
.def(
"AddNamedSystem",
[](DiagramBuilder<T>* self, std::string& name,
unique_ptr<System<T>> system) {
[](DiagramBuilder<T>* self, std::string& name, System<T>& system) {
// Using BuilderLifeSupport::stash makes the builder
// temporarily immortal (uncollectible self cycle). This will be
// resolved by the Build() step. See BuilderLifeSupport for
// rationale.
BuilderLifeSupport<T>::stash(self);
return self->AddNamedSystem(name, std::move(system));
// The ref_cycle is responsible for object lifetime, so we'll give
// the DiagramBuilder an unowned pointer.
return self->AddNamedSystem(
name, std::shared_ptr<System<T>>(
/* managed object = */ std::shared_ptr<void>{},
/* stored pointer = */ &system));
},
py::arg("name"), py::arg("system"), internal::ref_cycle<1, 3>(),
doc.DiagramBuilder.AddNamedSystem.doc)
Expand Down
15 changes: 9 additions & 6 deletions bindings/pydrake/systems/test/lifetime_test.py
Original file line number Diff line number Diff line change
Expand Up @@ -71,15 +71,18 @@ def test_ownership_diagram(self):
def test_ownership_multiple_containers(self):
info = Info()
system = DeleteListenerSystem(info.record_deletion)

# Add the system to a built diagram.
builder_1 = DiagramBuilder()
builder_2 = DiagramBuilder()
builder_1.AddSystem(system)
# This is tested in our fork of `pybind11`, but echoed here for when
# we decide to switch to use `shared_ptr`.
with self.assertRaises(RuntimeError):
# This should throw an error from `pybind11`, since two containers
# are trying to own a unique_ptr-held object.
diagram_1 = builder_1.Build()

# Add it again to another diagram. We don't care if the Add fails or
# the Build fails, so long as one of them does.
builder_2 = DiagramBuilder()
with self.assertRaisesRegex(Exception, "already.*different Diagram"):
builder_2.AddSystem(system)
builder_2.Build()

def test_ownership_simulator(self):
info = Info()
Expand Down
4 changes: 2 additions & 2 deletions systems/framework/diagram.h
Original file line number Diff line number Diff line change
Expand Up @@ -51,15 +51,15 @@ class OwnedSystems {
decltype(auto) end() const { return vec_.end(); }
decltype(auto) operator[](size_t i) const { return vec_[i]; }
decltype(auto) operator[](size_t i) { return vec_[i]; }
void push_back(std::unique_ptr<System<T>>&& sys) {
void push_back(std::shared_ptr<System<T>>&& sys) {
vec_.push_back(std::move(sys));
}
void pop_back() {
vec_.pop_back();
}

private:
std::vector<std::unique_ptr<System<T>>> vec_;
std::vector<std::shared_ptr<System<T>>> vec_;
};

// External life support data for the diagram. The data will be moved to the
Expand Down
21 changes: 20 additions & 1 deletion systems/framework/diagram_builder.cc
Original file line number Diff line number Diff line change
Expand Up @@ -45,7 +45,7 @@ void DiagramBuilder<T>::RemoveSystem(const System<T>& system) {
const size_t system_index = std::distance(
registered_systems_.begin(),
std::find_if(registered_systems_.begin(), registered_systems_.end(),
[&system](const std::unique_ptr<System<T>>& item) {
[&system](const std::shared_ptr<System<T>>& item) {
return item.get() == &system;
}));
DRAKE_DEMAND(system_index < registered_systems_.size());
Expand Down Expand Up @@ -443,6 +443,25 @@ void DiagramBuilder<T>::ThrowIfAlreadyBuilt() const {
}
}

template <typename T>
void DiagramBuilder<T>::AddSystemImpl(std::shared_ptr<System<T>>&& system) {
DRAKE_THROW_UNLESS(system != nullptr);
ThrowIfAlreadyBuilt();
if (system->get_name().empty()) {
system->set_name(system->GetMemoryObjectName());
}
systems_.insert(system.get());
registered_systems_.push_back(std::move(system));
}

template <typename T>
void DiagramBuilder<T>::AddNamedSystemImpl(
const std::string& name, std::shared_ptr<System<T>>&& system) {
DRAKE_THROW_UNLESS(system != nullptr);
system->set_name(name);
this->AddSystemImpl(std::move(system));
}

template <typename T>
void DiagramBuilder<T>::ThrowIfInputAlreadyWired(
const InputPortLocator& id) const {
Expand Down
97 changes: 57 additions & 40 deletions systems/framework/diagram_builder.h
Original file line number Diff line number Diff line change
Expand Up @@ -77,29 +77,36 @@ class DiagramBuilder {
DiagramBuilder();
virtual ~DiagramBuilder();

/// Takes ownership of @p system and adds it to the builder. Returns a bare
/// Takes ownership of `system` and adds it to the builder. Returns a bare
/// pointer to the System, which will remain valid for the lifetime of the
/// Diagram built by this builder.
///
/// If the system's name is unset, sets it to System::GetMemoryObjectName()
/// as a default in order to have unique names within the diagram.
///
/// @code
/// DiagramBuilder<T> builder;
/// auto foo = builder.AddSystem(std::make_unique<Foo<T>>());
/// @endcode
/// @warning a System may only be added to at most one DiagramBuilder.
/// Multiple Diagram instances cannot share the same System.
template<class S>
S* AddSystem(std::shared_ptr<S> system) {
S* result = system.get();
this->AddSystemImpl(std::move(system));
return result;
}

/// Takes ownership of `system` and adds it to the builder. Returns a bare
/// pointer to the System, which will remain valid for the lifetime of the
/// Diagram built by this builder.
///
/// @tparam S The type of system to add.
/// If the system's name is unset, sets it to System::GetMemoryObjectName()
/// as a default in order to have unique names within the diagram.
///
/// @exclude_from_pydrake_mkdoc{Not bound in pydrake -- pydrake only uses the
/// shared_ptr overload.}
template<class S>
S* AddSystem(std::unique_ptr<S> system) {
ThrowIfAlreadyBuilt();
if (system->get_name().empty()) {
system->set_name(system->GetMemoryObjectName());
}
S* raw_sys_ptr = system.get();
systems_.insert(raw_sys_ptr);
registered_systems_.push_back(std::move(system));
return raw_sys_ptr;
S* result = system.get();
this->AddSystemImpl(std::move(system));
return result;
}

/// Constructs a new system with the given @p args, and adds it to the
Expand All @@ -119,17 +126,16 @@ class DiagramBuilder {
/// auto foo = builder.template AddSystem<Foo<T>>("name", 3.14);
/// @endcode
///
/// You may prefer the `unique_ptr` variant instead.
///
///
/// @tparam S The type of System to construct. Must subclass System<T>.
///
/// @exclude_from_pydrake_mkdoc{Not bound in pydrake -- emplacement while
/// specifying <T> doesn't make sense for that language.}
template<class S, typename... Args>
S* AddSystem(Args&&... args) {
ThrowIfAlreadyBuilt();
return AddSystem(std::make_unique<S>(std::forward<Args>(args)...));
auto system = std::make_shared<S>(std::forward<Args>(args)...);
S* result = system.get();
this->AddSystemImpl(std::move(system));
return result;
}

/// Constructs a new system with the given @p args, and adds it to the
Expand All @@ -150,35 +156,40 @@ class DiagramBuilder {
/// auto foo = builder.template AddSystem<Foo>("name", 3.14);
/// @endcode
///
/// You may prefer the `unique_ptr` variant instead.
///
/// @tparam S A template for the type of System to construct. The template
/// will be specialized on the scalar type T of this builder.
///
/// @exclude_from_pydrake_mkdoc{Not bound in pydrake -- emplacement while
/// specifying <T> doesn't make sense for that language.}
template<template<typename Scalar> class S, typename... Args>
S<T>* AddSystem(Args&&... args) {
ThrowIfAlreadyBuilt();
return AddSystem(std::make_unique<S<T>>(std::forward<Args>(args)...));
auto system = std::make_shared<S<T>>(std::forward<Args>(args)...);
S<T>* result = system.get();
this->AddSystemImpl(std::move(system));
return result;
}

/// Takes ownership of @p system, applies @p name to it, and adds it to the
/// Takes ownership of `system`, set its name to `name`, and adds it to the
/// builder. Returns a bare pointer to the System, which will remain valid
/// for the lifetime of the Diagram built by this builder.
///
/// @code
/// DiagramBuilder<T> builder;
/// auto bar = builder.AddNamedSystem("bar", std::make_unique<Bar<T>>());
/// @endcode
///
/// @tparam S The type of system to add.
/// @post The system's name is @p name.
/// @warning a System may only be added to at most one DiagramBuilder.
/// Multiple Diagram instances cannot share the same System.
template<class S>
S* AddNamedSystem(const std::string& name, std::shared_ptr<S> system) {
S* result = system.get();
this->AddNamedSystemImpl(name, std::move(system));
return result;
}

/// Takes ownership of `system`, set its name to `name`, and adds it to the
/// builder. Returns a bare pointer to the System, which will remain valid
/// for the lifetime of the Diagram built by this builder.
template<class S>
S* AddNamedSystem(const std::string& name, std::unique_ptr<S> system) {
ThrowIfAlreadyBuilt();
system->set_name(name);
return AddSystem(std::move(system));
S* result = system.get();
this->AddNamedSystemImpl(name, std::move(system));
return result;
}

/// Constructs a new system with the given @p args, applies @p name to it,
Expand Down Expand Up @@ -207,9 +218,10 @@ class DiagramBuilder {
/// specifying <T> doesn't make sense for that language.}
template<class S, typename... Args>
S* AddNamedSystem(const std::string& name, Args&&... args) {
ThrowIfAlreadyBuilt();
return AddNamedSystem(
name, std::make_unique<S>(std::forward<Args>(args)...));
auto system = std::make_shared<S>(std::forward<Args>(args)...);
S* result = system.get();
this->AddNamedSystemImpl(name, std::move(system));
return result;
}

/// Constructs a new system with the given @p args, applies @p name to it,
Expand Down Expand Up @@ -240,9 +252,10 @@ class DiagramBuilder {
/// specifying <T> doesn't make sense for that language.}
template<template<typename Scalar> class S, typename... Args>
S<T>* AddNamedSystem(const std::string& name, Args&&... args) {
ThrowIfAlreadyBuilt();
return AddNamedSystem(
name, std::make_unique<S<T>>(std::forward<Args>(args)...));
auto system = std::make_shared<S<T>>(std::forward<Args>(args)...);
S<T>* result = system.get();
this->AddNamedSystemImpl(name, std::move(system));
return result;
}

/// Removes the given system from this builder and disconnects any connections
Expand Down Expand Up @@ -490,6 +503,10 @@ class DiagramBuilder {

void ThrowIfAlreadyBuilt() const;

void AddSystemImpl(std::shared_ptr<System<T>>&& system);
void AddNamedSystemImpl(const std::string& name,
std::shared_ptr<System<T>>&& system);

// Throws if the given input port (belonging to a child subsystem) has
// already been connected to an output port, or exported to be an input
// port of the whole diagram.
Expand Down
15 changes: 15 additions & 0 deletions systems/framework/system_base.cc
Original file line number Diff line number Diff line change
Expand Up @@ -425,6 +425,21 @@ void SystemBase::CreateSourceTrackers(ContextBase* context_ptr) const {
}
}

void SystemBase::set_parent_service(
SystemBase* child,
const internal::SystemParentServiceInterface* parent_service) {
DRAKE_DEMAND(child != nullptr);
DRAKE_DEMAND(parent_service != nullptr);
if (child->parent_service_ != nullptr) {
throw std::logic_error(fmt::format(
"Cannot build subsystem '{}' into Diagram '{}' because it has already "
"been built into a different Diagram '{}'",
child->GetSystemName(), parent_service->GetParentPathname(),
child->parent_service_->GetParentPathname()));
}
child->parent_service_ = parent_service;
}

// The only way for a system to evaluate its own input port is if that
// port is fixed. In that case the port's value is in the corresponding
// subcontext and we can just return it. Otherwise, the port obtains its value
Expand Down
11 changes: 3 additions & 8 deletions systems/framework/system_base.h
Original file line number Diff line number Diff line change
Expand Up @@ -1098,19 +1098,14 @@ class SystemBase : public internal::SystemMessageInterface {
bool IsObviouslyNotInputDependent(DependencyTicket dependency_ticket) const;

/** (Internal use only) Declares that `parent_service` is the service
interface of the Diagram that owns this subsystem. Aborts if the parent
service has already been set to something else. */
interface of the Diagram that owns this subsystem. Throws if the parent
service has already been set. */
// Use static method so Diagram can invoke this on behalf of a child.
// Output argument is listed first because it is serving as the 'this'
// pointer here.
static void set_parent_service(
SystemBase* child,
const internal::SystemParentServiceInterface* parent_service) {
DRAKE_DEMAND(child != nullptr && parent_service != nullptr);
DRAKE_DEMAND(child->parent_service_ == nullptr ||
child->parent_service_ == parent_service);
child->parent_service_ = parent_service;
}
const internal::SystemParentServiceInterface* parent_service);

/** (Internal use only) Given a `port_index`, returns a function to be called
when validating Context::FixInputPort requests. The function should attempt
Expand Down
16 changes: 16 additions & 0 deletions systems/framework/test/diagram_builder_test.cc
Original file line number Diff line number Diff line change
Expand Up @@ -132,6 +132,22 @@ GTEST_TEST(DiagramBuilderTest, AlreadyBuilt) {
".*DiagramBuilder may no longer be used.*");
}

// Integration test of the Digram <=> System <=> SystemBase interaction when the
// same System is added to multiple diagrams.
GTEST_TEST(DiagramBuilderTest, AddSystemToMultipleDiagrams) {
auto adder = std::make_shared<Adder<double>>(1 /* inputs */, 1 /* size */);

DiagramBuilder<double> builder_1;
builder_1.AddSystem(adder);
std::unique_ptr<Diagram<double>> diagram_1;
EXPECT_NO_THROW(diagram_1 = builder_1.Build());

DiagramBuilder<double> builder_2;
builder_2.AddSystem(adder);
DRAKE_EXPECT_THROWS_MESSAGE(builder_2.Build(),
".*already.*different Diagram.*");
}

// A special class to distinguish between cycles and algebraic loops. The system
// has one input and two outputs. One output simply "echoes" the input (direct
// feedthrough). The other output merely outputs a const value. That means, the
Expand Down

0 comments on commit c8d03fb

Please sign in to comment.