#include <memory>#include <string>#include <string_view>#include <vector>#include "drake/common/default_scalars.h"#include "drake/systems/analysis/integrator_base.h"#include "drake/systems/analysis/simulator.h"#include "drake/systems/analysis/simulator_config.h"#include "drake/systems/framework/system.h"Namespaces | |
| namespace | drake |
| namespace | drake::systems |
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. | |
| const std::vector< std::string > & | GetIntegrationSchemes () |
| Returns the allowed string values for the scheme parameter in ResetIntegratorFromFlags() and SimulatorConfig::integration_scheme. | |
| template<typename T> | |
| void | ApplySimulatorConfig (const SimulatorConfig &config, drake::systems::Simulator< T > *simulator) |
| Modifies the simulator based on the given config. | |
| template<typename T> | |
| SimulatorConfig | ExtractSimulatorConfig (const drake::systems::Simulator< T > &simulator) |
| Reports the simulator's current configuration, including the configuration of the integrator. | |
| 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. | |
| template<typename T> | |
| bool | IsScalarTypeSupportedByIntegrator (std::string_view integration_scheme) |
| Reports if an integration scheme supports the scalar type T. | |