maliput
LeafSystem< T > Class Template Reference

Detailed Description

template<typename T>
class maliput::drake::systems::LeafSystem< T >

A superclass template that extends System with some convenience utilities that are not applicable to Diagrams.

@tparam_default_scalar

#include <src/maliput/drake/systems/framework/leaf_system.h>

Inheritance diagram for LeafSystem< T >:
[legend]

Public Member Functions

 ~LeafSystem () override
 
std::unique_ptr< LeafContext< T > > AllocateContext () const
 Shadows System<T>::AllocateContext to provide a more concrete return type LeafContext<T>. More...
 
std::unique_ptr< EventCollection< PublishEvent< T > > > AllocateForcedPublishEventCollection () const override
 
std::unique_ptr< EventCollection< DiscreteUpdateEvent< T > > > AllocateForcedDiscreteUpdateEventCollection () const override
 
std::unique_ptr< EventCollection< UnrestrictedUpdateEvent< T > > > AllocateForcedUnrestrictedUpdateEventCollection () const override
 
std::unique_ptr< ContextBaseDoAllocateContext () const final
 
void SetDefaultState (const Context< T > &context, State< T > *state) const override
 Default implementation: sets all continuous state to the model vector given in DeclareContinuousState (or zero if no model vector was given) and discrete states to zero. More...
 
void SetDefaultParameters (const Context< T > &context, Parameters< T > *parameters) const override
 Default implementation: sets all numeric parameters to the model vector given to DeclareNumericParameter, or else if no model was provided sets the numeric parameter to one. More...
 
std::unique_ptr< ContinuousState< T > > AllocateTimeDerivatives () const final
 Returns a ContinuousState of the same size as the continuous_state allocated in CreateDefaultContext. More...
 
std::unique_ptr< DiscreteValues< T > > AllocateDiscreteVariables () const final
 Returns a DiscreteValues of the same dimensions as the discrete_state allocated in CreateDefaultContext. More...
 
std::multimap< int, int > GetDirectFeedthroughs () const final
 
- Public Member Functions inherited from System< T >
 ~System () override
 
virtual void Accept (SystemVisitor< T > *v) const
 Implements a visitor pattern. More...
 
std::unique_ptr< Context< T > > AllocateContext () const
 Returns a Context<T> suitable for use with this System<T>. More...
 
std::unique_ptr< CompositeEventCollection< T > > AllocateCompositeEventCollection () const
 Allocates a CompositeEventCollection for this system. More...
 
std::unique_ptr< BasicVector< T > > AllocateInputVector (const InputPort< T > &input_port) const
 Given an input port, allocates the vector storage. More...
 
std::unique_ptr< AbstractValueAllocateInputAbstract (const InputPort< T > &input_port) const
 Given an input port, allocates the abstract storage. More...
 
std::unique_ptr< SystemOutput< T > > AllocateOutput () const
 Returns a container that can hold the values of all of this System's output ports. More...
 
VectorX< T > AllocateImplicitTimeDerivativesResidual () const
 Returns an Eigen VectorX suitable for use as the output argument to the CalcImplicitTimeDerivativesResidual() method. More...
 
std::unique_ptr< Context< T > > CreateDefaultContext () const
 This convenience method allocates a context using AllocateContext() and sets its default values using SetDefaultContext(). More...
 
void SetDefaultContext (Context< T > *context) const
 Sets Context fields to their default values. More...
 
virtual void SetRandomState (const Context< T > &context, State< T > *state, RandomGenerator *generator) const
 Assigns random values to all elements of the state. More...
 
virtual void SetRandomParameters (const Context< T > &context, Parameters< T > *parameters, RandomGenerator *generator) const
 Assigns random values to all parameters. More...
 
void SetRandomContext (Context< T > *context, RandomGenerator *generator) const
 Sets Context fields to random values. More...
 
void AllocateFixedInputs (Context< T > *context) const
 For each input port, allocates a fixed input of the concrete type that this System requires, and binds it to the port, disconnecting any prior input. More...
 
bool HasAnyDirectFeedthrough () const
 Returns true if any of the inputs to the system might be directly fed through to any of its outputs and false otherwise. More...
 
bool HasDirectFeedthrough (int output_port) const
 Returns true if there might be direct-feedthrough from any input port to the given output_port, and false otherwise. More...
 
bool HasDirectFeedthrough (int input_port, int output_port) const
 Returns true if there might be direct-feedthrough from the given input_port to the given output_port, and false otherwise. More...
 
virtual std::multimap< int, int > GetDirectFeedthroughs () const=0
 Reports all direct feedthroughs from input ports to output ports. More...
 
void Publish (const Context< T > &context, const EventCollection< PublishEvent< T >> &events) const
 This method is the public entry point for dispatching all publish event handlers. More...
 
void Publish (const Context< T > &context) const
 Forces a publish on the system, given a context. More...
 
const ContinuousState< T > & EvalTimeDerivatives (const Context< T > &context) const
 Returns a reference to the cached value of the continuous state variable time derivatives, evaluating first if necessary using CalcTimeDerivatives(). More...
 
const CacheEntryget_time_derivatives_cache_entry () const
 (Advanced) Returns the CacheEntry used to cache time derivatives for EvalTimeDerivatives(). More...
 
const T & EvalPotentialEnergy (const Context< T > &context) const
 Returns a reference to the cached value of the potential energy (PE), evaluating first if necessary using CalcPotentialEnergy(). More...
 
const T & EvalKineticEnergy (const Context< T > &context) const
 Returns a reference to the cached value of the kinetic energy (KE), evaluating first if necessary using CalcKineticEnergy(). More...
 
const T & EvalConservativePower (const Context< T > &context) const
 Returns a reference to the cached value of the conservative power (Pc), evaluating first if necessary using CalcConservativePower(). More...
 
const T & EvalNonConservativePower (const Context< T > &context) const
 Returns a reference to the cached value of the non-conservative power (Pnc), evaluating first if necessary using CalcNonConservativePower(). More...
 
template<template< typename > class Vec = BasicVector>
const Vec< T > * EvalVectorInput (const Context< T > &context, int port_index) const
 Returns the value of the vector-valued input port with the given port_index as a BasicVector or a specific subclass Vec derived from BasicVector. More...
 
Eigen::VectorBlock< const VectorX< T > > EvalEigenVectorInput (const Context< T > &context, int port_index) const
 Returns the value of the vector-valued input port with the given port_index as an Eigen vector. More...
 
SystemConstraintIndex AddExternalConstraint (ExternalSystemConstraint constraint)
 Adds an "external" constraint to this System. More...
 
void CalcTimeDerivatives (const Context< T > &context, ContinuousState< T > *derivatives) const
 Calculates the time derivatives ẋ꜀ of the continuous state x꜀ into a given output argument. More...
 
void CalcImplicitTimeDerivativesResidual (const Context< T > &context, const ContinuousState< T > &proposed_derivatives, EigenPtr< VectorX< T >> residual) const
 Evaluates the implicit form of the System equations and returns the residual. More...
 
void CalcDiscreteVariableUpdates (const Context< T > &context, const EventCollection< DiscreteUpdateEvent< T >> &events, DiscreteValues< T > *discrete_state) const
 This method is the public entry point for dispatching all discrete variable update event handlers. More...
 
void ApplyDiscreteVariableUpdate (const EventCollection< DiscreteUpdateEvent< T >> &events, DiscreteValues< T > *discrete_state, Context< T > *context) const
 Given the discrete_state results of a previous call to CalcDiscreteVariableUpdates() that dispatched the given collection of events, modifies the context to reflect the updated discrete_state. More...
 
void CalcDiscreteVariableUpdates (const Context< T > &context, DiscreteValues< T > *discrete_state) const
 This method forces a discrete update on the system given a context, and the updated discrete state is stored in discrete_state. More...
 
void CalcUnrestrictedUpdate (const Context< T > &context, const EventCollection< UnrestrictedUpdateEvent< T >> &events, State< T > *state) const
 This method is the public entry point for dispatching all unrestricted update event handlers. More...
 
void ApplyUnrestrictedUpdate (const EventCollection< UnrestrictedUpdateEvent< T >> &events, State< T > *state, Context< T > *context) const
 Given the state results of a previous call to CalcUnrestrictedUpdate() that dispatched the given collection of events, modifies the context to reflect the updated state. More...
 
void CalcUnrestrictedUpdate (const Context< T > &context, State< T > *state) const
 This method forces an unrestricted update on the system given a context, and the updated state is stored in state. More...
 
CalcNextUpdateTime (const Context< T > &context, CompositeEventCollection< T > *events) const
 This method is called by a Simulator during its calculation of the size of the next continuous step to attempt. More...
 
void GetPerStepEvents (const Context< T > &context, CompositeEventCollection< T > *events) const
 This method is called by Simulator::Initialize() to gather all update and publish events that are to be handled in AdvanceTo() at the point before Simulator integrates continuous state. More...
 
void GetInitializationEvents (const Context< T > &context, CompositeEventCollection< T > *events) const
 This method is called by Simulator::Initialize() to gather all update and publish events that need to be handled at initialization before the simulator starts integration. More...
 
std::optional< PeriodicEventDataGetUniquePeriodicDiscreteUpdateAttribute () const
 Gets whether there exists a unique periodic attribute that triggers one or more discrete update events (and, if so, returns that unique periodic attribute). More...
 
bool IsDifferenceEquationSystem (double *time_period=nullptr) const
 Returns true iff the state dynamics of this system are governed exclusively by a difference equation on a single discrete state group and with a unique periodic update (having zero offset). More...
 
std::map< PeriodicEventData, std::vector< const Event< T > * >, PeriodicEventDataComparatorGetPeriodicEvents () const
 Gets all periodic triggered events for a system. More...
 
void CalcOutput (const Context< T > &context, SystemOutput< T > *outputs) const
 Utility method that computes for every output port i the value y(i) that should result from the current contents of the given Context. More...
 
CalcPotentialEnergy (const Context< T > &context) const
 Calculates and returns the potential energy represented by the current configuration provided in context. More...
 
CalcKineticEnergy (const Context< T > &context) const
 Calculates and returns the kinetic energy represented by the current configuration and velocity provided in context. More...
 
CalcConservativePower (const Context< T > &context) const
 Calculates and returns the conservative power represented by the current contents of the given context. More...
 
CalcNonConservativePower (const Context< T > &context) const
 Calculates and returns the non-conservative power represented by the current contents of the given context. More...
 
void MapVelocityToQDot (const Context< T > &context, const VectorBase< T > &generalized_velocity, VectorBase< T > *qdot) const
 Transforms a given generalized velocity v to the time derivative qdot of the generalized configuration q taken from the supplied Context. More...
 
void MapVelocityToQDot (const Context< T > &context, const Eigen::Ref< const VectorX< T >> &generalized_velocity, VectorBase< T > *qdot) const
 Transforms the given generalized velocity to the time derivative of generalized configuration. More...
 
void MapQDotToVelocity (const Context< T > &context, const VectorBase< T > &qdot, VectorBase< T > *generalized_velocity) const
 Transforms the time derivative qdot of the generalized configuration q to generalized velocities v. More...
 
void MapQDotToVelocity (const Context< T > &context, const Eigen::Ref< const VectorX< T >> &qdot, VectorBase< T > *generalized_velocity) const
 Transforms the given time derivative qdot of generalized configuration q to generalized velocity v. More...
 
const Context< T > & GetSubsystemContext (const System< T > &subsystem, const Context< T > &context) const
 Returns a const reference to the subcontext that corresponds to the contained System subsystem. More...
 
Context< T > & GetMutableSubsystemContext (const System< T > &subsystem, Context< T > *context) const
 Returns a mutable reference to the subcontext that corresponds to the contained System subsystem. More...
 
const Context< T > & GetMyContextFromRoot (const Context< T > &root_context) const
 Returns the const Context for this subsystem, given a root context. More...
 
Context< T > & GetMyMutableContextFromRoot (Context< T > *root_context) const
 Returns the mutable subsystem context for this system, given a root context. More...
 
std::string GetMemoryObjectName () const
 Returns a name for this System based on a stringification of its type name and memory address. More...
 
const InputPort< T > & get_input_port (int port_index) const
 Returns the typed input port at index port_index. More...
 
const InputPort< T > & get_input_port () const
 Convenience method for the case of exactly one input port. More...
 
const InputPort< T > * get_input_port_selection (std::variant< InputPortSelection, InputPortIndex > port_index) const
 Returns the typed input port specified by the InputPortSelection or by the InputPortIndex. More...
 
const InputPort< T > & GetInputPort (const std::string &port_name) const
 Returns the typed input port with the unique name port_name. More...
 
bool HasInputPort (const std::string &port_name) const
 Returns true iff the system has an InputPort of the given port_name. More...
 
const OutputPort< T > & get_output_port (int port_index) const
 Returns the typed output port at index port_index. More...
 
const OutputPort< T > & get_output_port () const
 Convenience method for the case of exactly one output port. More...
 
const OutputPort< T > * get_output_port_selection (std::variant< OutputPortSelection, OutputPortIndex > port_index) const
 Returns the typed output port specified by the OutputPortSelection or by the OutputPortIndex. More...
 
const OutputPort< T > & GetOutputPort (const std::string &port_name) const
 Returns the typed output port with the unique name port_name. More...
 
bool HasOutputPort (const std::string &port_name) const
 Returns true iff the system has an OutputPort of the given port_name. More...
 
int num_constraints () const
 Returns the number of constraints specified for the system. More...
 
const SystemConstraint< T > & get_constraint (SystemConstraintIndex constraint_index) const
 Returns the constraint at index constraint_index. More...
 
boolean< T > CheckSystemConstraintsSatisfied (const Context< T > &context, double tol) const
 Returns true if context satisfies all of the registered SystemConstraints with tolerance tol. More...
 
VectorX< T > CopyContinuousStateVector (const Context< T > &context) const
 Returns a copy of the continuous state vector x꜀ into an Eigen vector. More...
 
int num_input_ports () const
 Returns the number of input ports currently allocated in this System. More...
 
int num_output_ports () const
 Returns the number of output ports currently allocated in this System. More...
 
std::string GetGraphvizString (int max_depth=std::numeric_limits< int >::max()) const
 Returns a Graphviz string describing this System. More...
 
int64_t GetGraphvizId () const
 Returns an opaque integer that uniquely identifies this system in the Graphviz output. More...
 
void FixInputPortsFrom (const System< double > &other_system, const Context< double > &other_context, Context< T > *target_context) const
 Fixes all of the input ports in target_context to their current values in other_context, as evaluated by other_system. More...
 
const SystemScalarConverterget_system_scalar_converter () const
 (Advanced) Returns the SystemScalarConverter for this object. More...
 
template<typename U >
std::unique_ptr< System< U > > ToScalarType () const
 Creates a deep copy of this System, transmogrified to use the scalar type selected by a template parameter. More...
 
template<typename U >
std::unique_ptr< System< U > > ToScalarTypeMaybe () const
 Creates a deep copy of this system exactly like ToScalarType(), but returns nullptr if this System does not support the destination type, instead of throwing an exception. More...
 
void GetWitnessFunctions (const Context< T > &context, std::vector< const WitnessFunction< T > * > *w) const
 Gets the witness functions active for the given state. More...
 
CalcWitnessValue (const Context< T > &context, const WitnessFunction< T > &witness_func) const
 Evaluates a witness function at the given context. More...
 
CacheEntryDeclareCacheEntry (std::string description, ValueProducer value_producer, std::set< DependencyTicket > prerequisites_of_calc={all_sources_ticket()})
 Declares a new CacheEntry in this System using the most generic form of the calculation function. More...
 
CacheEntryDeclareCacheEntry (std::string description, std::function< std::unique_ptr< AbstractValue >()> alloc_function, std::function< void(const ContextBase &, AbstractValue *)> calc_function, std::set< DependencyTicket > prerequisites_of_calc={all_sources_ticket()})
 
template<class MySystem , class MyContext , typename ValueType >
CacheEntryDeclareCacheEntry (std::string description, const ValueType &model_value, void(MySystem::*calc)(const MyContext &, ValueType *) const, std::set< DependencyTicket > prerequisites_of_calc={all_sources_ticket()})
 Declares a cache entry by specifying a model value of concrete type ValueType and a calculator function that is a class member function (method) with signature: More...
 
template<class MySystem , class MyContext , typename ValueType >
CacheEntryDeclareCacheEntry (std::string description, void(MySystem::*calc)(const MyContext &, ValueType *) const, std::set< DependencyTicket > prerequisites_of_calc={all_sources_ticket()})
 Declares a cache entry by specifying only a calculator function that is a class member function (method) with signature: More...
 
template<class MySystem , class MyContext , typename ValueType >
CacheEntryDeclareCacheEntry (std::string description, ValueType(MySystem::*make)() const, void(MySystem::*calc)(const MyContext &, ValueType *) const, std::set< DependencyTicket > prerequisites_of_calc)
 
template<class MySystem , class MyContext , typename ValueType >
CacheEntryDeclareCacheEntry (std::string description, const ValueType &model_value, ValueType(MySystem::*calc)(const MyContext &) const, std::set< DependencyTicket > prerequisites_of_calc)
 
template<class MySystem , class MyContext , typename ValueType >
CacheEntryDeclareCacheEntry (std::string description, ValueType(MySystem::*calc)(const MyContext &) const, std::set< DependencyTicket > prerequisites_of_calc)
 
DependencyTicket abstract_parameter_ticket (AbstractParameterIndex index) const
 Returns a ticket indicating dependence on a particular abstract parameter paᵢ. More...
 
DependencyTicket abstract_state_ticket (AbstractStateIndex index) const
 Returns a ticket indicating dependence on a particular abstract state variable xaᵢ. More...
 
DependencyTicket cache_entry_ticket (CacheIndex index) const
 Returns a ticket indicating dependence on the cache entry indicated by index. More...
 
DependencyTicket discrete_state_ticket (DiscreteStateIndex index) const
 Returns a ticket indicating dependence on a particular discrete state variable xdᵢ (may be a vector). More...
 
DependencyTicket input_port_ticket (InputPortIndex index) const
 Returns a ticket indicating dependence on input port uᵢ indicated by index. More...
 
DependencyTicket numeric_parameter_ticket (NumericParameterIndex index) const
 Returns a ticket indicating dependence on a particular numeric parameter pnᵢ (may be a vector). More...
 

Protected Member Functions

 LeafSystem ()
 Default constructor that declares no inputs, outputs, state, parameters, events, nor scalar-type conversion support (AutoDiff, etc.). More...
 
 LeafSystem (SystemScalarConverter converter)
 Constructor that declares no inputs, outputs, state, parameters, or events, but allows subclasses to declare scalar-type conversion support (AutoDiff, etc.). More...
 
virtual std::unique_ptr< LeafContext< T > > DoMakeLeafContext () const
 Provides a new instance of the leaf context for this system. More...
 
virtual void DoValidateAllocatedLeafContext (const LeafContext< T > &context) const
 Derived classes that impose restrictions on what resources are permitted should check those restrictions by implementing this. More...
 
DoCalcWitnessValue (const Context< T > &context, const WitnessFunction< T > &witness_func) const final
 Derived classes will implement this method to evaluate a witness function at the given context. More...
 
void AddTriggeredWitnessFunctionToCompositeEventCollection (Event< T > *event, CompositeEventCollection< T > *events) const final
 Add event to events due to a witness function triggering. More...
 
void DoCalcNextUpdateTime (const Context< T > &context, CompositeEventCollection< T > *events, T *time) const override
 Computes the next update time based on the configured periodic events, for scalar types that are arithmetic, or aborts for scalar types that are not arithmetic. More...
 
void GetGraphvizFragment (int max_depth, std::stringstream *dot) const override
 Emits a graphviz fragment for this System. More...
 
void GetGraphvizInputPortToken (const InputPort< T > &port, int max_depth, std::stringstream *dot) const final
 Appends a fragment to the dot stream identifying the graphviz node representing port. More...
 
void GetGraphvizOutputPortToken (const OutputPort< T > &port, int max_depth, std::stringstream *dot) const final
 Appends a fragment to the dot stream identifying the graphviz node representing port. More...
 
std::unique_ptr< ContinuousState< T > > AllocateContinuousState () const
 Returns a copy of the state declared in the most recent DeclareContinuousState() call, or else a zero-sized state if that method has never been called. More...
 
std::unique_ptr< DiscreteValues< T > > AllocateDiscreteState () const
 Returns a copy of the states declared in DeclareDiscreteState() calls. More...
 
std::unique_ptr< AbstractValuesAllocateAbstractState () const
 Returns a copy of the states declared in DeclareAbstractState() calls. More...
 
std::unique_ptr< Parameters< T > > AllocateParameters () const
 Returns a copy of the parameters declared in DeclareNumericParameter() and DeclareAbstractParameter() calls. More...
 
int DeclareNumericParameter (const BasicVector< T > &model_vector)
 Declares a numeric parameter using the given model_vector. More...
 
template<template< typename > class U = BasicVector>
const U< T > & GetNumericParameter (const Context< T > &context, int index) const
 Extracts the numeric parameters of type U from the context at index. More...
 
template<template< typename > class U = BasicVector>
U< T > & GetMutableNumericParameter (Context< T > *context, int index) const
 Extracts the numeric parameters of type U from the context at index. More...
 
int DeclareAbstractParameter (const AbstractValue &model_value)
 Declares an abstract parameter using the given model_value. More...
 
Declare periodic events

Methods in this group declare that this System has an event that is triggered periodically. The first periodic trigger will occur at t = offset_sec, and it will recur at every period_sec thereafter. Several signatures are provided to allow for a general Event object to be triggered or for simpler class member functions to be invoked instead.

Reaching a designated time causes a periodic event to be dispatched to one of the three available types of event dispatcher: publish (read only), discrete update, and unrestricted update.

Note
If you want to handle timed events that are not periodic (timers, alarms, etc.), overload DoCalcNextUpdateTime() rather than using the methods in this section.

Template arguments to these methods are inferred from the argument lists and need not be specified explicitly.

Precondition
period_sec > 0 and offset_sec ≥ 0.
template<class MySystem >
void DeclarePeriodicPublishEvent (double period_sec, double offset_sec, EventStatus(MySystem::*publish)(const Context< T > &) const)
 Declares that a Publish event should occur periodically and that it should invoke the given event handler method. More...
 
template<class MySystem >
void DeclarePeriodicPublishEvent (double period_sec, double offset_sec, void(MySystem::*publish)(const Context< T > &) const)
 This variant accepts a handler that is assumed to succeed rather than one that returns an EventStatus result. More...
 
template<class MySystem >
void DeclarePeriodicDiscreteUpdateEvent (double period_sec, double offset_sec, EventStatus(MySystem::*update)(const Context< T > &, DiscreteValues< T > *) const)
 Declares that a DiscreteUpdate event should occur periodically and that it should invoke the given event handler method. More...
 
template<class MySystem >
void DeclarePeriodicDiscreteUpdateEvent (double period_sec, double offset_sec, void(MySystem::*update)(const Context< T > &, DiscreteValues< T > *) const)
 This variant accepts a handler that is assumed to succeed rather than one that returns an EventStatus result. More...
 
template<class MySystem >
void DeclarePeriodicUnrestrictedUpdateEvent (double period_sec, double offset_sec, EventStatus(MySystem::*update)(const Context< T > &, State< T > *) const)
 Declares that an UnrestrictedUpdate event should occur periodically and that it should invoke the given event handler method. More...
 
template<class MySystem >
void DeclarePeriodicUnrestrictedUpdateEvent (double period_sec, double offset_sec, void(MySystem::*update)(const Context< T > &, State< T > *) const)
 This variant accepts a handler that is assumed to succeed rather than one that returns an EventStatus result. More...
 
template<typename EventType >
void DeclarePeriodicEvent (double period_sec, double offset_sec, const EventType &event)
 (Advanced) Declares that a particular Event object should be dispatched periodically. More...
 
void DeclarePeriodicPublish (double period_sec, double offset_sec=0)
 (To be deprecated) Declares a periodic publish event that invokes the Publish() dispatcher but does not provide a handler function. More...
 
void DeclarePeriodicDiscreteUpdate (double period_sec, double offset_sec=0)
 (To be deprecated) Declares a periodic discrete update event that invokes the DiscreteUpdate() dispatcher but does not provide a handler function. More...
 
void DeclarePeriodicUnrestrictedUpdate (double period_sec, double offset_sec=0)
 (To be deprecated) Declares a periodic unrestricted update event that invokes the UnrestrictedUpdate() dispatcher but does not provide a handler function. More...
 
Declare per-step events

These methods are used to declare events that are triggered whenever the Drake Simulator advances the simulated trajectory. Note that each call to Simulator::AdvanceTo() typically generates many trajectory-advancing steps of varying time intervals; per-step events are triggered for each of those steps.

Per-step events are useful for taking discrete action at every point of a simulated trajectory (generally spaced irregularly in time) without missing anything. For example, per-step events can be used to implement a high-accuracy signal delay by maintaining a buffer of past signal values, updated at each step. Because the steps are smaller in regions of rapid change, the interpolated signal retains the accuracy provided by the denser sampling. A periodic sampling would produce less-accurate interpolations.

As with any Drake event trigger type, a per-step event is dispatched to one of the three available types of event dispatcher: publish (read only), discrete state update, and unrestricted state update. Several signatures are provided below to allow for a general Event object to be triggered, or simpler class member functions to be invoked instead.

Per-step events are issued as follows: First, the Simulator::Initialize() method queries and records the set of declared per-step events. That set does not change during a simulation. Any per-step publish events are dispatched at the end of Initialize() to publish the initial value of the trajectory. Then every AdvanceTo() internal step dispatches unrestricted and discrete update events at the start of the step, and dispatches publish events at the end of the step (that is, after time advances). This means that a per-step event at fixed step size h behaves identically to a periodic event of period h, offset 0.

Template arguments to these methods are inferred from the argument lists and need not be specified explicitly.

template<class MySystem >
void DeclarePerStepPublishEvent (EventStatus(MySystem::*publish)(const Context< T > &) const)
 Declares that a Publish event should occur at initialization and at the end of every trajectory-advancing step and that it should invoke the given event handler method. More...
 
template<class MySystem >
void DeclarePerStepDiscreteUpdateEvent (EventStatus(MySystem::*update)(const Context< T > &, DiscreteValues< T > *) const)
 Declares that a DiscreteUpdate event should occur at the start of every trajectory-advancing step and that it should invoke the given event handler method. More...
 
template<class MySystem >
void DeclarePerStepUnrestrictedUpdateEvent (EventStatus(MySystem::*update)(const Context< T > &, State< T > *) const)
 Declares that an UnrestrictedUpdate event should occur at the start of every trajectory-advancing step and that it should invoke the given event handler method. More...
 
template<typename EventType >
void DeclarePerStepEvent (const EventType &event)
 (Advanced) Declares that a particular Event object should be dispatched at every trajectory-advancing step. More...
 
Declare initialization events

These methods are used to declare events that occur when the Drake Simulator::Initialize() method is invoked.

During Initialize(), initialization-triggered unrestricted update events are dispatched first for the whole Diagram, then initialization-triggered discrete update events are dispatched for the whole Diagram. No other update events occur during initialization. On the other hand, any publish events, including initialization-triggered, per-step, and time-triggered publish events that trigger at the initial time, are dispatched together during initialization.

Template arguments to these methods are inferred from the argument lists and need not be specified explicitly.

template<class MySystem >
void DeclareInitializationPublishEvent (EventStatus(MySystem::*publish)(const Context< T > &) const)
 Declares that a Publish event should occur at initialization and that it should invoke the given event handler method. More...
 
template<class MySystem >
void DeclareInitializationDiscreteUpdateEvent (EventStatus(MySystem::*update)(const Context< T > &, DiscreteValues< T > *) const)
 Declares that a DiscreteUpdate event should occur at initialization and that it should invoke the given event handler method. More...
 
template<class MySystem >
void DeclareInitializationUnrestrictedUpdateEvent (EventStatus(MySystem::*update)(const Context< T > &, State< T > *) const)
 Declares that an UnrestrictedUpdate event should occur at initialization and that it should invoke the given event handler method. More...
 
template<typename EventType >
void DeclareInitializationEvent (const EventType &event)
 (Advanced) Declares that a particular Event object should be dispatched at initialization. More...
 
Declare forced events

Forced events are those that are triggered through invocation of System::Publish(const Context&), System::CalcDiscreteVariableUpdates(const Context&, DiscreteValues<T>*), or System::CalcUnrestrictedUpdate(const Context&, State<T>*), rather than as a response to some computation-related event (e.g., the beginning of a period of time was reached, a trajectory advancing step was performed, etc.) One useful application of a forced publish: a process receives a network message and wants to trigger message emissions in various systems embedded within a Diagram in response.

Template arguments to these methods are inferred from the argument lists. and need not be specified explicitly.

Note
It's rare that an event needs to be triggered by force. Please consider per-step and periodic triggered events first.
Warning
Simulator handles forced publish events at initialization and on a per-step basis when its "publish at initialization" and "publish every time step" options are set.
See also
Simulator::set_publish_at_initialization()
Simulator::set_publish_every_time_step()
template<class MySystem >
void DeclareForcedPublishEvent (EventStatus(MySystem::*publish)(const Context< T > &) const)
 Declares a function that is called whenever a user directly calls Publish(const Context&). More...
 
template<class MySystem >
void DeclareForcedDiscreteUpdateEvent (EventStatus(MySystem::*update)(const Context< T > &, DiscreteValues< T > *) const)
 Declares a function that is called whenever a user directly calls CalcDiscreteVariableUpdates(const Context&, DiscreteValues<T>*). More...
 
template<class MySystem >
void DeclareForcedUnrestrictedUpdateEvent (EventStatus(MySystem::*update)(const Context< T > &, State< T > *) const)
 Declares a function that is called whenever a user directly calls CalcUnrestrictedUpdate(const Context&, State<T>*). More...
 
Declare continuous state variables

Continuous state consists of up to three kinds of variables: generalized coordinates q, generalized velocities v, and miscellaneous continuous variables z.

Methods in this section provide different ways to declare these, and offer the ability to provide a model_vector to specify the initial values for these variables. Model values are useful when you want the values of these variables in a default Context to be something other than zero.

If multiple calls are made to DeclareContinuousState() methods, only the last call has any effect.

ContinuousStateIndex DeclareContinuousState (int num_state_variables)
 Declares that this System should reserve continuous state with num_state_variables state variables, which have no second-order structure. More...
 
ContinuousStateIndex DeclareContinuousState (int num_q, int num_v, int num_z)
 Declares that this System should reserve continuous state with num_q generalized positions, num_v generalized velocities, and num_z miscellaneous state variables. More...
 
ContinuousStateIndex DeclareContinuousState (const BasicVector< T > &model_vector)
 Declares that this System should reserve continuous state with model_vector.size() miscellaneous state variables, stored in a vector cloned from model_vector. More...
 
ContinuousStateIndex DeclareContinuousState (const BasicVector< T > &model_vector, int num_q, int num_v, int num_z)
 Declares that this System should reserve continuous state with num_q generalized positions, num_v generalized velocities, and num_z miscellaneous state variables, stored in a vector cloned from model_vector. More...
 
Declare discrete state variables

Discrete state consists of any number of discrete state "groups", each of which is a vector of discrete state variables.

Methods in this section provide different ways to declare these, and offer the ability to provide a model_vector to specify the initial values for each group of variables. Model values are useful when you want the values of these variables in a default Context to be something other than zero.

Each call to a DeclareDiscreteState() method produces another discrete state group, and the group index is returned.

DiscreteStateIndex DeclareDiscreteState (const BasicVector< T > &model_vector)
 Declares a discrete state group with model_vector.size() state variables, stored in a vector cloned from model_vector (preserving the concrete type and value). More...
 
DiscreteStateIndex DeclareDiscreteState (const Eigen::Ref< const VectorX< T >> &vector)
 Declares a discrete state group with vector.size() state variables, stored in a BasicVector initialized with the contents of vector. More...
 
DiscreteStateIndex DeclareDiscreteState (int num_state_variables)
 Declares a discrete state group with num_state_variables state variables, stored in a BasicVector initialized to be all-zero. More...
 
Declare abstract state variables

Abstract state consists of any number of arbitrarily-typed variables, each represented by an AbstractValue.

Each call to the DeclareAbstractState() method produces another abstract state variable, and the abstract state variable index is returned.

AbstractStateIndex DeclareAbstractState (const AbstractValue &abstract_state)
 Declares an abstract state. More...
 
(Advanced) Declare size of implicit time derivatives residual

for use with System::CalcImplicitTimeDerivativeResidual().

Most commonly the default value, same as num_continuous_states(), will be the correct size for the residual.

void DeclareImplicitTimeDerivativesResidualSize (int n)
 (Advanced) Overrides the default size for the implicit time derivatives residual. More...
 
Declare input ports

Methods in this section are used by derived classes to declare their input ports, which may be vector valued or abstract valued.

You should normally provide a meaningful name for any input port you create. Names must be unique for this system (passing in a duplicate name will throw std::exception). However, if you specify kUseDefaultName as the name, then a default name of e.g. "u2", where 2 is the input port number will be provided. An empty name is not permitted.

InputPort< T > & DeclareVectorInputPort (std::variant< std::string, UseDefaultName > name, const BasicVector< T > &model_vector, std::optional< RandomDistribution > random_type=std::nullopt)
 Declares a vector-valued input port using the given model_vector. More...
 
InputPort< T > & DeclareVectorInputPort (std::variant< std::string, UseDefaultName > name, int size, std::optional< RandomDistribution > random_type=std::nullopt)
 Declares a vector-valued input port with type BasicVector and size size. More...
 
InputPort< T > & DeclareAbstractInputPort (std::variant< std::string, UseDefaultName > name, const AbstractValue &model_value)
 Declares an abstract-valued input port using the given model_value. More...
 
Deprecated input port declarations

Methods in this section leave out the name parameter and are the same as invoking the corresponding method with kUseDefaultName as the name.

InputPort< T > & DeclareVectorInputPort (const BasicVector< T > &model_vector, std::optional< RandomDistribution > random_type=std::nullopt)
 
InputPort< T > & DeclareAbstractInputPort (const AbstractValue &model_value)
 
Deprecated output port declarations

Methods in this section leave out the name parameter and are the same as invoking the corresponding method with kUseDefaultName as the name.

template<class MySystem , typename BasicVectorSubtype >
LeafOutputPort< T > & DeclareVectorOutputPort (const BasicVectorSubtype &model_vector, void(MySystem::*calc)(const Context< T > &, BasicVectorSubtype *) const, std::set< DependencyTicket > prerequisites_of_calc={ all_sources_ticket()})
 
template<class MySystem , typename BasicVectorSubtype >
LeafOutputPort< T > & DeclareVectorOutputPort (void(MySystem::*calc)(const Context< T > &, BasicVectorSubtype *) const, std::set< DependencyTicket > prerequisites_of_calc={ all_sources_ticket()})
 
LeafOutputPort< T > & DeclareVectorOutputPort (const BasicVector< T > &model_vector, typename LeafOutputPort< T >::CalcVectorCallback vector_calc_function, std::set< DependencyTicket > prerequisites_of_calc={all_sources_ticket()})
 
template<class MySystem , typename OutputType >
std::enable_if_t<!std::is_same_v< OutputType, std::string >, LeafOutputPort< T > & > DeclareAbstractOutputPort (const OutputType &model_value, void(MySystem::*calc)(const Context< T > &, OutputType *) const, std::set< DependencyTicket > prerequisites_of_calc={all_sources_ticket()})
 
template<class MySystem , typename OutputType >
LeafOutputPort< T > & DeclareAbstractOutputPort (void(MySystem::*calc)(const Context< T > &, OutputType *) const, std::set< DependencyTicket > prerequisites_of_calc={ all_sources_ticket()})
 
template<class MySystem , typename OutputType >
LeafOutputPort< T > & DeclareAbstractOutputPort (OutputType(MySystem::*make)() const, void(MySystem::*calc)(const Context< T > &, OutputType *) const, std::set< DependencyTicket > prerequisites_of_calc={ all_sources_ticket()})
 
LeafOutputPort< T > & DeclareAbstractOutputPort (typename LeafOutputPort< T >::AllocCallback alloc_function, typename LeafOutputPort< T >::CalcCallback calc_function, std::set< DependencyTicket > prerequisites_of_calc={ all_sources_ticket()})
 
- Protected Member Functions inherited from System< T >
 System (SystemScalarConverter converter)
 Constructs an empty System base class object and allocates base class resources, possibly supporting scalar-type conversion support (AutoDiff, etc.) using converter. More...
 
InputPort< T > & DeclareInputPort (std::variant< std::string, UseDefaultName > name, PortDataType type, int size, std::optional< RandomDistribution > random_type=std::nullopt)
 Adds a port with the specified type and size to the input topology. More...
 
InputPort< T > & DeclareInputPort (PortDataType type, int size, std::optional< RandomDistribution > random_type=std::nullopt)
 
SystemConstraintIndex AddConstraint (std::unique_ptr< SystemConstraint< T >> constraint)
 Adds an already-created constraint to the list of constraints for this System. More...
 
virtual void DoCalcTimeDerivatives (const Context< T > &context, ContinuousState< T > *derivatives) const
 Override this if you have any continuous state variables x꜀ in your concrete System to calculate their time derivatives. More...
 
virtual void DoCalcImplicitTimeDerivativesResidual (const Context< T > &context, const ContinuousState< T > &proposed_derivatives, EigenPtr< VectorX< T >> residual) const
 Override this if you have an efficient way to evaluate the implicit time derivatives residual for this System. More...
 
virtual T DoCalcPotentialEnergy (const Context< T > &context) const
 Override this method for physical systems to calculate the potential energy PE currently stored in the configuration provided in the given Context. More...
 
virtual T DoCalcKineticEnergy (const Context< T > &context) const
 Override this method for physical systems to calculate the kinetic energy KE currently present in the motion provided in the given Context. More...
 
virtual T DoCalcConservativePower (const Context< T > &context) const
 Override this method to return the rate Pc at which mechanical energy is being converted from potential energy to kinetic energy by this system in the given Context. More...
 
virtual T DoCalcNonConservativePower (const Context< T > &context) const
 Override this method to return the rate Pnc at which work W is done on the system by non-conservative forces. More...
 
virtual void DoMapQDotToVelocity (const Context< T > &context, const Eigen::Ref< const VectorX< T >> &qdot, VectorBase< T > *generalized_velocity) const
 Provides the substantive implementation of MapQDotToVelocity(). More...
 
virtual void DoMapVelocityToQDot (const Context< T > &context, const Eigen::Ref< const VectorX< T >> &generalized_velocity, VectorBase< T > *qdot) const
 Provides the substantive implementation of MapVelocityToQDot(). More...
 
Eigen::VectorBlock< VectorX< T > > GetMutableOutputVector (SystemOutput< T > *output, int port_index) const
 Returns a mutable Eigen expression for a vector valued output port with index port_index in this system. More...
 
bool forced_publish_events_exist () const
 
bool forced_discrete_update_events_exist () const
 
bool forced_unrestricted_update_events_exist () const
 
EventCollection< PublishEvent< T > > & get_mutable_forced_publish_events ()
 
EventCollection< DiscreteUpdateEvent< T > > & get_mutable_forced_discrete_update_events ()
 
EventCollection< UnrestrictedUpdateEvent< T > > & get_mutable_forced_unrestricted_update_events ()
 
const EventCollection< PublishEvent< T > > & get_forced_publish_events () const
 
const EventCollection< DiscreteUpdateEvent< T > > & get_forced_discrete_update_events () const
 
const EventCollection< UnrestrictedUpdateEvent< T > > & get_forced_unrestricted_update_events () const
 
void set_forced_publish_events (std::unique_ptr< EventCollection< PublishEvent< T >>> forced)
 
void set_forced_discrete_update_events (std::unique_ptr< EventCollection< DiscreteUpdateEvent< T >>> forced)
 
void set_forced_unrestricted_update_events (std::unique_ptr< EventCollection< UnrestrictedUpdateEvent< T >>> forced)
 
SystemScalarConverterget_mutable_system_scalar_converter ()
 Returns the SystemScalarConverter for this system. More...
 
template<template< typename > class Clazz>
void ValidateChildOfContext (const Clazz< T > *object) const
 
virtual void DoGetWitnessFunctions (const Context< T > &, std::vector< const WitnessFunction< T > * > *) const
 Derived classes can override this method to provide witness functions active for the given state. More...
 

Static Protected Member Functions

static DependencyTicket all_sources_ticket ()
 Returns a ticket indicating dependence on every possible independent source value, including time, accuracy, state, input ports, and parameters (but not cache entries). More...
 

Declare output ports

Methods in this section are used by derived classes to declare their output ports, which may be vector valued or abstract valued. Every output port must have an allocator function and a calculator function. The allocator returns an object suitable for holding a value of the output port. The calculator uses the contents of a given Context to produce the output port's value, which is placed in an object of the type returned by the allocator.

Although the allocator and calculator functions ultimately satisfy generic function signatures defined in LeafOutputPort, we provide a variety of DeclareVectorOutputPort() and DeclareAbstractOutputPort() signatures here for convenient specification, with mapping to the generic form handled invisibly. In particular, allocators are most easily defined by providing a model value that can be used to construct an allocator that copies the model when a new value object is needed. Alternatively a method can be provided that constructs a value object when invoked (those methods are conventionally, but not necessarily, named MakeSomething() where Something is replaced by the output port value type).

Because output port values are ultimately stored in AbstractValue objects, the underlying types must be suitable. For vector ports, that means the type must be BasicVector or a class derived from BasicVector. For abstract ports, the type must be copy constructible or cloneable. For methods below that are not given an explicit model value or construction ("make") method, the underlying type must be default constructible.

See also
maliput::drake::Value for more about abstract values.

A list of prerequisites may be provided for the calculator function to avoid unnecessary recomputation. If no prerequisites are provided, the default is to assume the output port value is dependent on all possible sources. See DeclareCacheEntry for more information about prerequisites.

Output ports must have a name that is unique within the owning subsystem. Users can provide meaningful names or specify the name as kUseDefaultName in which case a name like "y3" is automatically provided, where the number is the output port index. An empty name is not permitted.

Direct feedthrough

By default, LeafSystem assumes there is direct feedthrough of values from every input to every output. This is a conservative assumption that ensures we detect and can prevent the formation of algebraic loops (implicit computations) in system Diagrams. Systems which do not have direct feedthrough may override that assumption in either of two ways:

(1) When declaring an output port (e.g., DeclareVectorOutputPort()), provide a non-default value for the prerequisites_of_calc argument. In that case the dependency path from each input port to that output port is probed via the fast cache invalidation mechanism to see if it has a direct or indirect dependence that input port. For example:

PendulumPlant<T>::PendulumPlant() {
// No feedthrough because the output port depends only on state,
// and state has no dependencies.
"state", &PendulumPlant::CopyStateOut,
{this->all_state_ticket()});
// Has feedthrough from input port 0 but not from any others.
"tau", &PendulumPlant::CopyTauOut,
// Doesn't specify prerequisites. We'll assume feedthrough from all
// inputs unless we can apply symbolic analysis (see below).
"result", &PendulumPlant::CalcResult);
}

See Dependency tickets for more information about tickets, including a list of possible ticket options.

(2) Add support for the symbolic::Expression scalar type, per How to write a System that supports scalar conversion. This allows the LeafSystem to infer the sparsity from the symbolic equations for any of the output ports that don't specify an explicit list of prerequisites.

Option 2 is a convenient default for simple systems that already support symbolic::Expression, but option 1 should be preferred as the most direct mechanism to control feedthrough reporting.

Normally the direct-feedthrough relations are checked automatically to detect algebraic loops. If you want to examine the computed feedthrough status for all ports or a particular port, see System::GetDirectFeedthroughs(), System::HasDirectFeedthrough(), and related methods.

ValueProducer::AllocateCallback allocate
 
auto & port
 
return port
 
template<class MySystem , typename BasicVectorSubtype >
LeafOutputPort< T > & DeclareVectorOutputPort (std::variant< std::string, UseDefaultName > name, const BasicVectorSubtype &model_vector, void(MySystem::*calc)(const Context< T > &, BasicVectorSubtype *) const, std::set< DependencyTicket > prerequisites_of_calc={ all_sources_ticket()})
 Declares a vector-valued output port by specifying (1) a model vector of type BasicVectorSubtype derived from BasicVector and initialized to the correct size and desired initial value, and (2) a calculator function that is a class member function (method) with signature: More...
 
template<class MySystem >
LeafOutputPort< T > & DeclareVectorOutputPort (std::variant< std::string, UseDefaultName > name, int size, void(MySystem::*calc)(const Context< T > &, BasicVector< T > *) const, std::set< DependencyTicket > prerequisites_of_calc={ all_sources_ticket()})
 Declares a vector-valued output port with type BasicVector and size size, using the maliput::drake::dummy_value<T>, which is NaN when T = double. More...
 
template<class MySystem , typename BasicVectorSubtype >
LeafOutputPort< T > & DeclareVectorOutputPort (std::variant< std::string, UseDefaultName > name, void(MySystem::*calc)(const Context< T > &, BasicVectorSubtype *) const, std::set< DependencyTicket > prerequisites_of_calc={ all_sources_ticket()})
 Declares a vector-valued output port by specifying only a calculator function that is a class member function (method) with signature: More...
 
LeafOutputPort< T > & DeclareVectorOutputPort (std::variant< std::string, UseDefaultName > name, const BasicVector< T > &model_vector, typename LeafOutputPort< T >::CalcVectorCallback vector_calc_function, std::set< DependencyTicket > prerequisites_of_calc={all_sources_ticket()})
 (Advanced) Declares a vector-valued output port using the given model_vector and a function for calculating the port's value at runtime. More...
 
LeafOutputPort< T > & DeclareVectorOutputPort (std::variant< std::string, UseDefaultName > name, int size, typename LeafOutputPort< T >::CalcVectorCallback vector_calc_function, std::set< DependencyTicket > prerequisites_of_calc={ all_sources_ticket()})
 (Advanced) Declares a vector-valued output port with type BasicVector<T> and size size, using the maliput::drake::dummy_value<T>, which is NaN when T = double. More...
 
template<class MySystem , typename OutputType >
LeafOutputPort< T > & DeclareAbstractOutputPort (std::variant< std::string, UseDefaultName > name, const OutputType &model_value, void(MySystem::*calc)(const Context< T > &, OutputType *) const, std::set< DependencyTicket > prerequisites_of_calc={ all_sources_ticket()})
 Declares an abstract-valued output port by specifying a model value of concrete type OutputType and a calculator function that is a class member function (method) with signature: More...
 
template<class MySystem , typename OutputType >
LeafOutputPort< T > & DeclareAbstractOutputPort (std::variant< std::string, UseDefaultName > name, void(MySystem::*calc)(const Context< T > &, OutputType *) const, std::set< DependencyTicket > prerequisites_of_calc={ all_sources_ticket()})
 Declares an abstract-valued output port by specifying only a calculator function that is a class member function (method) with signature: More...
 
template<class MySystem , typename OutputType >
 DRAKE_DEPRECATED ("2021-11-01", "This overload for DeclareAbstractOutputPort is rarely the best choice;" " it is unusual for a boutique allocation to return an abstract type by" " value rather than provide a model_value. If the default constructor" " or a model value cannot be used, use the overload that accepts an" " AllocCallback alloc_function instead.") LeafOutputPort< T > &DeclareAbstractOutputPort(std
 
 MALIPUT_DRAKE_DEMAND (this_ptr !=nullptr)
 
LeafOutputPort< T > & DeclareAbstractOutputPort (std::variant< std::string, UseDefaultName > name, typename LeafOutputPort< T >::AllocCallback alloc_function, typename LeafOutputPort< T >::CalcCallback calc_function, std::set< DependencyTicket > prerequisites_of_calc={ all_sources_ticket()})
 (Advanced) Declares an abstract-valued output port using the given allocator and calculator functions provided in their most generic forms. More...
 
LeafOutputPort< T > & DeclareStateOutputPort (std::variant< std::string, UseDefaultName > name, ContinuousStateIndex state_index)
 Declares a vector-valued output port whose value is the continuous state of this system. More...
 
LeafOutputPort< T > & DeclareStateOutputPort (std::variant< std::string, UseDefaultName > name, DiscreteStateIndex state_index)
 Declares a vector-valued output port whose value is the given discrete state group of this system. More...
 
LeafOutputPort< T > & DeclareStateOutputPort (std::variant< std::string, UseDefaultName > name, AbstractStateIndex state_index)
 Declares an abstract-valued output port whose value is the given abstract state of this system. More...
 

Make witness functions

Methods in this section are used by derived classes to make any witness functions useful for ensuring that integration ends a step upon entering particular times or states.

In contrast to other declaration methods (e.g., DeclareVectorOutputPort(), for which the System class creates and stores the objects and returns references to them, the witness function declaration functions return heap-allocated objects that the subclass of leaf system owns. This facilitates returning pointers to these objects in System::DoGetWitnessFunctions().

template<class MySystem >
std::unique_ptr< WitnessFunction< T > > MakeWitnessFunction (const std::string &description, const WitnessFunctionDirection &direction_type, T(MySystem::*calc)(const Context< T > &) const) const
 Constructs the witness function with the given description (used primarily for debugging and logging), direction type, and calculator function; and with no event object. More...
 
std::unique_ptr< WitnessFunction< T > > MakeWitnessFunction (const std::string &description, const WitnessFunctionDirection &direction_type, std::function< T(const Context< T > &)> calc) const
 Constructs the witness function with the given description (used primarily for debugging and logging), direction type, and calculator function; and with no event object. More...
 
template<class MySystem >
std::unique_ptr< WitnessFunction< T > > MakeWitnessFunction (const std::string &description, const WitnessFunctionDirection &direction_type, T(MySystem::*calc)(const Context< T > &) const, void(MySystem::*publish_callback)(const Context< T > &, const PublishEvent< T > &) const) const
 Constructs the witness function with the given description (used primarily for debugging and logging), direction type, calculator function, and publish event callback function for when this triggers. More...
 
template<class MySystem >
std::unique_ptr< WitnessFunction< T > > MakeWitnessFunction (const std::string &description, const WitnessFunctionDirection &direction_type, T(MySystem::*calc)(const Context< T > &) const, void(MySystem::*du_callback)(const Context< T > &, const DiscreteUpdateEvent< T > &, DiscreteValues< T > *) const) const
 Constructs the witness function with the given description (used primarily for debugging and logging), direction type, calculator function, and discrete update event callback function for when this triggers. More...
 
template<class MySystem >
std::unique_ptr< WitnessFunction< T > > MakeWitnessFunction (const std::string &description, const WitnessFunctionDirection &direction_type, T(MySystem::*calc)(const Context< T > &) const, void(MySystem::*uu_callback)(const Context< T > &, const UnrestrictedUpdateEvent< T > &, State< T > *) const) const
 Constructs the witness function with the given description (used primarily for debugging and logging), direction type, calculator function, and unrestricted update event callback function for when this triggers. More...
 
template<class MySystem >
std::unique_ptr< WitnessFunction< T > > MakeWitnessFunction (const std::string &description, const WitnessFunctionDirection &direction_type, T(MySystem::*calc)(const Context< T > &) const, const Event< T > &e) const
 Constructs the witness function with the given description (used primarily for debugging and logging), direction type, and calculator function, and with an object corresponding to the event that is to be dispatched when this witness function triggers. More...
 
std::unique_ptr< WitnessFunction< T > > MakeWitnessFunction (const std::string &description, const WitnessFunctionDirection &direction_type, std::function< T(const Context< T > &)> calc, const Event< T > &e) const
 Constructs the witness function with the given description (used primarily for debugging and logging), direction type, and calculator function, and with an object corresponding to the event that is to be dispatched when this witness function triggers. More...
 
template<class MySystem >
SystemConstraintIndex DeclareEqualityConstraint (void(MySystem::*calc)(const Context< T > &, VectorX< T > *) const, int count, std::string description)
 Declares a system constraint of the form f(context) = 0 by specifying a member function to use to calculate the (VectorX) constraint value with a signature: More...
 
SystemConstraintIndex DeclareEqualityConstraint (ContextConstraintCalc< T > calc, int count, std::string description)
 Declares a system constraint of the form f(context) = 0 by specifying a std::function to use to calculate the (Vector) constraint value with a signature: More...
 
template<class MySystem >
SystemConstraintIndex DeclareInequalityConstraint (void(MySystem::*calc)(const Context< T > &, VectorX< T > *) const, SystemConstraintBounds bounds, std::string description)
 Declares a system constraint of the form bounds.lower() <= calc(context) <= bounds.upper() by specifying a member function to use to calculate the (VectorX) constraint value with a signature: More...
 
SystemConstraintIndex DeclareInequalityConstraint (ContextConstraintCalc< T > calc, SystemConstraintBounds bounds, std::string description)
 Declares a system constraint of the form bounds.lower() <= calc(context) <= bounds.upper() by specifying a std::function to use to calculate the (Vector) constraint value with a signature: More...
 
virtual void DoPublish (const Context< T > &context, const std::vector< const PublishEvent< T > * > &events) const
 Derived-class event dispatcher for all simultaneous publish events in events. More...
 
virtual void DoCalcDiscreteVariableUpdates (const Context< T > &context, const std::vector< const DiscreteUpdateEvent< T > * > &events, DiscreteValues< T > *discrete_state) const
 Derived-class event dispatcher for all simultaneous discrete update events. More...
 
virtual void DoCalcUnrestrictedUpdate (const Context< T > &context, const std::vector< const UnrestrictedUpdateEvent< T > * > &events, State< T > *state) const
 Derived-class event dispatcher for all simultaneous unrestricted update events. More...
 

Additional Inherited Members

- Static Public Member Functions inherited from System< T >
template<typename U , template< typename > class S = ::maliput::drake::systems::System>
static std::unique_ptr< S< U > > ToScalarType (const S< T > &from)
 Creates a deep copy of from, transmogrified to use the scalar type selected by a template parameter. More...
 
static DependencyTicket accuracy_ticket ()
 Returns a ticket indicating dependence on the accuracy setting in the Context. More...
 
static DependencyTicket all_input_ports_ticket ()
 Returns a ticket indicating dependence on all input ports u of this system. More...
 
static DependencyTicket all_parameters_ticket ()
 Returns a ticket indicating dependence on all parameters p in this system, including numeric parameters pn, and abstract parameters pa. More...
 
static DependencyTicket all_sources_ticket ()
 Returns a ticket indicating dependence on every possible independent source value, including time, accuracy, state, input ports, and parameters (but not cache entries). More...
 
static DependencyTicket all_state_ticket ()
 Returns a ticket indicating dependence on all state variables x in this system, including continuous variables xc, discrete (numeric) variables xd, and abstract state variables xa. More...
 
static DependencyTicket configuration_ticket ()
 Returns a ticket indicating dependence on all source values that may affect configuration-dependent computations. More...
 
static DependencyTicket ke_ticket ()
 Returns a ticket for the cache entry that holds the kinetic energy calculation. More...
 
static DependencyTicket kinematics_ticket ()
 Returns a ticket indicating dependence on all source values that may affect configuration- or velocity-dependent computations. More...
 
static DependencyTicket nothing_ticket ()
 Returns a ticket indicating that a computation does not depend on any source value; that is, it is a constant. More...
 
static DependencyTicket pa_ticket ()
 Returns a ticket indicating dependence on all of the abstract parameters pa in the current Context. More...
 
static DependencyTicket pc_ticket ()
 Returns a ticket for the cache entry that holds the conservative power calculation. More...
 
static DependencyTicket pe_ticket ()
 Returns a ticket for the cache entry that holds the potential energy calculation. More...
 
static DependencyTicket pn_ticket ()
 Returns a ticket indicating dependence on all of the numerical parameters in the current Context. More...
 
static DependencyTicket pnc_ticket ()
 Returns a ticket for the cache entry that holds the non-conservative power calculation. More...
 
static DependencyTicket q_ticket ()
 Returns a ticket indicating that a computation depends on configuration state variables q. More...
 
static DependencyTicket time_ticket ()
 Returns a ticket indicating dependence on time. More...
 
static DependencyTicket v_ticket ()
 Returns a ticket indicating dependence on velocity state variables v. More...
 
static DependencyTicket xa_ticket ()
 Returns a ticket indicating dependence on all of the abstract state variables in the current Context. More...
 
static DependencyTicket xc_ticket ()
 Returns a ticket indicating dependence on all of the continuous state variables q, v, or z. More...
 
static DependencyTicket xcdot_ticket ()
 Returns a ticket for the cache entry that holds time derivatives of the continuous variables. More...
 
static DependencyTicket xd_ticket ()
 Returns a ticket indicating dependence on all of the numerical discrete state variables, in any discrete variable group. More...
 
static DependencyTicket z_ticket ()
 Returns a ticket indicating dependence on any or all of the miscellaneous continuous state variables z. More...
 

Constructor & Destructor Documentation

◆ ~LeafSystem()

~LeafSystem
override

◆ LeafSystem() [1/2]

LeafSystem
protected

Default constructor that declares no inputs, outputs, state, parameters, events, nor scalar-type conversion support (AutoDiff, etc.).

To enable AutoDiff support, use the SystemScalarConverter-based constructor.

◆ LeafSystem() [2/2]

LeafSystem ( SystemScalarConverter  converter)
explicitprotected

Constructor that declares no inputs, outputs, state, parameters, or events, but allows subclasses to declare scalar-type conversion support (AutoDiff, etc.).

The scalar-type conversion support will use converter. To enable scalar-type conversion support, pass a SystemTypeTag<S>{} where S must be the exact class of this being constructed.

See System Scalar Conversion for detailed background and examples related to scalar-type conversion support.

Member Function Documentation

◆ AddTriggeredWitnessFunctionToCompositeEventCollection()

void AddTriggeredWitnessFunctionToCompositeEventCollection ( Event< T > *  event,
CompositeEventCollection< T > *  events 
) const
finalprotectedvirtual

Add event to events due to a witness function triggering.

events should be allocated with this system's AllocateCompositeEventCollection. Neither event nor events can be nullptr. Additionally, event must contain event data (event->get_event_data() must not be nullptr) and the type of that data must be WitnessTriggeredEventData.

Implements System< T >.

◆ all_sources_ticket()

static DependencyTicket all_sources_ticket
staticprotected

Returns a ticket indicating dependence on every possible independent source value, including time, accuracy, state, input ports, and parameters (but not cache entries).

This is the default dependency for computations that have not specified anything more refined. It is equivalent to the set {all_sources_except_input_ports_ticket(), all_input_ports_ticket()}.

See also
cache_entry_ticket() to obtain a ticket for a cache entry.

◆ AllocateAbstractState()

std::unique_ptr< AbstractValues > AllocateAbstractState
protected

Returns a copy of the states declared in DeclareAbstractState() calls.

◆ AllocateContext()

std::unique_ptr< LeafContext< T > > AllocateContext

Shadows System<T>::AllocateContext to provide a more concrete return type LeafContext<T>.

◆ AllocateContinuousState()

std::unique_ptr< ContinuousState< T > > AllocateContinuousState
protected

Returns a copy of the state declared in the most recent DeclareContinuousState() call, or else a zero-sized state if that method has never been called.

◆ AllocateDiscreteState()

std::unique_ptr< DiscreteValues< T > > AllocateDiscreteState
protected

Returns a copy of the states declared in DeclareDiscreteState() calls.

◆ AllocateDiscreteVariables()

std::unique_ptr< DiscreteValues< T > > AllocateDiscreteVariables ( ) const
finalvirtual

Returns a DiscreteValues of the same dimensions as the discrete_state allocated in CreateDefaultContext.

The simulator will provide this state as the output argument to Update.

Implements System< T >.

◆ AllocateForcedDiscreteUpdateEventCollection()

std::unique_ptr< EventCollection< DiscreteUpdateEvent< T > > > AllocateForcedDiscreteUpdateEventCollection
override

◆ AllocateForcedPublishEventCollection()

std::unique_ptr< EventCollection< PublishEvent< T > > > AllocateForcedPublishEventCollection
override

◆ AllocateForcedUnrestrictedUpdateEventCollection()

std::unique_ptr< EventCollection< UnrestrictedUpdateEvent< T > > > AllocateForcedUnrestrictedUpdateEventCollection
override

◆ AllocateParameters()

std::unique_ptr< Parameters< T > > AllocateParameters
protected

Returns a copy of the parameters declared in DeclareNumericParameter() and DeclareAbstractParameter() calls.

◆ AllocateTimeDerivatives()

std::unique_ptr< ContinuousState< T > > AllocateTimeDerivatives ( ) const
finalvirtual

Returns a ContinuousState of the same size as the continuous_state allocated in CreateDefaultContext.

The simulator will provide this state as the output argument to EvalTimeDerivatives.

Implements System< T >.

◆ DeclareAbstractInputPort() [1/2]

InputPort< T > & DeclareAbstractInputPort ( const AbstractValue model_value)
protected

◆ DeclareAbstractInputPort() [2/2]

InputPort< T > & DeclareAbstractInputPort ( std::variant< std::string, UseDefaultName name,
const AbstractValue model_value 
)
protected

Declares an abstract-valued input port using the given model_value.

This is the best way to declare LeafSystem abstract input ports.

Any port connected to this input, and any call to FixValue for this input, must provide for values whose type matches this model_value.

See also
System::DeclareInputPort() for more information.

◆ DeclareAbstractOutputPort() [1/7]

std::enable_if_t<!std::is_same_v<OutputType, std::string>, LeafOutputPort<T>&> DeclareAbstractOutputPort ( const OutputType &  model_value,
void(MySystem::*)(const Context< T > &, OutputType *) const  calc,
std::set< DependencyTicket prerequisites_of_calc = {all_sources_ticket()} 
)
protected

◆ DeclareAbstractOutputPort() [2/7]

LeafOutputPort<T>& DeclareAbstractOutputPort ( OutputType(MySystem::*)() const  make,
void(MySystem::*)(const Context< T > &, OutputType *) const  calc,
std::set< DependencyTicket prerequisites_of_calc = { all_sources_ticket()} 
)
protected

◆ DeclareAbstractOutputPort() [3/7]

LeafOutputPort<T>& DeclareAbstractOutputPort ( std::variant< std::string, UseDefaultName name,
const OutputType &  model_value,
void(MySystem::*)(const Context< T > &, OutputType *) const  calc,
std::set< DependencyTicket prerequisites_of_calc = { all_sources_ticket()} 
)
protected

Declares an abstract-valued output port by specifying a model value of concrete type OutputType and a calculator function that is a class member function (method) with signature:

void MySystem::CalcOutputValue(const Context<T>&, OutputType*) const;

where MySystem must be a class derived from LeafSystem<T>. OutputType must be such that Value<OutputType> is permitted. Template arguments will be deduced and do not need to be specified.

See also
maliput::drake::Value

◆ DeclareAbstractOutputPort() [4/7]

LeafOutputPort< T > & DeclareAbstractOutputPort ( std::variant< std::string, UseDefaultName name,
typename LeafOutputPort< T >::AllocCallback  alloc_function,
typename LeafOutputPort< T >::CalcCallback  calc_function,
std::set< DependencyTicket prerequisites_of_calc = { all_sources_ticket()} 
)
protected

(Advanced) Declares an abstract-valued output port using the given allocator and calculator functions provided in their most generic forms.

If you have a member function available use one of the other signatures.

See also
LeafOutputPort::AllocCallback, LeafOutputPort::CalcCallback

◆ DeclareAbstractOutputPort() [5/7]

LeafOutputPort<T>& DeclareAbstractOutputPort ( std::variant< std::string, UseDefaultName name,
void(MySystem::*)(const Context< T > &, OutputType *) const  calc,
std::set< DependencyTicket prerequisites_of_calc = { all_sources_ticket()} 
)
protected

Declares an abstract-valued output port by specifying only a calculator function that is a class member function (method) with signature:

void MySystem::CalcOutputValue(const Context<T>&, OutputType*) const;

where MySystem is a class derived from LeafSystem<T>. OutputType is a concrete type such that Value<OutputType> is permitted, and must be default constructible, so that we can create a model value using Value<OutputType>{} (value initialized so numerical types will be zeroed in the model). Template arguments will be deduced and do not need to be specified.

Note
The default constructor will be called once immediately, and subsequent allocations will just copy the model value without invoking the constructor again. If you want the constructor invoked again at each allocation (not common), use one of the other signatures to explicitly provide a method for the allocator to call; that method can then invoke the OutputType default constructor.
See also
maliput::drake::Value

◆ DeclareAbstractOutputPort() [6/7]

LeafOutputPort< T > & DeclareAbstractOutputPort ( typename LeafOutputPort< T >::AllocCallback  alloc_function,
typename LeafOutputPort< T >::CalcCallback  calc_function,
std::set< DependencyTicket prerequisites_of_calc = { all_sources_ticket()} 
)
protected

◆ DeclareAbstractOutputPort() [7/7]

LeafOutputPort<T>& DeclareAbstractOutputPort ( void(MySystem::*)(const Context< T > &, OutputType *) const  calc,
std::set< DependencyTicket prerequisites_of_calc = { all_sources_ticket()} 
)
protected

◆ DeclareAbstractParameter()

int DeclareAbstractParameter ( const AbstractValue model_value)
protected

Declares an abstract parameter using the given model_value.

LeafSystem's default implementation of SetDefaultParameters() will reset parameters to their model values. Returns the index of the new parameter.

◆ DeclareAbstractState()

AbstractStateIndex DeclareAbstractState ( const AbstractValue abstract_state)
protected

Declares an abstract state.

Parameters
abstract_stateThe abstract state model value.
Returns
index of the declared abstract state.

◆ DeclareContinuousState() [1/4]

ContinuousStateIndex DeclareContinuousState ( const BasicVector< T > &  model_vector)
protected

Declares that this System should reserve continuous state with model_vector.size() miscellaneous state variables, stored in a vector cloned from model_vector.

Returns
index of the declared state (currently always zero).

◆ DeclareContinuousState() [2/4]

ContinuousStateIndex DeclareContinuousState ( const BasicVector< T > &  model_vector,
int  num_q,
int  num_v,
int  num_z 
)
protected

Declares that this System should reserve continuous state with num_q generalized positions, num_v generalized velocities, and num_z miscellaneous state variables, stored in a vector cloned from model_vector.

Aborts if model_vector has the wrong size. If the model_vector declares any VectorBase::GetElementBounds() constraints, they will be re-declared as inequality constraints on this system (see DeclareInequalityConstraint()).

Returns
index of the declared state (currently always zero).

◆ DeclareContinuousState() [3/4]

ContinuousStateIndex DeclareContinuousState ( int  num_q,
int  num_v,
int  num_z 
)
protected

Declares that this System should reserve continuous state with num_q generalized positions, num_v generalized velocities, and num_z miscellaneous state variables.

Returns
index of the declared state (currently always zero).

◆ DeclareContinuousState() [4/4]

ContinuousStateIndex DeclareContinuousState ( int  num_state_variables)
protected

Declares that this System should reserve continuous state with num_state_variables state variables, which have no second-order structure.

Returns
index of the declared state (currently always zero).

◆ DeclareDiscreteState() [1/3]

DiscreteStateIndex DeclareDiscreteState ( const BasicVector< T > &  model_vector)
protected

Declares a discrete state group with model_vector.size() state variables, stored in a vector cloned from model_vector (preserving the concrete type and value).

◆ DeclareDiscreteState() [2/3]

DiscreteStateIndex DeclareDiscreteState ( const Eigen::Ref< const VectorX< T >> &  vector)
protected

Declares a discrete state group with vector.size() state variables, stored in a BasicVector initialized with the contents of vector.

◆ DeclareDiscreteState() [3/3]

DiscreteStateIndex DeclareDiscreteState ( int  num_state_variables)
protected

Declares a discrete state group with num_state_variables state variables, stored in a BasicVector initialized to be all-zero.

If you want non-zero initial values, use an alternate DeclareDiscreteState() signature that accepts a model_vector parameter.

Precondition
num_state_variables must be non-negative.

◆ DeclareEqualityConstraint() [1/2]

SystemConstraintIndex DeclareEqualityConstraint ( ContextConstraintCalc< T >  calc,
int  count,
std::string  description 
)
protected

Declares a system constraint of the form f(context) = 0 by specifying a std::function to use to calculate the (Vector) constraint value with a signature:

void CalcConstraint(const Context<T>&, VectorX<T>*);
Parameters
countis the dimension of the VectorX output.
descriptionshould be a human-readable phrase.
Returns
The index of the constraint.
See also
SystemConstraint<T> for more information about the meaning of these constraints.

◆ DeclareEqualityConstraint() [2/2]

SystemConstraintIndex DeclareEqualityConstraint ( void(MySystem::*)(const Context< T > &, VectorX< T > *) const  calc,
int  count,
std::string  description 
)
protected

Declares a system constraint of the form f(context) = 0 by specifying a member function to use to calculate the (VectorX) constraint value with a signature:

void MySystem::CalcConstraint(const Context<T>&, VectorX<T>*) const;
Parameters
countis the dimension of the VectorX output.
descriptionshould be a human-readable phrase.
Returns
The index of the constraint. Template arguments will be deduced and do not need to be specified.
See also
SystemConstraint<T> for more information about the meaning of these constraints.

◆ DeclareForcedDiscreteUpdateEvent()

void DeclareForcedDiscreteUpdateEvent ( EventStatus(MySystem::*)(const Context< T > &, DiscreteValues< T > *) const  update)
protected

Declares a function that is called whenever a user directly calls CalcDiscreteVariableUpdates(const Context&, DiscreteValues<T>*).

Multiple calls to DeclareForcedDiscreteUpdateEvent() will cause multiple handlers to be called upon a call to CalcDiscreteVariableUpdates(); these handlers which will be called with the same const Context in arbitrary order. The handler should be a class member function (method) with this signature:

EventStatus MySystem::MyDiscreteVariableUpdates(const Context<T>&,
DiscreteValues<T>*);

where MySystem is a class derived from LeafSystem<T> and the method name is arbitrary.

See Declare forced events for more information.

Precondition
this must be dynamic_cast-able to MySystem.
update must not be null.

◆ DeclareForcedPublishEvent()

void DeclareForcedPublishEvent ( EventStatus(MySystem::*)(const Context< T > &) const  publish)
protected

Declares a function that is called whenever a user directly calls Publish(const Context&).

Multiple calls to DeclareForcedPublishEvent() will cause multiple handlers to be called upon a call to Publish(); these handlers which will be called with the same const Context in arbitrary order. The handler should be a class member function (method) with this signature:

EventStatus MySystem::MyPublish(const Context<T>&) const;

where MySystem is a class derived from LeafSystem<T> and the method name is arbitrary.

See Declare forced events for more information.

Precondition
this must be dynamic_cast-able to MySystem.
publish must not be null.

◆ DeclareForcedUnrestrictedUpdateEvent()

void DeclareForcedUnrestrictedUpdateEvent ( EventStatus(MySystem::*)(const Context< T > &, State< T > *) const  update)
protected

Declares a function that is called whenever a user directly calls CalcUnrestrictedUpdate(const Context&, State<T>*).

Multiple calls to DeclareForcedUnrestrictedUpdateEvent() will cause multiple handlers to be called upon a call to CalcUnrestrictedUpdate(); these handlers which will be called with the same const Context in arbitrary order.The handler should be a class member function (method) with this signature:

EventStatus MySystem::MyUnrestrictedUpdates(const Context<T>&,
State<T>*);

where MySystem is a class derived from LeafSystem<T> and the method name is arbitrary.

See Declare forced events for more information.

Precondition
this must be dynamic_cast-able to MySystem.
update must not be null.

◆ DeclareImplicitTimeDerivativesResidualSize()

void DeclareImplicitTimeDerivativesResidualSize ( int  n)
protected

(Advanced) Overrides the default size for the implicit time derivatives residual.

If no value is set, the default size is n=num_continuous_states().

Parameters
[in]nThe size of the residual vector output argument of System::CalcImplicitTimeDerivativesResidual(). If n <= 0 restore to the default, num_continuous_states().
See also
implicit_time_derivatives_residual_size()
System::CalcImplicitTimeDerivativesResidual()

◆ DeclareInequalityConstraint() [1/2]

SystemConstraintIndex DeclareInequalityConstraint ( ContextConstraintCalc< T >  calc,
SystemConstraintBounds  bounds,
std::string  description 
)
protected

Declares a system constraint of the form bounds.lower() <= calc(context) <= bounds.upper() by specifying a std::function to use to calculate the (Vector) constraint value with a signature:

void CalcConstraint(const Context<T>&, VectorX<T>*);
Parameters
descriptionshould be a human-readable phrase.
Returns
The index of the constraint.
See also
SystemConstraint<T> for more information about the meaning of these constraints.

◆ DeclareInequalityConstraint() [2/2]

SystemConstraintIndex DeclareInequalityConstraint ( void(MySystem::*)(const Context< T > &, VectorX< T > *) const  calc,
SystemConstraintBounds  bounds,
std::string  description 
)
protected

Declares a system constraint of the form bounds.lower() <= calc(context) <= bounds.upper() by specifying a member function to use to calculate the (VectorX) constraint value with a signature:

void MySystem::CalcConstraint(const Context<T>&, VectorX<T>*) const;
Parameters
descriptionshould be a human-readable phrase.
Returns
The index of the constraint. Template arguments will be deduced and do not need to be specified.
See also
SystemConstraint<T> for more information about the meaning of these constraints.

◆ DeclareInitializationDiscreteUpdateEvent()

void DeclareInitializationDiscreteUpdateEvent ( EventStatus(MySystem::*)(const Context< T > &, DiscreteValues< T > *) const  update)
protected

Declares that a DiscreteUpdate event should occur at initialization and that it should invoke the given event handler method.

The handler should be a class member function (method) with this signature:

EventStatus MySystem::MyUpdate(const Context<T>&,
DiscreteValues<T>*) const;

where MySystem is a class derived from LeafSystem<T> and the method name is arbitrary.

See Declare initialization events for more information.

Precondition
this must be dynamic_cast-able to MySystem.
update must not be null.
See also
DeclareInitializationPublishEvent()
DeclareInitializationUnrestrictedUpdateEvent()
DeclareInitializationEvent()

◆ DeclareInitializationEvent()

void DeclareInitializationEvent ( const EventType &  event)
protected

(Advanced) Declares that a particular Event object should be dispatched at initialization.

This is the most general form for declaring initialization events and most users should use one of the other methods in this group instead.

See also
DeclareInitializationPublishEvent()
DeclareInitializationDiscreteUpdateEvent()
DeclareInitializationUnrestrictedUpdate()

See Declare initialization events for more information.

Depending on the type of event, on initialization it will be passed to the Publish, DiscreteUpdate, or UnrestrictedUpdate event dispatcher. If the event object contains a handler function, Drake's default dispatchers will invoke that handler. If not, then no further action is taken. Thus an event with no handler has no effect unless its dispatcher has been overridden. We strongly recommend that you do not override the dispatcher and instead do supply a handler.

The given event object is deep-copied (cloned), and the copy is stored internally so you do not need to keep the object around after this call.

Precondition
event's associated trigger type must be TriggerType::kUnknown or already set to TriggerType::kInitialization.

◆ DeclareInitializationPublishEvent()

void DeclareInitializationPublishEvent ( EventStatus(MySystem::*)(const Context< T > &) const  publish)
protected

Declares that a Publish event should occur at initialization and that it should invoke the given event handler method.

The handler should be a class member function (method) with this signature:

EventStatus MySystem::MyPublish(const Context<T>&) const;

where MySystem is a class derived from LeafSystem<T> and the method name is arbitrary.

See Declare initialization events for more information.

Precondition
this must be dynamic_cast-able to MySystem.
publish must not be null.
See also
DeclareInitializationDiscreteUpdateEvent()
DeclareInitializationUnrestrictedUpdateEvent()
DeclareInitializationEvent()

◆ DeclareInitializationUnrestrictedUpdateEvent()

void DeclareInitializationUnrestrictedUpdateEvent ( EventStatus(MySystem::*)(const Context< T > &, State< T > *) const  update)
protected

Declares that an UnrestrictedUpdate event should occur at initialization and that it should invoke the given event handler method.

The handler should be a class member function (method) with this signature:

EventStatus MySystem::MyUpdate(const Context<T>&,
State<T>*) const;

where MySystem is a class derived from LeafSystem<T> and the method name is arbitrary.

See Declare initialization events for more information.

Precondition
this must be dynamic_cast-able to MySystem.
update must not be null.
See also
DeclareInitializationPublishEvent()
DeclareInitializationDiscreteUpdateEvent()
DeclareInitializationEvent()

◆ DeclareNumericParameter()

int DeclareNumericParameter ( const BasicVector< T > &  model_vector)
protected

Declares a numeric parameter using the given model_vector.

LeafSystem's default implementation of SetDefaultParameters() will reset parameters to their model vectors. If the model_vector declares any VectorBase::GetElementBounds() constraints, they will be re-declared as inequality constraints on this system (see DeclareInequalityConstraint()). Returns the index of the new parameter.

◆ DeclarePeriodicDiscreteUpdate()

void DeclarePeriodicDiscreteUpdate ( double  period_sec,
double  offset_sec = 0 
)
protected

(To be deprecated) Declares a periodic discrete update event that invokes the DiscreteUpdate() dispatcher but does not provide a handler function.

This does guarantee that a Simulator step will end exactly at the update time, but otherwise has no effect unless the DoDiscreteUpdate() dispatcher has been overloaded (not recommended).

◆ DeclarePeriodicDiscreteUpdateEvent() [1/2]

void DeclarePeriodicDiscreteUpdateEvent ( double  period_sec,
double  offset_sec,
EventStatus(MySystem::*)(const Context< T > &, DiscreteValues< T > *) const  update 
)
protected

Declares that a DiscreteUpdate event should occur periodically and that it should invoke the given event handler method.

The handler should be a class member function (method) with this signature:

EventStatus MySystem::MyUpdate(const Context<T>&,
DiscreteValues<T>*) const;

where MySystem is a class derived from LeafSystem<T> and the method name is arbitrary.

See Declare periodic events for more information.

Precondition
this must be dynamic_cast-able to MySystem.
update must not be null.
See also
DeclarePeriodicPublishEvent()
DeclarePeriodicUnrestrictedUpdateEvent()
DeclarePeriodicEvent()

◆ DeclarePeriodicDiscreteUpdateEvent() [2/2]

void DeclarePeriodicDiscreteUpdateEvent ( double  period_sec,
double  offset_sec,
void(MySystem::*)(const Context< T > &, DiscreteValues< T > *) const  update 
)
protected

This variant accepts a handler that is assumed to succeed rather than one that returns an EventStatus result.

The handler signature is:

void MySystem::MyUpdate(const Context<T>&,
DiscreteValues<T>*) const;

See the other signature for more information.

◆ DeclarePeriodicEvent()

void DeclarePeriodicEvent ( double  period_sec,
double  offset_sec,
const EventType &  event 
)
protected

(Advanced) Declares that a particular Event object should be dispatched periodically.

This is the most general form for declaring periodic events and most users should use one of the other methods in this group instead.

See also
DeclarePeriodicPublishEvent()
DeclarePeriodicDiscreteUpdateEvent()
DeclarePeriodicUnrestrictedUpdateEvent()

See Declare periodic events for more information.

Depending on the type of event, when triggered it will be passed to the Publish, DiscreteUpdate, or UnrestrictedUpdate event dispatcher. If the event object contains a handler function, Drake's default dispatchers will invoke that handler. If not, then no further action is taken. Thus an event with no handler has no effect unless its dispatcher has been overridden. We strongly recommend that you do not override the dispatcher and instead do supply a handler.

The given event object is deep-copied (cloned), and the copy is stored internally so you do not need to keep the object around after this call.

Precondition
event's associated trigger type must be TriggerType::kUnknown or already set to TriggerType::kPeriodic.

◆ DeclarePeriodicPublish()

void DeclarePeriodicPublish ( double  period_sec,
double  offset_sec = 0 
)
protected

(To be deprecated) Declares a periodic publish event that invokes the Publish() dispatcher but does not provide a handler function.

This does guarantee that a Simulator step will end exactly at the publish time, but otherwise has no effect unless the DoPublish() dispatcher has been overloaded (not recommended).

◆ DeclarePeriodicPublishEvent() [1/2]

void DeclarePeriodicPublishEvent ( double  period_sec,
double  offset_sec,
EventStatus(MySystem::*)(const Context< T > &) const  publish 
)
protected

Declares that a Publish event should occur periodically and that it should invoke the given event handler method.

The handler should be a class member function (method) with this signature:

EventStatus MySystem::MyPublish(const Context<T>&) const;

where MySystem is a class derived from LeafSystem<T> and the method name is arbitrary.

See Declare periodic events for more information.

Precondition
this must be dynamic_cast-able to MySystem.
publish must not be null.
See also
DeclarePeriodicDiscreteUpdateEvent()
DeclarePeriodicUnrestrictedUpdateEvent()
DeclarePeriodicEvent()

◆ DeclarePeriodicPublishEvent() [2/2]

void DeclarePeriodicPublishEvent ( double  period_sec,
double  offset_sec,
void(MySystem::*)(const Context< T > &) const  publish 
)
protected

This variant accepts a handler that is assumed to succeed rather than one that returns an EventStatus result.

The handler signature is:

void MySystem::MyPublish(const Context<T>&) const;

See the other signature for more information.

◆ DeclarePeriodicUnrestrictedUpdate()

void DeclarePeriodicUnrestrictedUpdate ( double  period_sec,
double  offset_sec = 0 
)
protected

(To be deprecated) Declares a periodic unrestricted update event that invokes the UnrestrictedUpdate() dispatcher but does not provide a handler function.

This does guarantee that a Simulator step will end exactly at the update time, but otherwise has no effect unless the DoUnrestrictedUpdate() dispatcher has been overloaded (not recommended).

◆ DeclarePeriodicUnrestrictedUpdateEvent() [1/2]

void DeclarePeriodicUnrestrictedUpdateEvent ( double  period_sec,
double  offset_sec,
EventStatus(MySystem::*)(const Context< T > &, State< T > *) const  update 
)
protected

Declares that an UnrestrictedUpdate event should occur periodically and that it should invoke the given event handler method.

The handler should be a class member function (method) with this signature:

EventStatus MySystem::MyUpdate(const Context<T>&, State<T>*) const;

where MySystem is a class derived from LeafSystem<T> and the method name is arbitrary.

See Declare periodic events for more information.

Precondition
this must be dynamic_cast-able to MySystem.
update must not be null.
See also
DeclarePeriodicPublishEvent()
DeclarePeriodicDiscreteUpdateEvent()
DeclarePeriodicEvent()

◆ DeclarePeriodicUnrestrictedUpdateEvent() [2/2]

void DeclarePeriodicUnrestrictedUpdateEvent ( double  period_sec,
double  offset_sec,
void(MySystem::*)(const Context< T > &, State< T > *) const  update 
)
protected

This variant accepts a handler that is assumed to succeed rather than one that returns an EventStatus result.

The handler signature is:

void MySystem::MyUpdate(const Context<T>&, State<T>*) const;

See the other signature for more information.

◆ DeclarePerStepDiscreteUpdateEvent()

void DeclarePerStepDiscreteUpdateEvent ( EventStatus(MySystem::*)(const Context< T > &, DiscreteValues< T > *) const  update)
protected

Declares that a DiscreteUpdate event should occur at the start of every trajectory-advancing step and that it should invoke the given event handler method.

The handler should be a class member function (method) with this signature:

EventStatus MySystem::MyUpdate(const Context<T>&,
DiscreteValues<T>*) const;

where MySystem is a class derived from LeafSystem<T> and the method name is arbitrary.

See Declare per-step events for more information.

Precondition
this must be dynamic_cast-able to MySystem.
update must not be null.
See also
DeclarePerStepPublishEvent()
DeclarePerStepUnrestrictedUpdateEvent()
DeclarePerStepEvent()

◆ DeclarePerStepEvent()

void DeclarePerStepEvent ( const EventType &  event)
protected

(Advanced) Declares that a particular Event object should be dispatched at every trajectory-advancing step.

Publish events are dispatched at the end of initialization and at the end of each step. Discrete- and unrestricted update events are dispatched at the start of each step. This is the most general form for declaring per-step events and most users should use one of the other methods in this group instead.

See also
DeclarePerStepPublishEvent()
DeclarePerStepDiscreteUpdateEvent()
DeclarePerStepUnrestrictedUpdateEvent()

See Declare per-step events for more information.

Depending on the type of event, at each step it will be passed to the Publish, DiscreteUpdate, or UnrestrictedUpdate event dispatcher. If the event object contains a handler function, Drake's default dispatchers will invoke that handler. If not, then no further action is taken. Thus an event with no handler has no effect unless its dispatcher has been overridden. We strongly recommend that you do not override the dispatcher and instead do supply a handler.

The given event object is deep-copied (cloned), and the copy is stored internally so you do not need to keep the object around after this call.

Precondition
event's associated trigger type must be TriggerType::kUnknown or already set to TriggerType::kPerStep.

◆ DeclarePerStepPublishEvent()

void DeclarePerStepPublishEvent ( EventStatus(MySystem::*)(const Context< T > &) const  publish)
protected

Declares that a Publish event should occur at initialization and at the end of every trajectory-advancing step and that it should invoke the given event handler method.

The handler should be a class member function (method) with this signature:

EventStatus MySystem::MyPublish(const Context<T>&) const;

where MySystem is a class derived from LeafSystem<T> and the method name is arbitrary.

Warning
These per-step publish events are independent of the Simulator's optional "publish every time step" and "publish at initialization" features. Generally if you are declaring per-step publish events yourself you should turn off those Simulation options.

See Declare per-step events for more information.

Precondition
this must be dynamic_cast-able to MySystem.
publish must not be null.
See also
DeclarePerStepDiscreteUpdateEvent()
DeclarePerStepUnrestrictedUpdateEvent()
DeclarePerStepEvent()
Simulator::set_publish_at_initialization()
Simulator::set_publish_every_time_step()

◆ DeclarePerStepUnrestrictedUpdateEvent()

void DeclarePerStepUnrestrictedUpdateEvent ( EventStatus(MySystem::*)(const Context< T > &, State< T > *) const  update)
protected

Declares that an UnrestrictedUpdate event should occur at the start of every trajectory-advancing step and that it should invoke the given event handler method.

The handler should be a class member function (method) with this signature:

EventStatus MySystem::MyUpdate(const Context<T>&,
State<T>*) const;

where MySystem is a class derived from LeafSystem<T> and the method name is arbitrary.

See Declare per-step events for more information.

Precondition
this must be dynamic_cast-able to MySystem.
update must not be null.
See also
DeclarePerStepPublishEvent()
DeclarePerStepDiscreteUpdateEvent()
DeclarePerStepEvent()

◆ DeclareStateOutputPort() [1/3]

LeafOutputPort< T > & DeclareStateOutputPort ( std::variant< std::string, UseDefaultName name,
AbstractStateIndex  state_index 
)
protected

Declares an abstract-valued output port whose value is the given abstract state of this system.

@pydrake_mkdoc_identifier{abstract}

◆ DeclareStateOutputPort() [2/3]

LeafOutputPort< T > & DeclareStateOutputPort ( std::variant< std::string, UseDefaultName name,
ContinuousStateIndex  state_index 
)
protected

Declares a vector-valued output port whose value is the continuous state of this system.

Parameters
state_indexmust be ContinuousStateIndex(0) for now, since LeafSystem only supports a single continuous state group at the moment. @pydrake_mkdoc_identifier{continuous}

◆ DeclareStateOutputPort() [3/3]

LeafOutputPort< T > & DeclareStateOutputPort ( std::variant< std::string, UseDefaultName name,
DiscreteStateIndex  state_index 
)
protected

Declares a vector-valued output port whose value is the given discrete state group of this system.

@pydrake_mkdoc_identifier{discrete}

◆ DeclareVectorInputPort() [1/3]

InputPort< T > & DeclareVectorInputPort ( const BasicVector< T > &  model_vector,
std::optional< RandomDistribution random_type = std::nullopt 
)
protected

◆ DeclareVectorInputPort() [2/3]

InputPort< T > & DeclareVectorInputPort ( std::variant< std::string, UseDefaultName name,
const BasicVector< T > &  model_vector,
std::optional< RandomDistribution random_type = std::nullopt 
)
protected

Declares a vector-valued input port using the given model_vector.

This is the best way to declare LeafSystem input ports that require subclasses of BasicVector. The port's size and type will be the same as model_vector. If the port is intended to model a random noise or disturbance input, random_type can (optionally) be used to label it as such. If the model_vector declares any VectorBase::GetElementBounds() constraints, they will be re-declared as inequality constraints on this system (see DeclareInequalityConstraint()).

See also
System::DeclareInputPort() for more information. @pydrake_mkdoc_identifier{3args_model_vector}

◆ DeclareVectorInputPort() [3/3]

InputPort< T > & DeclareVectorInputPort ( std::variant< std::string, UseDefaultName name,
int  size,
std::optional< RandomDistribution random_type = std::nullopt 
)
protected

Declares a vector-valued input port with type BasicVector and size size.

If the port is intended to model a random noise or disturbance input, random_type can (optionally) be used to label it as such.

See also
System::DeclareInputPort() for more information. @pydrake_mkdoc_identifier{3args_size}

◆ DeclareVectorOutputPort() [1/8]

LeafOutputPort< T > & DeclareVectorOutputPort ( const BasicVector< T > &  model_vector,
typename LeafOutputPort< T >::CalcVectorCallback  vector_calc_function,
std::set< DependencyTicket prerequisites_of_calc = {all_sources_ticket()} 
)
protected

◆ DeclareVectorOutputPort() [2/8]

LeafOutputPort<T>& DeclareVectorOutputPort ( const BasicVectorSubtype &  model_vector,
void(MySystem::*)(const Context< T > &, BasicVectorSubtype *) const  calc,
std::set< DependencyTicket prerequisites_of_calc = { all_sources_ticket()} 
)
protected

◆ DeclareVectorOutputPort() [3/8]

LeafOutputPort< T > & DeclareVectorOutputPort ( std::variant< std::string, UseDefaultName name,
const BasicVector< T > &  model_vector,
typename LeafOutputPort< T >::CalcVectorCallback  vector_calc_function,
std::set< DependencyTicket prerequisites_of_calc = {all_sources_ticket()} 
)
protected

(Advanced) Declares a vector-valued output port using the given model_vector and a function for calculating the port's value at runtime.

The port's size will be model_vector.size(), and the default allocator for the port will be model_vector.Clone(). Note that this takes the calculator function in its most generic form; if you have a member function available use one of the other signatures.

See also
LeafOutputPort::CalcVectorCallback @pydrake_mkdoc_identifier{4args_model_vector}

◆ DeclareVectorOutputPort() [4/8]

LeafOutputPort<T>& DeclareVectorOutputPort ( std::variant< std::string, UseDefaultName name,
const BasicVectorSubtype &  model_vector,
void(MySystem::*)(const Context< T > &, BasicVectorSubtype *) const  calc,
std::set< DependencyTicket prerequisites_of_calc = { all_sources_ticket()} 
)
protected

Declares a vector-valued output port by specifying (1) a model vector of type BasicVectorSubtype derived from BasicVector and initialized to the correct size and desired initial value, and (2) a calculator function that is a class member function (method) with signature:

void MySystem::CalcOutputVector(const Context<T>&,
BasicVectorSubtype*) const;

where MySystem is a class derived from LeafSystem<T>. Template arguments will be deduced and do not need to be specified. @exclude_from_pydrake_mkdoc{Not bound in pydrake.}

◆ DeclareVectorOutputPort() [5/8]

LeafOutputPort<T>& DeclareVectorOutputPort ( std::variant< std::string, UseDefaultName name,
int  size,
typename LeafOutputPort< T >::CalcVectorCallback  vector_calc_function,
std::set< DependencyTicket prerequisites_of_calc = { all_sources_ticket()} 
)
protected

(Advanced) Declares a vector-valued output port with type BasicVector<T> and size size, using the maliput::drake::dummy_value<T>, which is NaN when T = double.

vector_calc_function is a function for calculating the port's value at runtime. Note that this takes the calculator function in its most generic form; if you have a member function available use one of the other signatures.

See also
LeafOutputPort::CalcVectorCallback @pydrake_mkdoc_identifier{4args_size}

◆ DeclareVectorOutputPort() [6/8]

LeafOutputPort<T>& DeclareVectorOutputPort ( std::variant< std::string, UseDefaultName name,
int  size,
void(MySystem::*)(const Context< T > &, BasicVector< T > *) const  calc,
std::set< DependencyTicket prerequisites_of_calc = { all_sources_ticket()} 
)
protected

Declares a vector-valued output port with type BasicVector and size size, using the maliput::drake::dummy_value<T>, which is NaN when T = double.

calc is a calculator function that is a class member function (method) with signature:

void MySystem::CalcOutputVector(const Context<T>&,
BasicVector<T>*) const;

where MySystem is a class derived from LeafSystem<T>. Template arguments will be deduced and do not need to be specified. @exclude_from_pydrake_mkdoc{Not bound in pydrake.}

◆ DeclareVectorOutputPort() [7/8]

LeafOutputPort<T>& DeclareVectorOutputPort ( std::variant< std::string, UseDefaultName name,
void(MySystem::*)(const Context< T > &, BasicVectorSubtype *) const  calc,
std::set< DependencyTicket prerequisites_of_calc = { all_sources_ticket()} 
)
protected

Declares a vector-valued output port by specifying only a calculator function that is a class member function (method) with signature:

void MySystem::CalcOutputVector(const Context<T>&,
BasicVectorSubtype*) const;

where MySystem is a class derived from LeafSystem<T> and BasicVectorSubtype is derived from BasicVector<T> and has a suitable default constructor that allocates a vector of the expected size. This will use BasicVectorSubtype{} (that is, the default constructor) to produce a model vector for the output port's value. Template arguments will be deduced and do not need to be specified.

Note
The default constructor will be called once immediately, and subsequent allocations will just copy the model value without invoking the constructor again. If you want the constructor invoked again at each allocation (not common), use one of the other signatures to explicitly provide a method for the allocator to call; that method can then invoke the BasicVectorSubtype default constructor. @exclude_from_pydrake_mkdoc{Not bound in pydrake.}

◆ DeclareVectorOutputPort() [8/8]

LeafOutputPort<T>& DeclareVectorOutputPort ( void(MySystem::*)(const Context< T > &, BasicVectorSubtype *) const  calc,
std::set< DependencyTicket prerequisites_of_calc = { all_sources_ticket()} 
)
protected

◆ DoAllocateContext()

std::unique_ptr< ContextBase > DoAllocateContext
final

◆ DoCalcDiscreteVariableUpdates()

void DoCalcDiscreteVariableUpdates ( const Context< T > &  context,
const std::vector< const DiscreteUpdateEvent< T > * > &  events,
DiscreteValues< T > *  discrete_state 
) const
protectedvirtual

Derived-class event dispatcher for all simultaneous discrete update events.

Override this in your derived LeafSystem only if you require behavior other than the default dispatch behavior (not common). The default behavior is to traverse events in the arbitrary order they appear in events, and for each event that has a callback function, to invoke the callback with context, that event, and discrete_state. Note that the same (possibly modified) discrete_state is passed to subsequent callbacks.

Do not override this just to handle an event – instead declare the event and a handler callback for it using one of the Declare...DiscreteUpdateEvent() methods.

This method is called only from the virtual DispatchDiscreteVariableUpdateHandler(), which is only called from the public non-virtual CalcDiscreteVariableUpdates(), which will already have error-checked the parameters so you don't have to. In particular, implementations may assume that context is valid; that discrete_state is non-null, and that the referenced object has the same constituent structure as was produced by AllocateDiscreteVariables().

Parameters
[in]contextThe "before" state.
[in]eventsAll the discrete update events that need handling.
[in,out]discrete_stateThe current state of the system on input; the desired state of the system on return.

◆ DoCalcNextUpdateTime()

void DoCalcNextUpdateTime ( const Context< T > &  context,
CompositeEventCollection< T > *  events,
T *  time 
) const
overrideprotectedvirtual

Computes the next update time based on the configured periodic events, for scalar types that are arithmetic, or aborts for scalar types that are not arithmetic.

Subclasses that require aperiodic events should override, but be sure to invoke the parent class implementation at the start of the override if you want periodic events to continue to be handled.

Postcondition
time is set to a value greater than or equal to context.get_time() on return.
Warning
If you override this method, think carefully before setting time to context.get_time() on return, which can inadvertently cause simulations of systems derived from LeafSystem to loop interminably. Such a loop will occur if, for example, the event(s) does not modify the state.

Reimplemented from System< T >.

◆ DoCalcUnrestrictedUpdate()

void DoCalcUnrestrictedUpdate ( const Context< T > &  context,
const std::vector< const UnrestrictedUpdateEvent< T > * > &  events,
State< T > *  state 
) const
protectedvirtual

Derived-class event dispatcher for all simultaneous unrestricted update events.

Override this in your derived LeafSystem only if you require behavior other than the default dispatch behavior (not common). The default behavior is to traverse events in the arbitrary order they appear in events, and for each event that has a callback function, to invoke the callback with context, that event, and state. Note that the same (possibly modified) state is passed to subsequent callbacks.

Do not override this just to handle an event – instead declare the event and a handler callback for it using one of the Declare...UnrestrictedUpdateEvent() methods.

This method is called only from the virtual DispatchUnrestrictedUpdateHandler(), which is only called from the non-virtual public CalcUnrestrictedUpdate(), which will already have error-checked the parameters so you don't have to. In particular, implementations may assume that the context is valid; that state is non-null, and that the referenced object has the same constituent structure as the state in context.

Parameters
[in]contextThe "before" state that is to be used to calculate the returned state update.
[in]eventsAll the unrestricted update events that need handling.
[in,out]stateThe current state of the system on input; the desired state of the system on return.

◆ DoCalcWitnessValue()

T DoCalcWitnessValue ( const Context< T > &  context,
const WitnessFunction< T > &  witness_func 
) const
finalprotectedvirtual

Derived classes will implement this method to evaluate a witness function at the given context.

Implements System< T >.

◆ DoMakeLeafContext()

std::unique_ptr< LeafContext< T > > DoMakeLeafContext
protectedvirtual

Provides a new instance of the leaf context for this system.

Derived leaf systems with custom derived leaf system contexts should override this to provide a context of the appropriate type. The returned context should be "empty"; invoked by AllocateContext(), the caller will take the responsibility to initialize the core LeafContext data. The default implementation provides a default-constructed LeafContext<T>.

◆ DoPublish()

void DoPublish ( const Context< T > &  context,
const std::vector< const PublishEvent< T > * > &  events 
) const
protectedvirtual

Derived-class event dispatcher for all simultaneous publish events in events.

Override this in your derived LeafSystem only if you require behavior other than the default dispatch behavior (not common). The default behavior is to traverse events in the arbitrary order they appear in events, and for each event that has a callback function, to invoke the callback with context and that event.

Do not override this just to handle an event – instead declare the event and a handler callback for it using one of the Declare...PublishEvent() methods.

This method is called only from the virtual DispatchPublishHandler, which is only called from the public non-virtual Publish(), which will have already error-checked context so you may assume that it is valid.

Parameters
[in]contextConst current context.
[in]eventsAll the publish events that need handling.

◆ DoValidateAllocatedLeafContext()

virtual void DoValidateAllocatedLeafContext ( const LeafContext< T > &  context) const
protectedvirtual

Derived classes that impose restrictions on what resources are permitted should check those restrictions by implementing this.

For example, a derived class might require a single input and single output. Note that the supplied Context will be complete except that input and output dependencies on peer and parent subcontexts will not yet have been set up, so you may not consider them for validation. The default implementation does nothing.

◆ DRAKE_DEPRECATED()

DRAKE_DEPRECATED ( "2021-11-01"  ,
"This overload for DeclareAbstractOutputPort is rarely the best choice;" " it is unusual for a boutique allocation to return an abstract type by" " value rather than provide a model_value. If the default constructor" " or a model value cannot be  used,
use the overload that accepts an" " AllocCallback alloc_function instead."   
) &
protected

◆ GetDirectFeedthroughs()

std::multimap< int, int > GetDirectFeedthroughs
final

◆ GetGraphvizFragment()

void GetGraphvizFragment ( int  max_depth,
std::stringstream *  dot 
) const
overrideprotectedvirtual

Emits a graphviz fragment for this System.

Leaf systems are visualized as records. For instance, a leaf system with 2 inputs and 1 output is:

123456 [shape= record, label="name | {<u0> 0 |<y0> 0} | {<u1> 1 | }"];

which looks like:

+------------+----+
| name  | u0 | u1 |
|       | y0 |    |
+-------+----+----+

Reimplemented from System< T >.

◆ GetGraphvizInputPortToken()

void GetGraphvizInputPortToken ( const InputPort< T > &  port,
int  max_depth,
std::stringstream *  dot 
) const
finalprotectedvirtual

Appends a fragment to the dot stream identifying the graphviz node representing port.

Does nothing by default.

Reimplemented from System< T >.

◆ GetGraphvizOutputPortToken()

void GetGraphvizOutputPortToken ( const OutputPort< T > &  port,
int  max_depth,
std::stringstream *  dot 
) const
finalprotectedvirtual

Appends a fragment to the dot stream identifying the graphviz node representing port.

Does nothing by default.

Reimplemented from System< T >.

◆ GetMutableNumericParameter()

U<T>& GetMutableNumericParameter ( Context< T > *  context,
int  index 
) const
protected

Extracts the numeric parameters of type U from the context at index.

Asserts if the context is not a LeafContext, or if it does not have a vector-valued parameter of type U at index.

◆ GetNumericParameter()

const U<T>& GetNumericParameter ( const Context< T > &  context,
int  index 
) const
protected

Extracts the numeric parameters of type U from the context at index.

Asserts if the context is not a LeafContext, or if it does not have a vector-valued parameter of type U at index.

◆ MakeWitnessFunction() [1/7]

std::unique_ptr< WitnessFunction< T > > MakeWitnessFunction ( const std::string &  description,
const WitnessFunctionDirection direction_type,
std::function< T(const Context< T > &)>  calc 
) const
protected

Constructs the witness function with the given description (used primarily for debugging and logging), direction type, and calculator function; and with no event object.

Note
In order for the witness function to be used, you MUST overload System::DoGetWitnessFunctions().

◆ MakeWitnessFunction() [2/7]

std::unique_ptr< WitnessFunction< T > > MakeWitnessFunction ( const std::string &  description,
const WitnessFunctionDirection direction_type,
std::function< T(const Context< T > &)>  calc,
const Event< T > &  e 
) const
protected

Constructs the witness function with the given description (used primarily for debugging and logging), direction type, and calculator function, and with an object corresponding to the event that is to be dispatched when this witness function triggers.

Example types of event objects are publish, discrete variable update, unrestricted update events. A clone of the event will be owned by the newly constructed WitnessFunction.

Note
In order for the witness function to be used, you MUST overload System::DoGetWitnessFunctions().

◆ MakeWitnessFunction() [3/7]

std::unique_ptr<WitnessFunction<T> > MakeWitnessFunction ( const std::string &  description,
const WitnessFunctionDirection direction_type,
T(MySystem::*)(const Context< T > &) const  calc 
) const
protected

Constructs the witness function with the given description (used primarily for debugging and logging), direction type, and calculator function; and with no event object.

Note
Constructing a witness function with no corresponding event forces Simulator's integration of an ODE to end a step at the witness isolation time. For example, isolating a function's minimum or maximum values can be realized with a witness that triggers on a sign change of the function's time derivative, ensuring that the actual extreme value is present in the discretized trajectory.
In order for the witness function to be used, you MUST overload System::DoGetWitnessFunctions(). @exclude_from_pydrake_mkdoc{Only the std::function versions are bound.}

◆ MakeWitnessFunction() [4/7]

std::unique_ptr<WitnessFunction<T> > MakeWitnessFunction ( const std::string &  description,
const WitnessFunctionDirection direction_type,
T(MySystem::*)(const Context< T > &) const  calc,
const Event< T > &  e 
) const
protected

Constructs the witness function with the given description (used primarily for debugging and logging), direction type, and calculator function, and with an object corresponding to the event that is to be dispatched when this witness function triggers.

Example types of event objects are publish, discrete variable update, unrestricted update events. A clone of the event will be owned by the newly constructed WitnessFunction.

Note
In order for the witness function to be used, you MUST overload System::DoGetWitnessFunctions(). @exclude_from_pydrake_mkdoc{Only the std::function versions are bound.}

◆ MakeWitnessFunction() [5/7]

std::unique_ptr<WitnessFunction<T> > MakeWitnessFunction ( const std::string &  description,
const WitnessFunctionDirection direction_type,
T(MySystem::*)(const Context< T > &) const  calc,
void(MySystem::*)(const Context< T > &, const DiscreteUpdateEvent< T > &, DiscreteValues< T > *) const  du_callback 
) const
protected

Constructs the witness function with the given description (used primarily for debugging and logging), direction type, calculator function, and discrete update event callback function for when this triggers.

Note
In order for the witness function to be used, you MUST overload System::DoGetWitnessFunctions(). @exclude_from_pydrake_mkdoc{Only the std::function versions are bound.}

◆ MakeWitnessFunction() [6/7]

std::unique_ptr<WitnessFunction<T> > MakeWitnessFunction ( const std::string &  description,
const WitnessFunctionDirection direction_type,
T(MySystem::*)(const Context< T > &) const  calc,
void(MySystem::*)(const Context< T > &, const PublishEvent< T > &) const  publish_callback 
) const
protected

Constructs the witness function with the given description (used primarily for debugging and logging), direction type, calculator function, and publish event callback function for when this triggers.

Note
In order for the witness function to be used, you MUST overload System::DoGetWitnessFunctions(). @exclude_from_pydrake_mkdoc{Only the std::function versions are bound.}

◆ MakeWitnessFunction() [7/7]

std::unique_ptr<WitnessFunction<T> > MakeWitnessFunction ( const std::string &  description,
const WitnessFunctionDirection direction_type,
T(MySystem::*)(const Context< T > &) const  calc,
void(MySystem::*)(const Context< T > &, const UnrestrictedUpdateEvent< T > &, State< T > *) const  uu_callback 
) const
protected

Constructs the witness function with the given description (used primarily for debugging and logging), direction type, calculator function, and unrestricted update event callback function for when this triggers.

Note
In order for the witness function to be used, you MUST overload System::DoGetWitnessFunctions(). @exclude_from_pydrake_mkdoc{Only the std::function versions are bound.}

◆ MALIPUT_DRAKE_DEMAND()

MALIPUT_DRAKE_DEMAND ( this_ptr !  = nullptr)
protected

◆ SetDefaultParameters()

void SetDefaultParameters ( const Context< T > &  context,
Parameters< T > *  parameters 
) const
overridevirtual

Default implementation: sets all numeric parameters to the model vector given to DeclareNumericParameter, or else if no model was provided sets the numeric parameter to one.

It sets all abstract parameters to the model value given to DeclareAbstractParameter. Overrides must not change the number of parameters.

Implements System< T >.

◆ SetDefaultState()

void SetDefaultState ( const Context< T > &  context,
State< T > *  state 
) const
overridevirtual

Default implementation: sets all continuous state to the model vector given in DeclareContinuousState (or zero if no model vector was given) and discrete states to zero.

Overrides must not change the number of state variables.

Implements System< T >.

Member Data Documentation

◆ allocate

ValueProducer::AllocateCallback allocate
protected
Initial value:
= [this_ptr, make]() {
return AbstractValue::Make<OutputType>((this_ptr->*make)());
}

◆ port [1/2]

auto& port
protected
Initial value:
= CreateAbstractLeafOutputPort(NextOutputPortName(std::move(name)),
ValueProducer(this_ptr, std::move(allocate), calc),
std::move(prerequisites_of_calc))

◆ port [2/2]

return port
protected

The documentation for this class was generated from the following files:
maliput::drake::systems::System::all_state_ticket
static DependencyTicket all_state_ticket()
Returns a ticket indicating dependence on all state variables x in this system, including continuous ...
Definition: system_base.h:554
maliput::drake::systems::LeafSystem::allocate
ValueProducer::AllocateCallback allocate
Definition: leaf_system.h:1433
maliput::drake::systems::InputPortIndex
TypeSafeIndex< class InputPortTag > InputPortIndex
Serves as the local index for the input ports of a given System.
Definition: framework_common.h:46
maliput::drake::systems::System::input_port_ticket
DependencyTicket input_port_ticket(InputPortIndex index) const
Returns a ticket indicating dependence on input port uᵢ indicated by index.
Definition: system_base.h:589
maliput::drake::systems::LeafSystem::DeclareVectorOutputPort
LeafOutputPort< T > & DeclareVectorOutputPort(std::variant< std::string, UseDefaultName > name, const BasicVectorSubtype &model_vector, void(MySystem::*calc)(const Context< T > &, BasicVectorSubtype *) const, std::set< DependencyTicket > prerequisites_of_calc={ all_sources_ticket()})
Declares a vector-valued output port by specifying (1) a model vector of type BasicVectorSubtype deri...
Definition: leaf_system.h:1246