Drake
Collaboration diagram for Primitives:

Classes

class  Adder< T >
 An adder for arbitrarily many inputs of equal size. More...
 
class  AffineSystem< T >
 A discrete OR continuous affine system (with constant coefficients). More...
 
class  ConstantValueSource< T >
 A source block that always outputs a constant value. More...
 
class  ConstantVectorSource< T >
 A source block with a constant output port at all times. More...
 
class  Demultiplexer< T >
 This system splits a vector valued signal in its inputs of size size into size output scalar valued signals. More...
 
class  FirstOrderLowPassFilter< T >
 An element-wise first order low pass filter system that filters the i-th input uᵢ into the i-th output zᵢ. More...
 
class  Gain< T >
 An element-wise gain block with input u and output y = k * u with k a constant vector. More...
 
class  Integrator< T >
 An integrator for a continuous vector input. More...
 
class  LinearSystem< T >
 A discrete OR continuous linear system. More...
 
class  MatrixGain< T >
 A system that specializes LinearSystem by setting coefficient matrices A, B, and C to all be zero. More...
 
class  Multiplexer< T >
 This system combines multiple vector-valued inputs into a vector-valued output. More...
 
class  PassThrough< T >
 A pass through system with input u and output y = u. More...
 
class  RandomSource< Distribution, Generator >
 A source block which generates random numbers at a fixed sampling interval, with a zero-order hold between samples. More...
 
class  Saturation< T >
 An element-wise hard saturation block with inputs signal u, saturation values \( u_{min} \) and/or \( u_{max} \), and output y respectively as in: More...
 
class  SignalLogger< T >
 A sink block which logs its input to memory. More...
 
class  TrajectorySource< T >
 A source block that generates the value of a Trajectory for a given time. More...
 
class  ZeroOrderHold< T >
 A ZeroOrderHold block with input u, which may be vector-valued (discrete or continuous) or abstract, and discrete output y, where the y is sampled from u with a fixed period. More...
 

Typedefs

typedef RandomSource< internal::mean_zero_uniform_real_distribution > UniformRandomSource
 Generates uniformly distributed random numbers in the interval [-1,1]. More...
 
typedef RandomSource< std::normal_distribution< double > > GaussianRandomSource
 Generates uniformly distributed random numbers with mean zero and unit covariance. More...
 

Functions

std::unique_ptr< LinearSystem< double > > Linearize (const System< double > &system, const Context< double > &context, const double equilibrium_check_tolerance=1e-6)
 Takes the first-order Taylor expansion of a System around a nominal operating point (defined by the Context). More...
 

Detailed Description

Typedef Documentation

typedef RandomSource<std::normal_distribution<double> > GaussianRandomSource

Generates uniformly distributed random numbers with mean zero and unit covariance.

typedef RandomSource<internal::mean_zero_uniform_real_distribution> UniformRandomSource

Generates uniformly distributed random numbers in the interval [-1,1].

Function Documentation

std::unique_ptr< LinearSystem< double > > Linearize ( const System< double > &  system,
const Context< double > &  context,
const double  equilibrium_check_tolerance = 1e-6 
)

Takes the first-order Taylor expansion of a System around a nominal operating point (defined by the Context).

Parameters
systemThe system or subsystem to linearize.
contextDefines the nominal operating point about which the system should be linearized. See note below.
equilibrium_check_toleranceSpecifies the tolerance on ensuring that the derivative vector isZero at the nominal operating point.
Default: 1e-6.
Returns
A LinearSystem that approximates the original system in the vicinity of the operating point. See note below.
Exceptions
std::runtime_errorif the system the operating point is not an equilibrium point of the system (within the specified tolerance)

Note: The inputs in the Context must be connected, either to the output of some upstream System within a Diagram (e.g., if system is a reference to a subsystem in a Diagram), or to a constant value using, e.g. context->FixInputPort(0,default_input);

Note: The inputs, states, and outputs of the returned system are NOT the same as the original system. Denote x0,u0 as the nominal state and input defined by the Context, and y0 as the value of the output at (x0,u0), then the created systems inputs are (u-u0), states are (x-x0), and outputs are (y-y0).

Here is the call graph for this function:

Here is the caller graph for this function: