Skip to content

Commit

Permalink
[systems] Add DiagramBuilder overloads for shared_ptr
Browse files Browse the repository at this point in the history
AddSystem and AddNamedSystem functions are overloaded to allow passing
the system via mutable shared_ptr (in addition to mutable unique_ptr).

Architecturally, the diagram still maintains exclusive ownership of
its children: each child still has a back-pointer to the Diagram (via
the SystemParentServiceInterface) so it's not possible to actually
"share" a subsystem across multiple diagrams. However, unique_ptr is
overly restrictive: it not only denotes exclusive ownership (which is
fine), but also demands that resource cleanup is `delete MyClass`
(which is insufficient for our Python bindings). We must use a smart
pointer type that allows customizing cleanup. We could imagine using
unique_ptr whose Deleter was a std::function, but it's simpler to just
use shared_ptr.

Relatedly, we also adjust the Diagram subclasses PidControlledSystem
and RgbdSensorDiscrete to accept the more general shared_ptr (instead
of unique_ptr) for their child systems and to use ref_cycle for their
pydrake bindings.
  • Loading branch information
jwnimmer-tri committed Jan 2, 2025
1 parent f19d31c commit 7b55dd6
Show file tree
Hide file tree
Showing 15 changed files with 248 additions and 97 deletions.
2 changes: 2 additions & 0 deletions bindings/pydrake/systems/BUILD.bazel
Original file line number Diff line number Diff line change
Expand Up @@ -121,6 +121,7 @@ drake_pybind_library(
"//bindings/pydrake:documentation_pybind",
"//bindings/pydrake:symbolic_types_pybind",
"//bindings/pydrake/common:deprecation_pybind",
"//bindings/pydrake/common:ref_cycle_pybind",
"//bindings/pydrake/common:wrap_pybind",
],
cc_srcs = ["controllers_py.cc"],
Expand Down Expand Up @@ -171,6 +172,7 @@ drake_pybind_library(
"//bindings/pydrake/common:cpp_template_pybind",
"//bindings/pydrake/common:default_scalars_pybind",
"//bindings/pydrake/common:eigen_pybind",
"//bindings/pydrake/common:ref_cycle_pybind",
"//bindings/pydrake/common:serialize_pybind",
"//bindings/pydrake/common:type_pack",
"//bindings/pydrake/common:value_pybind",
Expand Down
81 changes: 62 additions & 19 deletions bindings/pydrake/systems/controllers_py.cc
Original file line number Diff line number Diff line change
@@ -1,4 +1,5 @@
#include "drake/bindings/pydrake/common/deprecation_pybind.h"
#include "drake/bindings/pydrake/common/ref_cycle_pybind.h"
#include "drake/bindings/pydrake/common/wrap_pybind.h"
#include "drake/bindings/pydrake/documentation_pybind.h"
#include "drake/bindings/pydrake/pydrake_pybind.h"
Expand Down Expand Up @@ -180,40 +181,82 @@ PYBIND11_MODULE(controllers, m) {
}

{
using Class = PidControlledSystem<double>;
using T = double;
using Class = PidControlledSystem<T>;
constexpr auto& cls_doc = doc.PidControlledSystem;
py::class_<Class, Diagram<double>>(m, "PidControlledSystem", cls_doc.doc)
.def(py::init<std::unique_ptr<System<double>>, double, double, double,
int, int>(),
py::class_<Class, Diagram<T>>(m, "PidControlledSystem", cls_doc.doc)
.def(py::init([](System<T>& plant, double Kp, double Ki, double Kd,
int state_output_port_index,
int plant_input_port_index) {
return std::make_unique<Class>(
// The ref_cycle is responsible for object lifetime, so we'll give
// the constructor an unowned pointer.
std::shared_ptr<System<T>>(
/* managed object = */ std::shared_ptr<void>{},
/* stored pointer = */ &plant),
Kp, Ki, Kd, state_output_port_index, plant_input_port_index);
}),
py::arg("plant"), py::arg("kp"), py::arg("ki"), py::arg("kd"),
py::arg("state_output_port_index") = 0,
py::arg("plant_input_port_index") = 0,
// Keep alive, ownership: `plant` keeps `self` alive.
py::keep_alive<2, 1>(), cls_doc.ctor.doc_6args_double_gains)
.def(py::init<std::unique_ptr<System<double>>, const VectorX<double>&,
const VectorX<double>&, const VectorX<double>&, int, int>(),
// `self` and `plant` form a cycle as part of the Diagram.
internal::ref_cycle<1, 2>(), cls_doc.ctor.doc_6args_double_gains)
.def(py::init([](System<T>& plant, const Eigen::VectorXd& Kp,
const Eigen::VectorXd& Ki, const Eigen::VectorXd& Kd,
int state_output_port_index,
int plant_input_port_index) {
return std::make_unique<Class>(
// The ref_cycle is responsible for object lifetime, so we'll give
// the constructor an unowned pointer.
std::shared_ptr<System<T>>(
/* managed object = */ std::shared_ptr<void>{},
/* stored pointer = */ &plant),
Kp, Ki, Kd, state_output_port_index, plant_input_port_index);
}),
py::arg("plant"), py::arg("kp"), py::arg("ki"), py::arg("kd"),
py::arg("state_output_port_index") = 0,
py::arg("plant_input_port_index") = 0,
// Keep alive, ownership: `plant` keeps `self` alive.
py::keep_alive<2, 1>(), cls_doc.ctor.doc_6args_vector_gains)
.def(py::init<std::unique_ptr<System<double>>, const MatrixX<double>&,
double, double, double, int, int>(),
// `self` and `plant` form a cycle as part of the Diagram.
internal::ref_cycle<1, 2>(), cls_doc.ctor.doc_6args_vector_gains)
.def(py::init(
[](System<T>& plant, const MatrixX<double>& feedback_selector,
double Kp, double Ki, double Kd,
int state_output_port_index, int plant_input_port_index) {
return std::make_unique<Class>(
// The ref_cycle is responsible for object lifetime, so
// we'll give the constructor an unowned pointer.
std::shared_ptr<System<T>>(
/* managed object = */ std::shared_ptr<void>{},
/* stored pointer = */ &plant),
feedback_selector, Kp, Ki, Kd, state_output_port_index,
plant_input_port_index);
}),
py::arg("plant"), py::arg("feedback_selector"), py::arg("kp"),
py::arg("ki"), py::arg("kd"),
py::arg("state_output_port_index") = 0,
py::arg("plant_input_port_index") = 0,
// Keep alive, ownership: `plant` keeps `self` alive.
py::keep_alive<2, 1>(), cls_doc.ctor.doc_7args_double_gains)
.def(py::init<std::unique_ptr<System<double>>, const MatrixX<double>&,
const VectorX<double>&, const VectorX<double>&,
const VectorX<double>&, int, int>(),
// `self` and `plant` form a cycle as part of the Diagram.
internal::ref_cycle<1, 2>(), cls_doc.ctor.doc_7args_double_gains)
.def(py::init(
[](System<T>& plant, const MatrixX<double>& feedback_selector,
const Eigen::VectorXd& Kp, const Eigen::VectorXd& Ki,
const Eigen::VectorXd& Kd, int state_output_port_index,
int plant_input_port_index) {
return std::make_unique<Class>(
// The ref_cycle is responsible for object lifetime, so
// we'll give the constructor an unowned pointer.
std::shared_ptr<System<T>>(
/* managed object = */ std::shared_ptr<void>{},
/* stored pointer = */ &plant),
feedback_selector, Kp, Ki, Kd, state_output_port_index,
plant_input_port_index);
}),
py::arg("plant"), py::arg("feedback_selector"), py::arg("kp"),
py::arg("ki"), py::arg("kd"),
py::arg("state_output_port_index") = 0,
py::arg("plant_input_port_index") = 0,
// Keep alive, ownership: `plant` keeps `self` alive.
py::keep_alive<2, 1>(), cls_doc.ctor.doc_7args_vector_gains)
// `self` and `plant` form a cycle as part of the Diagram.
internal::ref_cycle<1, 2>(), cls_doc.ctor.doc_7args_vector_gains)
.def("get_control_input_port", &Class::get_control_input_port,
py_rvp::reference_internal, cls_doc.get_control_input_port.doc)
.def("get_state_input_port", &Class::get_state_input_port,
Expand Down
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
16 changes: 13 additions & 3 deletions bindings/pydrake/systems/sensors_py_rgbd.cc
Original file line number Diff line number Diff line change
@@ -1,3 +1,4 @@
#include "drake/bindings/pydrake/common/ref_cycle_pybind.h"
#include "drake/bindings/pydrake/documentation_pybind.h"
#include "drake/bindings/pydrake/systems/sensors_py.h"
#include "drake/systems/sensors/camera_info.h"
Expand Down Expand Up @@ -140,12 +141,21 @@ void DefineSensorsRgbd(py::module m) {
py::class_<RgbdSensorDiscrete, Diagram<double>> rgbd_camera_discrete(
m, "RgbdSensorDiscrete", doc.RgbdSensorDiscrete.doc);
rgbd_camera_discrete
.def(py::init<std::unique_ptr<RgbdSensor>, double, bool>(),
.def(py::init(
[](RgbdSensor& sensor, double period, bool render_label_image) {
return std::make_unique<RgbdSensorDiscrete>(
// The ref_cycle is responsible for object lifetime, so
// we'll give the constructor an unowned pointer.
std::shared_ptr<RgbdSensor>(
/* managed object = */ std::shared_ptr<void>{},
/* stored pointer = */ &sensor),
period, render_label_image);
}),
py::arg("sensor"),
py::arg("period") = double{RgbdSensorDiscrete::kDefaultPeriod},
py::arg("render_label_image") = true,
// Keep alive, ownership: `sensor` keeps `self` alive.
py::keep_alive<2, 1>(), doc.RgbdSensorDiscrete.ctor.doc)
// `self` and `sensor` form a cycle as part of the Diagram.
internal::ref_cycle<1, 2>(), doc.RgbdSensorDiscrete.ctor.doc)
// N.B. Since `camera` is already connected, we do not need additional
// `keep_alive`s.
.def("sensor", &RgbdSensorDiscrete::sensor, py_rvp::reference_internal,
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
10 changes: 5 additions & 5 deletions systems/controllers/pid_controlled_system.cc
Original file line number Diff line number Diff line change
Expand Up @@ -9,7 +9,7 @@ namespace systems {
namespace controllers {

template <typename T>
PidControlledSystem<T>::PidControlledSystem(std::unique_ptr<System<T>> plant,
PidControlledSystem<T>::PidControlledSystem(std::shared_ptr<System<T>> plant,
double Kp, double Ki, double Kd,
int state_output_port_index,
int plant_input_port_index)
Expand All @@ -26,7 +26,7 @@ PidControlledSystem<T>::PidControlledSystem(std::unique_ptr<System<T>> plant,
}

template <typename T>
PidControlledSystem<T>::PidControlledSystem(std::unique_ptr<System<T>> plant,
PidControlledSystem<T>::PidControlledSystem(std::shared_ptr<System<T>> plant,
const Eigen::VectorXd& Kp,
const Eigen::VectorXd& Ki,
const Eigen::VectorXd& Kd,
Expand All @@ -39,7 +39,7 @@ PidControlledSystem<T>::PidControlledSystem(std::unique_ptr<System<T>> plant,

template <typename T>
PidControlledSystem<T>::PidControlledSystem(
std::unique_ptr<System<T>> plant, const MatrixX<double>& feedback_selector,
std::shared_ptr<System<T>> plant, const MatrixX<double>& feedback_selector,
double Kp, double Ki, double Kd, int state_output_port_index,
int plant_input_port_index)
: state_output_port_index_(state_output_port_index),
Expand All @@ -53,7 +53,7 @@ PidControlledSystem<T>::PidControlledSystem(

template <typename T>
PidControlledSystem<T>::PidControlledSystem(
std::unique_ptr<System<T>> plant, const MatrixX<double>& feedback_selector,
std::shared_ptr<System<T>> plant, const MatrixX<double>& feedback_selector,
const Eigen::VectorXd& Kp, const Eigen::VectorXd& Ki,
const Eigen::VectorXd& Kd, int state_output_port_index,
int plant_input_port_index)
Expand All @@ -64,7 +64,7 @@ PidControlledSystem<T>::PidControlledSystem(

template <typename T>
void PidControlledSystem<T>::Initialize(
std::unique_ptr<System<T>> plant, const MatrixX<double>& feedback_selector,
std::shared_ptr<System<T>> plant, const MatrixX<double>& feedback_selector,
const Eigen::VectorXd& Kp, const Eigen::VectorXd& Ki,
const Eigen::VectorXd& Kd) {
DRAKE_DEMAND(plant != nullptr);
Expand Down
28 changes: 22 additions & 6 deletions systems/controllers/pid_controlled_system.h
Original file line number Diff line number Diff line change
Expand Up @@ -83,8 +83,12 @@ class PidControlledSystem : public Diagram<T> {
/// @param[in] plant_input_port_index identifies the input port on the plant
/// that takes in the input (computed as the output of the PID controller).
///
/// @warning a System (i.e., `plant`) may only be added to at most one Diagram
/// (i.e., this `PidControlledSystem`) so should not be re-used outside of the
/// `PidControlledSystem`.
///
/// @pydrake_mkdoc_identifier{6args_double_gains}
PidControlledSystem(std::unique_ptr<System<T>> plant, double Kp, double Ki,
PidControlledSystem(std::shared_ptr<System<T>> plant, double Kp, double Ki,
double Kd, int state_output_port_index = 0,
int plant_input_port_index = 0);

Expand All @@ -100,12 +104,16 @@ class PidControlledSystem : public Diagram<T> {
/// @param[in] plant_input_port_index identifies the input port on the plant
/// that takes in the input (computed as the output of the PID controller).
///
/// @warning a System (i.e., `plant`) may only be added to at most one Diagram
/// (i.e., this `PidControlledSystem`) so should not be re-used outside of the
/// `PidControlledSystem`.
///
/// @pydrake_mkdoc_identifier{6args_vector_gains}
PidControlledSystem(std::unique_ptr<System<T>> plant,
PidControlledSystem(std::shared_ptr<System<T>> plant,
const Eigen::VectorXd& Kp, const Eigen::VectorXd& Ki,
const Eigen::VectorXd& Kd,
int state_output_port_index = 0,
int plant_output_port_index = 0);
int plant_input_port_index = 0);

/// A constructor where the gains are scalar values and some of the plant's
/// output is part of the feedback signal as specified by
Expand All @@ -123,8 +131,12 @@ class PidControlledSystem : public Diagram<T> {
/// @param[in] plant_input_port_index identifies the input port on the plant
/// that takes in the input (computed as the output of the PID controller).
///
/// @warning a System (i.e., `plant`) may only be added to at most one Diagram
/// (i.e., this `PidControlledSystem`) so should not be re-used outside of the
/// `PidControlledSystem`.
///
/// @pydrake_mkdoc_identifier{7args_double_gains}
PidControlledSystem(std::unique_ptr<System<T>> plant,
PidControlledSystem(std::shared_ptr<System<T>> plant,
const MatrixX<double>& feedback_selector, double Kp,
double Ki, double Kd, int state_output_port_index = 0,
int plant_input_port_index = 0);
Expand All @@ -145,8 +157,12 @@ class PidControlledSystem : public Diagram<T> {
/// @param[in] plant_input_port_index identifies the input port on the plant
/// that takes in the input (computed as the output of the PID controller).
///
/// @warning a System (i.e., `plant`) may only be added to at most one Diagram
/// (i.e., this `PidControlledSystem`) so should not be re-used outside of the
/// `PidControlledSystem`.
///
/// @pydrake_mkdoc_identifier{7args_vector_gains}
PidControlledSystem(std::unique_ptr<System<T>> plant,
PidControlledSystem(std::shared_ptr<System<T>> plant,
const MatrixX<double>& feedback_selector,
const Eigen::VectorXd& Kp, const Eigen::VectorXd& Ki,
const Eigen::VectorXd& Kd,
Expand Down Expand Up @@ -229,7 +245,7 @@ class PidControlledSystem : public Diagram<T> {
// A helper function for the constructors. This is necessary to avoid seg
// faults caused by simultaneously moving the plant and calling methods on
// the plant when one constructor delegates to another constructor.
void Initialize(std::unique_ptr<System<T>> plant,
void Initialize(std::shared_ptr<System<T>> plant,
const MatrixX<double>& feedback_selector,
const Eigen::VectorXd& Kp, const Eigen::VectorXd& Ki,
const Eigen::VectorXd& Kd);
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
Loading

0 comments on commit 7b55dd6

Please sign in to comment.