Drake
DiagramBuilder< T > Class Template Reference

Detailed Description

template<typename T>
class drake::systems::DiagramBuilder< T >

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.

A system must be added to the DiagramBuilder with AddSystem before it can be wired up in any way. Every system must have a unique, non-empty name.

#include <drake/systems/framework/diagram_builder.h>

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...
 
bool empty () const
 Returns whether any Systems have been added yet. More...
 
std::vector< systems::System< T > * > GetMutableSystems ()
 Returns the list of contained 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, variant< std::string, UseDefaultName > name=kUseDefaultName)
 Declares that the given input port of a constituent system is an input to the entire Diagram. More...
 
OutputPortIndex ExportOutput (const OutputPort< T > &output, 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...
 
Does not allow copy, move, or assignment
 DiagramBuilder (const DiagramBuilder &)=delete
 
DiagramBuilderoperator= (const DiagramBuilder &)=delete
 
 DiagramBuilder (DiagramBuilder &&)=delete
 
DiagramBuilderoperator= (DiagramBuilder &&)=delete
 

Friends

int AddRandomInputs (double, systems::DiagramBuilder< double > *)
 For each subsystem input port in builder that is (a) not yet connected and (b) labeled as random in the InputPort, this method will add a new RandomSource system of the appropriate type and connect it to the subsystem input port. More...
 

Constructor & Destructor Documentation

◆ DiagramBuilder() [1/3]

DiagramBuilder ( const DiagramBuilder< T > &  )
delete

◆ DiagramBuilder() [2/3]

DiagramBuilder ( DiagramBuilder< T > &&  )
delete

◆ DiagramBuilder() [3/3]

◆ ~DiagramBuilder()

virtual ~DiagramBuilder ( )
virtual

Member Function Documentation

◆ AddSystem() [1/3]

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.

DiagramBuilder<T> builder;
auto foo = builder.AddSystem(std::make_unique<Foo<T>>());
Template Parameters
SThe type of system to add.

◆ AddSystem() [2/3]

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.

DiagramBuilder<double> builder;
auto foo = builder.AddSystem<Foo<double>>("name", 3.14);

Note that for dependent names you must use the template keyword:

DiagramBuilder<T> builder;
auto foo = builder.template AddSystem<Foo<T>>("name", 3.14);

You may prefer the unique_ptr variant instead.

Template Parameters
SThe type of System to construct. Must subclass System<T>.

◆ AddSystem() [3/3]

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.

DiagramBuilder<double> builder;
// Foo must be a template.
auto foo = builder.AddSystem<Foo>("name", 3.14);

Note that for dependent names you must use the template keyword:

DiagramBuilder<T> builder;
auto foo = builder.template AddSystem<Foo>("name", 3.14);

You may prefer the unique_ptr variant instead.

Template Parameters
SA template for the type of System to construct. The template will be specialized on the scalar type T of this builder.

◆ Build()

std::unique_ptr<Diagram<T> > Build ( void  )

Builds the Diagram that has been described by the calls to Connect, ExportInput, and ExportOutput.

Exceptions
std::logic_errorif the graph is not buildable.

◆ BuildInto()

void BuildInto ( Diagram< T > *  target)

Configures target to have the topology that has been described by the calls to Connect, ExportInput, and ExportOutput.

Exceptions
std::logic_errorif the graph is not buildable.

Only Diagram subclasses should call this method. The target must not already be initialized.

◆ Cascade()

void Cascade ( const System< T > &  src,
const System< T > &  dest 
)

Cascades src and dest.

The sole input port on the dest system is connected to sole output port on the src system.

Exceptions
std::exceptionif 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).

◆ Connect() [1/2]

void Connect ( const OutputPort< T > &  src,
const InputPort< T > &  dest 
)

Declares that input port dest is connected to output port src.

Note
The connection created between src and dest via a call to this method can be effectively overridden by any subsequent call to Context::FixInputPort(). That is, calling Context::FixInputPort() on an already connected input port causes the resultant FixedInputPortValue to override any other value present on that port.

◆ Connect() [2/2]

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.

Note
The connection created between src and dest via a call to this method can be effectively overridden by any subsequent call to Context::FixInputPort(). That is, calling Context::FixInputPort() on an already connected input port causes the resultant FixedInputPortValue to override any other value present on that port.
Exceptions
std::exceptionif 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).

◆ empty()

bool empty ( ) const

Returns whether any Systems have been added yet.

◆ ExportInput()

InputPortIndex ExportInput ( const InputPort< T > &  input,
variant< std::string, UseDefaultName name = kUseDefaultName 
)

Declares that the given input port of a constituent system is an input to the entire Diagram.

name is an optional name for the input port; if it is unspecified, then a default name will be provided.

Precondition
If supplied at all, name must not be empty.
Returns
The index of the exported input port of the entire diagram.

◆ ExportOutput()

OutputPortIndex ExportOutput ( const OutputPort< T > &  output,
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.

Precondition
If supplied at all, name must not be empty.
Returns
The index of the exported output port of the entire diagram.

◆ GetMutableSystems()

std::vector<systems::System<T>*> GetMutableSystems ( )

Returns the list of contained Systems.

◆ operator=() [1/2]

DiagramBuilder& operator= ( DiagramBuilder< T > &&  )
delete

◆ operator=() [2/2]

DiagramBuilder& operator= ( const DiagramBuilder< T > &  )
delete

Friends And Related Function Documentation

◆ AddRandomInputs

int AddRandomInputs ( double  ,
systems::DiagramBuilder< double > *   
)
friend

For each subsystem input port in builder that is (a) not yet connected and (b) labeled as random in the InputPort, this method will add a new RandomSource system of the appropriate type and connect it to the subsystem input port.

Parameters
sampling_interval_secinterval to be used for all new sources.
Returns
the total number of RandomSource systems added.
See also
Stochastic Systems

The documentation for this class was generated from the following files: