DiagramBuilder is a factory class for Diagram.
It is single use: after calling Build or BuildInto, DiagramBuilder gives up ownership of the constituent systems, and should therefore be discarded; all member functions will throw an exception after this point.
When a Diagram (or DiagramBuilder) that owns systems is destroyed, the systems will be destroyed in the reverse of the order they were added.
A system must be added to the DiagramBuilder with AddSystem or AddNamedSystem before it can be wired up in any way. Every system must have a unique, non-empty name.
When building large Diagrams with many added systems and input-output port connections, the runtime performance of DiagramBuilder::Build() might become relevant.
As part of its correctness checks, the DiagramBuilder::Build() function performs a graph search of the diagram's dependencies. In the graph, the nodes are the child systems that have been added to the diagram, and the edges are the diagram connections from one child's output port to another child's input port(s). The builder must confirm that the graph is acyclic; a cycle would imply an infinite loop in an output calculation function. With a large graph, this check can be computationally expensive. To speed it up, ensure that your output ports do not gratuitously depend on irrelevant input ports.
The dependencies are supplied via the prerequisites_of_calc
argument to DeclareOutputPort family of functions. If the default value is used (i.e., when no prerequisites are provided), the default is to assume the output port value is dependent on all possible sources.
Refer to the Direct feedthrough documentation for additional details and examples. In particular, the SystemBase::all_sources_except_input_ports_ticket() is a convenient shortcut for outputs that do not depend on any inputs.
#include <drake/systems/framework/diagram_builder.h>
Public Types | |
using | InputPortLocator = typename Diagram< T >::InputPortLocator |
A designator for a "system + input port" pair, to uniquely refer to some input port on one of this builder's subsystems. More... | |
using | OutputPortLocator = typename Diagram< T >::OutputPortLocator |
A designator for a "system + output port" pair, to uniquely refer to some output port on one of this builder's subsystems. More... | |
Public Member Functions | |
DiagramBuilder () | |
virtual | ~DiagramBuilder () |
template<class S > | |
S * | AddSystem (std::unique_ptr< S > system) |
Takes ownership of system and adds it to the builder. More... | |
template<class S , typename... Args> | |
S * | AddSystem (Args &&... args) |
Constructs a new system with the given args , and adds it to the builder, which retains ownership. More... | |
template<template< typename Scalar > class S, typename... Args> | |
S< T > * | AddSystem (Args &&... args) |
Constructs a new system with the given args , and adds it to the builder, which retains ownership. More... | |
template<class S > | |
S * | AddNamedSystem (const std::string &name, std::unique_ptr< S > system) |
Takes ownership of system , applies name to it, and adds it to the builder. More... | |
template<class S , typename... Args> | |
S * | AddNamedSystem (const std::string &name, Args &&... args) |
Constructs a new system with the given args , applies name to it, and adds it to the builder, which retains ownership. More... | |
template<template< typename Scalar > class S, typename... Args> | |
S< T > * | AddNamedSystem (const std::string &name, Args &&... args) |
Constructs a new system with the given args , applies name to it, and adds it to the builder, which retains ownership. More... | |
void | RemoveSystem (const System< T > &system) |
Removes the given system from this builder and disconnects any connections or exported ports associated with it. More... | |
bool | empty () const |
Returns whether any Systems have been added yet. More... | |
bool | already_built () const |
Returns true iff Build() or BuildInto() has been called on this Builder, in which case it's an error to call any member function other than the the destructor. More... | |
std::vector< const System< T > * > | GetSystems () const |
Returns the list of contained Systems. More... | |
std::vector< System< T > * > | GetMutableSystems () |
Returns the list of contained Systems. More... | |
bool | HasSubsystemNamed (std::string_view name) const |
Returns true iff this contains a subsystem with the given name. More... | |
const System< T > & | GetSubsystemByName (std::string_view name) const |
Retrieves a const reference to the subsystem with name name returned by get_name(). More... | |
System< T > & | GetMutableSubsystemByName (std::string_view name) |
Retrieves a mutable reference to the subsystem with name name returned by get_name(). More... | |
template<template< typename > class MySystem> | |
const MySystem< T > & | GetDowncastSubsystemByName (std::string_view name) const |
Retrieves a const reference to the subsystem with name name returned by get_name(), downcast to the type provided as a template argument. More... | |
template<template< typename > class MySystem> | |
MySystem< T > & | GetMutableDowncastSubsystemByName (std::string_view name) |
Retrieves a mutable reference to the subsystem with name name returned by get_name(), downcast to the type provided as a template argument. More... | |
const std::map< InputPortLocator, OutputPortLocator > & | connection_map () const |
(Advanced) Returns a reference to the map of connections between Systems. More... | |
void | Connect (const OutputPort< T > &src, const InputPort< T > &dest) |
Declares that input port dest is connected to output port src . More... | |
void | Connect (const System< T > &src, const System< T > &dest) |
Declares that sole input port on the dest system is connected to sole output port on the src system. More... | |
void | Cascade (const System< T > &src, const System< T > &dest) |
Cascades src and dest . More... | |
InputPortIndex | ExportInput (const InputPort< T > &input, std::variant< std::string, UseDefaultName > name=kUseDefaultName) |
Declares that the given input port of a constituent system is connected to a new input to the entire Diagram. More... | |
void | ConnectInput (std::string_view diagram_port_name, const InputPort< T > &input) |
Connects an input to the entire Diagram, indicated by diagram_port_name , to the given input port of a constituent system. More... | |
void | ConnectInput (InputPortIndex diagram_port_index, const InputPort< T > &input) |
Connects an input to the entire Diagram, indicated by diagram_port_index , to the given input port of a constituent system. More... | |
bool | ConnectToSame (const InputPort< T > &exemplar, const InputPort< T > &dest) |
Connects dest to the same source as exemplar is connected to. More... | |
OutputPortIndex | ExportOutput (const OutputPort< T > &output, std::variant< std::string, UseDefaultName > name=kUseDefaultName) |
Declares that the given output port of a constituent system is an output of the entire diagram. More... | |
std::unique_ptr< Diagram< T > > | Build () |
Builds the Diagram that has been described by the calls to Connect, ExportInput, and ExportOutput. More... | |
void | BuildInto (Diagram< T > *target) |
Configures target to have the topology that has been described by the calls to Connect, ExportInput, and ExportOutput. More... | |
bool | IsConnectedOrExported (const InputPort< T > &port) const |
Returns true iff the given input port of a constituent system is either connected to another constituent system or exported as a diagram input. More... | |
int | num_input_ports () const |
Returns the current number of diagram input ports. More... | |
int | num_output_ports () const |
Returns the current number of diagram output outputs. More... | |
Does not allow copy, move, or assignment | |
DiagramBuilder (const DiagramBuilder &)=delete | |
DiagramBuilder & | operator= (const DiagramBuilder &)=delete |
DiagramBuilder (DiagramBuilder &&)=delete | |
DiagramBuilder & | operator= (DiagramBuilder &&)=delete |
using InputPortLocator = typename Diagram<T>::InputPortLocator |
A designator for a "system + input port" pair, to uniquely refer to some input port on one of this builder's subsystems.
using OutputPortLocator = typename Diagram<T>::OutputPortLocator |
A designator for a "system + output port" pair, to uniquely refer to some output port on one of this builder's subsystems.
|
delete |
|
delete |
DiagramBuilder | ( | ) |
|
virtual |
S* AddNamedSystem | ( | const std::string & | name, |
std::unique_ptr< S > | system | ||
) |
Takes ownership of system
, applies name
to it, 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.
S | The type of system to add. |
name
. S* AddNamedSystem | ( | const std::string & | name, |
Args &&... | args | ||
) |
Constructs a new system with the given args
, applies name
to it, and adds it to the builder, which retains ownership.
Returns a bare pointer to the System, which will remain valid for the lifetime of the Diagram built by this builder.
Note that for dependent names you must use the template keyword:
You may prefer the unique_ptr
variant instead.
S | The type of System to construct. Must subclass System<T>. |
name
. S<T>* AddNamedSystem | ( | const std::string & | name, |
Args &&... | args | ||
) |
Constructs a new system with the given args
, applies name
to it, and adds it to the builder, which retains ownership.
Returns a bare pointer to the System, which will remain valid for the lifetime of the Diagram built by this builder.
Note that for dependent names you must use the template keyword:
You may prefer the unique_ptr
variant instead.
S | A template for the type of System to construct. The template will be specialized on the scalar type T of this builder. |
name
. S* AddSystem | ( | std::unique_ptr< S > | system | ) |
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.
S | The type of system to add. |
S* AddSystem | ( | Args &&... | args | ) |
Constructs a new system with the given args
, and adds it to the builder, which retains ownership.
Returns a bare pointer to the System, which will remain valid for the lifetime of the Diagram built by this builder.
Note that for dependent names you must use the template keyword:
You may prefer the unique_ptr
variant instead.
S | The type of System to construct. Must subclass System<T>. |
S<T>* AddSystem | ( | Args &&... | args | ) |
Constructs a new system with the given args
, and adds it to the builder, which retains ownership.
Returns a bare pointer to the System, which will remain valid for the lifetime of the Diagram built by this builder.
Note that for dependent names you must use the template keyword:
You may prefer the unique_ptr
variant instead.
S | A template for the type of System to construct. The template will be specialized on the scalar type T of this builder. |
bool already_built | ( | ) | const |
Returns true iff Build() or BuildInto() has been called on this Builder, in which case it's an error to call any member function other than the the destructor.
std::unique_ptr<Diagram<T> > Build | ( | ) |
Builds the Diagram that has been described by the calls to Connect, ExportInput, and ExportOutput.
std::exception | if the graph is not buildable. |
See Building large Diagrams for tips on improving runtime performance of this function.
void BuildInto | ( | Diagram< T > * | target | ) |
Configures target
to have the topology that has been described by the calls to Connect, ExportInput, and ExportOutput.
std::exception | if the graph is not buildable. |
Only Diagram subclasses should call this method. The target must not already be initialized.
Cascades src
and dest
.
The sole input port on the dest
system is connected to sole output port on the src
system.
std::exception | if the sole-port precondition is not met (i.e., if dest has no input ports, or dest has more than one input port, or src has no output ports, or src has more than one output port). |
void Connect | ( | const OutputPort< T > & | src, |
const InputPort< T > & | dest | ||
) |
Declares that input port dest
is connected to output port src
.
src
and dest
via a call to this method can be effectively overridden by any subsequent call to InputPort::FixValue(). That is, calling InputPort::FixValue() on an already connected input port causes the resultant FixedInputPortValue to override any other value present on that port. Declares that sole input port on the dest
system is connected to sole output port on the src
system.
This function ignores deprecated ports, unless there is only one port in which case it will use the deprecated port.
src
and dest
via a call to this method can be effectively overridden by any subsequent call to InputPort::FixValue(). That is, calling InputPort::FixValue() on an already connected input port causes the resultant FixedInputPortValue to override any other value present on that port. std::exception | if the sole-port precondition is not met (i.e., if dest has no input ports, or dest has more than one input port, or src has no output ports, or src has more than one output port). |
void ConnectInput | ( | std::string_view | diagram_port_name, |
const InputPort< T > & | input | ||
) |
Connects an input to the entire Diagram, indicated by diagram_port_name
, to the given input
port of a constituent system.
diagram_port_name
must have been previously built via ExportInput(). input
is connected to the indicated Diagram input port. void ConnectInput | ( | InputPortIndex | diagram_port_index, |
const InputPort< T > & | input | ||
) |
Connects an input to the entire Diagram, indicated by diagram_port_index
, to the given input
port of a constituent system.
diagram_port_index
must have been previously built via ExportInput(). input
is connected to the indicated Diagram input port. const std::map<InputPortLocator, OutputPortLocator>& connection_map | ( | ) | const |
(Advanced) Returns a reference to the map of connections between Systems.
The reference becomes invalid upon any call to Build or BuildInto.
Connects dest
to the same source as exemplar
is connected to.
If exemplar
was connected to an output port, then dest
is connected to that same output. Or, if exemplar
was exported as an input of this diagram, then dest
will be connected to that same diagram input. Or, if exemplar
was neither connected or exported, then this function is a no-op.
Both exemplar
and dest
must be ports of constituent systems that have already been added to this diagram.
bool empty | ( | ) | const |
Returns whether any Systems have been added yet.
InputPortIndex ExportInput | ( | const InputPort< T > & | input, |
std::variant< std::string, UseDefaultName > | name = kUseDefaultName |
||
) |
Declares that the given input
port of a constituent system is connected to a new input to the entire Diagram.
name
is an optional name for the new input port; if it is unspecified, then a default name will be provided.
name
must not be empty. name
must not exist. input
is connected to the new exported input port. OutputPortIndex ExportOutput | ( | const OutputPort< T > & | output, |
std::variant< std::string, UseDefaultName > | name = kUseDefaultName |
||
) |
Declares that the given output
port of a constituent system is an output of the entire diagram.
name
is an optional name for the output port; if it is unspecified, then a default name will be provided.
name
must not be empty. const MySystem<T>& GetDowncastSubsystemByName | ( | std::string_view | name | ) | const |
Retrieves a const reference to the subsystem with name name
returned by get_name(), downcast to the type provided as a template argument.
MySystem | is the downcast type, e.g., drake::systems::Adder |
std::exception | if a unique match cannot be found. |
MySystem<T>& GetMutableDowncastSubsystemByName | ( | std::string_view | name | ) |
Retrieves a mutable reference to the subsystem with name name
returned by get_name(), downcast to the type provided as a template argument.
MySystem | is the downcast type, e.g., drake::systems::Adder |
std::exception | if a unique match cannot be found. |
System<T>& GetMutableSubsystemByName | ( | std::string_view | name | ) |
Retrieves a mutable reference to the subsystem with name name
returned by get_name().
std::exception | if a unique match cannot be found. |
std::vector<System<T>*> GetMutableSystems | ( | ) |
Returns the list of contained Systems.
const System<T>& GetSubsystemByName | ( | std::string_view | name | ) | const |
Retrieves a const reference to the subsystem with name name
returned by get_name().
std::exception | if a unique match cannot be found. |
std::vector<const System<T>*> GetSystems | ( | ) | const |
Returns the list of contained Systems.
bool HasSubsystemNamed | ( | std::string_view | name | ) | const |
Returns true iff this contains a subsystem with the given name.
bool IsConnectedOrExported | ( | const InputPort< T > & | port | ) | const |
Returns true iff the given input port
of a constituent system is either connected to another constituent system or exported as a diagram input.
int num_input_ports | ( | ) | const |
Returns the current number of diagram input ports.
The count may change as more ports are exported.
int num_output_ports | ( | ) | const |
Returns the current number of diagram output outputs.
The count may change as more ports are exported.
|
delete |
|
delete |
void RemoveSystem | ( | const System< T > & | system | ) |
Removes the given system from this builder and disconnects any connections or exported ports associated with it.
Note that un-exporting this system's ports might have a ripple effect on other exported port index assignments. The relative order will remain intact, but any "holes" created by this removal will be filled in by decrementing the indices of all higher-numbered ports that remain.