Loading [MathJax]/extensions/tex2jax.js
Drake
Drake C++ Documentation
All Classes Namespaces Files Functions Variables Typedefs Enumerations Enumerator Friends Macros Modules Pages
Simulator configuration

Detailed Description

Configuration helpers to control Simulator and IntegratorBase settings.

Functions

template<typename T >
IntegratorBase< T > & ResetIntegratorFromFlags (Simulator< T > *simulator, const std::string &scheme, const T &max_step_size)
 Resets the integrator used to advanced the continuous time dynamics of the system associated with simulator according to the given arguments. More...
 
const std::vector< std::string > & GetIntegrationSchemes ()
 Returns the allowed string values for the scheme parameter in ResetIntegratorFromFlags() and SimulatorConfig::integration_scheme. More...
 
template<typename T >
void ApplySimulatorConfig (const SimulatorConfig &config, drake::systems::Simulator< T > *simulator)
 Modifies the simulator based on the given config. More...
 
template<typename T >
SimulatorConfig ExtractSimulatorConfig (const drake::systems::Simulator< T > &simulator)
 Reports the simulator's current configuration, including the configuration of the integrator. More...
 
template<typename T >
std::unique_ptr< IntegratorBase< T > > CreateIntegratorFromConfig (const System< T > *system, const SimulatorConfig &integrator_config)
 Create an integrator according to the given configuration. More...
 
template<typename T >
bool IsScalarTypeSupportedByIntegrator (std::string_view integration_scheme)
 Reports if an integration scheme supports the scalar type T. More...
 

Function Documentation

◆ ApplySimulatorConfig()

void drake::systems::ApplySimulatorConfig ( const SimulatorConfig config,
drake::systems::Simulator< T > *  simulator 
)

Modifies the simulator based on the given config.

(Always replaces the Integrator with a new one; be careful not to keep old references around.)

Parameters
[in]configConfiguration to be used. Contains values for both the integrator and the simulator.
[in,out]simulatorOn input, a valid pointer to a Simulator. On output the integrator for simulator is reset according to the given config.
Template Parameters
TThe scalar type, which must be one of the default nonsymbolic scalars.

◆ CreateIntegratorFromConfig()

std::unique_ptr<IntegratorBase<T> > drake::systems::CreateIntegratorFromConfig ( const System< T > *  system,
const SimulatorConfig integrator_config 
)

Create an integrator according to the given configuration.

Parameters
systemA pointer to the System to be integrated; the integrator will maintain a reference to the system in perpetuity, so the integrator must not outlive the system.
integrator_configConfiguration to be used. Only values relevant to the integrator (integration_scheme, max_step_size, use_error_control, accuracy) are applied.
Precondition
system != nullptr.
Exceptions
std::exceptionif the integration scheme does not match any of GetIntegrationSchemes(), or if the integration scheme does not support the scalar type T.
Template Parameters
TThe scalar type, which must be one of the default scalars.

◆ ExtractSimulatorConfig()

SimulatorConfig drake::systems::ExtractSimulatorConfig ( const drake::systems::Simulator< T > &  simulator)

Reports the simulator's current configuration, including the configuration of the integrator.

Parameters
[in]simulatorThe Simulator to extract the configuration from.
Template Parameters
TThe scalar type, which must be one of the default nonsymbolic scalars.
Note
For non-double T (T=AutoDiffXd), doing ExtractSimulatorConfig will discard the integrator's scalar type's extra information such as gradients.

◆ GetIntegrationSchemes()

const std::vector<std::string>& drake::systems::GetIntegrationSchemes ( )

Returns the allowed string values for the scheme parameter in ResetIntegratorFromFlags() and SimulatorConfig::integration_scheme.

◆ IsScalarTypeSupportedByIntegrator()

bool drake::systems::IsScalarTypeSupportedByIntegrator ( std::string_view  integration_scheme)

Reports if an integration scheme supports the scalar type T.

Parameters
integration_schemeIntegration scheme to be checked.
Exceptions
std::exceptionif the integration scheme does not match any of GetIntegrationSchemes().
Template Parameters
TThe scalar type, which must be one of the default scalars.

◆ ResetIntegratorFromFlags()

IntegratorBase<T>& drake::systems::ResetIntegratorFromFlags ( Simulator< T > *  simulator,
const std::string &  scheme,
const T &  max_step_size 
)

Resets the integrator used to advanced the continuous time dynamics of the system associated with simulator according to the given arguments.

Parameters
[in,out]simulatorOn input, a valid pointer to a Simulator. On output the integrator for simulator is reset according to the given arguments.
[in]schemeIntegration scheme to be used, e.g., "runge_kutta2". See GetIntegrationSchemes() for a the list of valid options.
[in]max_step_sizeThe IntegratorBase::set_maximum_step_size() value.
Returns
A reference to the newly created integrator owned by simulator.
Template Parameters
TThe scalar type, which must be one of the default nonsymbolic scalars.