Drake
Drake C++ Documentation
InputPort< T > Class Template Referencefinal

Detailed Description

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

An InputPort is a System resource that describes the kind of input a System accepts, on a given port.

It does not directly contain any runtime input port data; that is always contained in a Context. The actual value will be either the value of an OutputPort to which this is connected, or a fixed value set in a Context.

Template Parameters
TThe scalar type, which must be one of the default scalars.

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

Public Member Functions

template<typename ValueType = VectorX<T>>
const ValueType & Eval (const Context< T > &context) const
 Returns a reference to the up-to-date value of this input port contained in the given Context. More...
 
template<typename ValueType >
FixedInputPortValueFixValue (Context< T > *context, const ValueType &value) const
 Provides a fixed value for this InputPort in the given Context. More...
 
bool HasValue (const Context< T > &context) const
 Returns true iff this port is connected or has had a fixed value provided in the given Context. More...
 
const System< T > & get_system () const
 Returns a reference to the System that owns this input port. More...
 
const std::string & get_name () const
 Get port name. More...
 
std::string GetFullDescription () const
 Returns a verbose human-readable description of port. More...
 
InputPortIndex get_index () const
 Returns the index of this input port within the owning System. More...
 
PortDataType get_data_type () const
 Returns the port data type. More...
 
int size () const
 Returns the fixed size expected for a vector-valued port. More...
 
bool is_random () const
 Returns true if this is a random port. More...
 
std::optional< RandomDistributionget_random_type () const
 Returns the RandomDistribution if this is a random port. More...
 
DependencyTicket ticket () const
 (Advanced.) Returns the DependencyTicket for this port within the owning System. More...
 
std::unique_ptr< AbstractValueAllocate () const
 Allocates a concrete object suitable for holding the value to be provided by this input port, and returns that as an AbstractValue. More...
 
Does not allow copy, move, or assignment
 InputPort (const InputPort &)=delete
 
InputPortoperator= (const InputPort &)=delete
 
 InputPort (InputPort &&)=delete
 
InputPortoperator= (InputPort &&)=delete
 
- Public Member Functions inherited from InputPortBase
 ~InputPortBase () override
 
InputPortIndex get_index () const
 Returns the index of this input port within the owning System. More...
 
bool is_random () const
 Returns true if this is a random port. More...
 
std::optional< RandomDistributionget_random_type () const
 Returns the RandomDistribution if this is a random port. More...
 
std::unique_ptr< AbstractValueAllocate () const
 Allocates a concrete object suitable for holding the value to be provided by this input port, and returns that as an AbstractValue. More...
 
const std::string & get_name () const
 Get port name. More...
 
std::string GetFullDescription () const
 Returns a verbose human-readable description of port. More...
 
PortDataType get_data_type () const
 Returns the port data type. More...
 
int size () const
 Returns the fixed size expected for a vector-valued port. More...
 
DependencyTicket ticket () const
 (Advanced.) Returns the DependencyTicket for this port within the owning System. More...
 
 InputPortBase (const InputPortBase &)=delete
 
InputPortBaseoperator= (const InputPortBase &)=delete
 
 InputPortBase (InputPortBase &&)=delete
 
InputPortBaseoperator= (InputPortBase &&)=delete
 
- Public Member Functions inherited from PortBase
virtual ~PortBase ()
 
const std::string & get_name () const
 Get port name. More...
 
std::string GetFullDescription () const
 Returns a verbose human-readable description of port. More...
 
PortDataType get_data_type () const
 Returns the port data type. More...
 
int size () const
 Returns the fixed size expected for a vector-valued port. More...
 
const std::optional< std::string > & get_deprecation () const
 When this port is deprecated, returns non-null with a (possibly empty) deprecation message; when this port is not deprecated, returns null. More...
 
void set_deprecation (std::optional< std::string > deprecation)
 Sets whether this port is deprecated (and if so, the message). More...
 
DependencyTicket ticket () const
 (Advanced.) Returns the DependencyTicket for this port within the owning System. More...
 
 PortBase (const PortBase &)=delete
 
PortBaseoperator= (const PortBase &)=delete
 
 PortBase (PortBase &&)=delete
 
PortBaseoperator= (PortBase &&)=delete
 

Friends

class internal::FrameworkFactory
 

Additional Inherited Members

- Protected Types inherited from InputPortBase
using EvalAbstractCallback = std::function< const AbstractValue *(const ContextBase &)>
 Signature of a function suitable for returning the cached value of a particular input port. More...
 
- Protected Member Functions inherited from InputPortBase
 InputPortBase (internal::SystemMessageInterface *owning_system, internal::SystemId owning_system_id, std::string name, InputPortIndex index, DependencyTicket ticket, PortDataType data_type, int size, const std::optional< RandomDistribution > &random_type, EvalAbstractCallback eval, ValueProducer::AllocateCallback alloc)
 (Internal use only) Provides derived classes the ability to set the base class members at construction. More...
 
const AbstractValueDoEvalRequired (const ContextBase &context) const
 Evaluate this port; throws an exception if the port is not connected. More...
 
const AbstractValueDoEvalOptional (const ContextBase &context) const
 Evaluate this port; returns nullptr if the port is not connected. More...
 
void ThrowRequiredMissing () const
 Throws an exception that this port is not connected, but was expected to be connected (i.e., an Eval caller expected that it was always connected). More...
 
- Protected Member Functions inherited from PortBase
 PortBase (const char *kind_string, internal::SystemMessageInterface *owning_system, internal::SystemId owning_system_id, std::string name, int index, DependencyTicket ticket, PortDataType data_type, int size)
 Provides derived classes the ability to set the base class members at construction. More...
 
int get_int_index () const
 Returns the index of this port within the owning System (i.e., an InputPortIndex or OutputPortIndex, but as a bare integer). More...
 
const internal::SystemMessageInterface & get_system_interface () const
 Returns a reference to the system that owns this port. More...
 
internal::SystemMessageInterface & get_mutable_system_interface ()
 Returns get_system_interface(), but without the const. More...
 
void ValidateSystemId (internal::SystemId id) const
 (Internal use only) Checks whether the given id (nominally obtained from a Context passed to this port) was created for the system that owns this port. More...
 
void ThrowValidateContextMismatch () const
 (Internal use only) Throws std::exception with a message that the sanity check(s) related to ValidateContext have failed. More...
 
template<typename ValueType >
const ValueType & PortEvalCast (const AbstractValue &abstract) const
 Pull a value of a given type from an abstract value or issue a nice message if the type is not correct. More...
 
template<typename ValueType , typename T >
const ValueType & PortEvalCast (const BasicVector< T > &basic) const
 Downcast a basic vector to a more specific subclass, or else issue a nice message if the type is not correct. More...
 
template<typename ValueType >
const ValueType & ThrowBadCast (const AbstractValue &abstract) const
 Reports that the user provided a bad ValueType argument to Eval. More...
 
template<typename ValueType , typename T >
const ValueType & ThrowBadCast (const BasicVector< T > &basic) const
 Reports that the user provided a bad ValueType argument to Eval. More...
 
void ThrowBadCast (const std::string &value_typename, const std::string &eval_typename) const
 Reports that the user provided a bad ValueType argument to Eval. More...
 

Constructor & Destructor Documentation

◆ InputPort() [1/2]

InputPort ( const InputPort< T > &  )
delete

◆ InputPort() [2/2]

InputPort ( InputPort< T > &&  )
delete

Member Function Documentation

◆ Allocate()

std::unique_ptr<AbstractValue> Allocate

Allocates a concrete object suitable for holding the value to be provided by this input port, and returns that as an AbstractValue.

The returned object will never be null.

◆ Eval()

const ValueType& Eval ( const Context< T > &  context) const

Returns a reference to the up-to-date value of this input port contained in the given Context.

This is the preferred way to obtain an input port's value since it will not be recalculated once up to date.

If the value is not already up to date with respect to its prerequisites, it will recalculate an up-to-date value before the reference is returned. The recalculation may be arbitrarily expensive, but Eval() is constant time and very fast if the value is already up to date.

Parameters
contextA Context for this System that also contains the value source for this input port. If that source is an output port of another System then context must be a subcontext of the Diagram that contains both this System and the one providing the output port.
Template Parameters
ValueTypeThe type of the const-reference returned by this method. When omitted, the return type is const VectorX<T>& (this is only valid when this is a vector-valued port). For abstract ports, the ValueType either can be the declared type of the port (e.g., lcmt_iiwa_status), or else in advanced use cases can be AbstractValue to get the type-erased value.
Returns
reference to the up-to-date value; if a ValueType is provided, the return type is const ValueType&; if a ValueType is omitted, the return type is const VectorX<T>&.
Exceptions
std::exceptionif the port is not connected. (Use HasValue() to check first, if necessary.)
Precondition
The input port is vector-valued (when no ValueType is provided).
The input port is of type ValueType (when ValueType is provided).

◆ FixValue()

FixedInputPortValue& FixValue ( Context< T > *  context,
const ValueType &  value 
) const

Provides a fixed value for this InputPort in the given Context.

If the port is already connected, this value will override the connected source value. (By "connected" we mean that the port appeared in a DiagramBuilder::Connect() call.)

For vector-valued input ports, you can provide an Eigen vector expression, a BasicVector object, or a scalar (treated as a Vector1). In each of these cases the value is copied into a Value<BasicVector>. If the original value was a BasicVector-derived object, its concrete type is maintained although the stored type is still Value<BasicVector>. The supplied vector must have the right size for the vector port or an std::logic_error is thrown.

For abstract-valued input ports, you can provide any ValueType that is compatible with the model type provided when the port was declared. If the type has a copy constructor it will be copied into a Value<ValueType> object for storage. Otherwise it must have an accessible Clone() method and it is stored using the type returned by that method, which must be ValueType or a base class of ValueType. Eigen objects and expressions are not accepted directly, but you can store then in abstract ports by providing an already-abstract object like Value<MatrixXd>(your_matrix).

The returned FixedInputPortValue reference may be used to modify the input port's value subsequently using the appropriate FixedInputPortValue method, which will ensure that cache invalidation notifications are delivered.

Template Parameters
ValueTypeThe type of the supplied value object. This will be inferred so no template argument need be specified. The type must be copy constructible or have an accessible Clone() method.
Parameters
[in,out]contextA Context that is compatible with the System that owns this port.
[in]valueThe fixed value for this port. Must be convertible to the input port's data type.
Returns
a reference to the FixedInputPortValue object in the Context that contains this port's value.
Precondition
context is compatible with the System that owns this InputPort.
value is compatible with this InputPort's data type.

◆ get_data_type()

PortDataType get_data_type

Returns the port data type.

◆ get_index()

InputPortIndex get_index

Returns the index of this input port within the owning System.

For a Diagram, this will be the index within the Diagram, not the index within a LeafSystem whose input port was exported.

◆ get_name()

const std::string& get_name

Get port name.

◆ get_random_type()

std::optional<RandomDistribution> get_random_type

Returns the RandomDistribution if this is a random port.

◆ get_system()

const System<T>& get_system ( ) const

Returns a reference to the System that owns this input port.

Note that for a Diagram input port this will be the Diagram, not the LeafSystem whose input port was exported.

◆ GetFullDescription()

std::string GetFullDescription

Returns a verbose human-readable description of port.

This is useful for error messages or debugging.

◆ HasValue()

bool HasValue ( const Context< T > &  context) const

Returns true iff this port is connected or has had a fixed value provided in the given Context.

Beware that at the moment, this could be an expensive operation, because the value is brought up-to-date as part of this operation.

◆ is_random()

bool is_random

Returns true if this is a random port.

◆ operator=() [1/2]

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

◆ operator=() [2/2]

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

◆ size()

int size

Returns the fixed size expected for a vector-valued port.

Not meaningful for abstract-valued ports.

◆ ticket()

(Advanced.) Returns the DependencyTicket for this port within the owning System.

Friends And Related Function Documentation

◆ internal::FrameworkFactory

friend class internal::FrameworkFactory
friend

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