Class StatePropagator#
Defined in File StatePropagator.h
Nested Relationships#
Nested Types#
Inheritance Relationships#
Base Type#
public Karana::Dynamics::ModelManager(Class ModelManager)
Class Documentation#
-
class StatePropagator : public Karana::Dynamics::ModelManager#
Class to integrate and propagate system state.
See Time-domain simulations section for more information on the StatePropagator class.
Public Types
-
enum class SpStatusEnum#
Enum with values to classify the reason for the termination of a step.
Values:
-
enumerator UNKNOWN#
unknown
-
enumerator REACHED_END_TIME#
normal termination, reached requested end time
-
enumerator REACHED_TERMINATION_CONDITION#
premature termination since the termination condition was met
-
enumerator REACHED_ZERO_CROSSING#
premature end on reaching zero-crossing condition
-
enumerator FAILED_STEP_VALIDATION#
rolled back due to failing step validation check
-
enumerator UNKNOWN#
Public Functions
-
StatePropagator(const kc::ks_ptr<SubTree> &st, const km::IntegratorType &integrator_type, km::Integrator::IntegratorOptions *integ_opts = nullptr, kc::ks_ptr<SpOptions> sp_opts = nullptr, MMSolverType solver_type = MMSolverType::UNDEFINED)#
StatePropagator constructor. The constructor is not meant to be called directly. Please use the create(…) method instead to create an instance.
If the solver type is not specified, the constructor will use TREE_DYNAMICS if the specified st argument is a pure subtree (and not SubGraph), or if is the multibody instance itself with no bilateral constraints. For all other st, an error will be raised - and a legal solver type must be explicitly specified since there is no good way to infer one.
- Parameters:
st – the SubTree instance
integrator_type – the numerical integrator type
integ_opts – options for the numerical integrator
sp_opts – options for the state propagator
solver_type – the solver type
-
~StatePropagator()#
Destructor.
-
SpStatusEnum advanceTo(const km::Ktime &to_time)#
Method to advance the system state to a new time in the future.
- Parameters:
to_time – the desired future time
- Returns:
advancement status value
-
SpStatusEnum advanceBy(const km::Ktime &delta_time)#
Method to advance the system state by a time interval.
- Parameters:
delta_time – the time to advance by
- Returns:
advancement status value
-
inline const kc::ks_ptr<km::Integrator> &getIntegrator() const#
Return the integrator instance.
See Numerical integration section for more information on numerical integrators.
- Returns:
the Integrator instance
-
void setIntegrator(kc::ks_ptr<km::Integrator> integrator)#
Change to the specified integrator.
If there was a previous integrator, the time and state values are transferred as well.
See Numerical integration section for more information on numerical integrators.
- Parameters:
integrator – the new integrator
-
virtual void setTime(const km::Ktime &t) override#
Reset the integrator to the new time value.
This is also referred to as a soft reset. If the time set is different than the current time, this will attempt to rescheduled all TimedEvents appropriately; however, since TimedEvents can have arbitrary reschedule_fns, it is impossible to meet all corner cases. Use this with caution when you have non-uniform TimedEvents. See
System state section for more on this topic.
- Parameters:
t – the new time
-
virtual void setState(const km::Vec &x) override#
Reset the integrator to the new state values.
This is also referred to as a soft reset. This method assumes that only the state values have changed, and there have been no configuration changes causing changes to the size or structure of the state vector. The input state vector elements for subhinges should contain global coordinate values. This method resets the chart offsets for all regular and constraint subhinges for the sub graph.
The state itself is often created using the assembleState method.
See also
- Parameters:
x – the new state value
-
virtual void derivFunction(const km::Ktime &t, const km::Vec &x, Eigen::Ref<km::Vec> dx) override#
The derivative function for use by the integrator.
This method is used to compute the state derivative by the numerical integrator for propagating system state.
- Parameters:
t – the current time
x – the current state
dx – the computed state derivative
-
virtual void hardReset() override#
Reset the size of the internal state vector to match the size of the SubTree state.
the size of all the continuous model states.
This method also makeNotReadys the state, so setState must be called afterwards.
-
const km::Ktime &getMaxStepSize()#
Get the step size that advanceTo() is using to break up the overall time advancement into sub-steps.
This is especially useful for fixed-step integrators to ensure that integrator steps are not too large. Also for cases where external interactions and data logging needs to be done at fixed step intervals.
- Returns:
The maximum step size that advanceTo will use.
-
void setMaxStepSize(const km::Ktime &max_step_size)#
Set the step size that advanceTo() will use to break up the overall time advancement into sub-steps.
See getMaxStepSize for more details.
- Parameters:
max_step_size – The maximum step size that advanceTo will use.
-
bool getUpdateStateDerivativesHopEnd()#
Get the setting for updating the derivatives at hop end.
If true, then update the multibody state derivatives with the integrator states at the end of each hop.
- Returns:
The the setting for updating the derivatives at hop end.
-
void setUpdateStateDerivativesHopEnd(bool update_state_derivatives_hop_end)#
Set whether to update the derivatives at hop end or not.
If true, then update the multibody state derivatives with the integrator states at the end of each hop.
- Parameters:
update_state_derivatives_hop_end – The setting for updating the derivatives at hop end.
-
std::string dumpString(std::string_view prefix = "", const Base::DumpOptions *options = nullptr) const override#
-
virtual void registerTimedEvent(const kc::ks_ptr<TimedEvent> &timed_event) override#
Register a TimedEvent. See.
Timed events section for more on using the TimedEvent class.
- Parameters:
timed_event – The TimedEvent to register.
-
virtual void unregisterTimedEvent(std::string_view name, bool pre_hop, bool okay_not_exists = false) override#
Unregister a TimedEvent. See.
Timed events section for more on using the TimedEvent class.
- Parameters:
name – - The name of the timed event to remove.
pre_hop – - Whether the event to remove is a pre_hop or post_hop timed event.
okay_not_exists – - If true, then do not error out if a timed event by this name does not exist with the given pre_hop setting, otherwise, error our if the given event is not found.
-
virtual bool hasRegisteredTimedEvent(std::string_view name, bool pre_hop) const override#
Determine whether a TimedEvent with the given name exists.
- Parameters:
name – - The name of the TimedEvent.
pre_hop – - Whether this is a pre_hop timed event or not.
- Returns:
true if a TimedEvent with the given name and pre_hop setting exists, false otherwise.
Public Static Functions
-
static kc::ks_ptr<StatePropagator> create(const kc::ks_ptr<SubTree> &st, const km::IntegratorType &integrator_type, km::Integrator::IntegratorOptions *integ_opts = nullptr, kc::ks_ptr<SpOptions> sp_opts = nullptr, MMSolverType solver_type = MMSolverType::UNDEFINED)#
Create an instance of the StatePropagator.
If the solver type is not specified, the constructor will use TREE_DYNAMICS if the specified st argument is a pure subtree (and not SubGraph), or if is the multibody instance itself with no bilateral constraints. For all other st, an error will be raised - and a legal solver type must be explicitly specified since there is no good way to infer one.
- Parameters:
st – the SubTree instance
integrator_type – the numerical integrator type
integ_opts – options for the numerical integrator
sp_opts – options for the state propagator
solver_type – the solver type
- Returns:
An instance of the StatePropagator.
Protected Functions
-
SpStatusEnum _hopStep(const km::Ktime &to_time)#
Helper method to execute a hop sub-step.
- Parameters:
to_time – the to time
- Returns:
the status value
-
SpStatusEnum _integrationStep(const km::Ktime &to_time)#
Helper method to execute a numerical integration sub-step.
This will also sanitize the coordinates at the end of the integration sub-step.
- Parameters:
to_time – The time to integrate to.
- Returns:
The status of the integration sub step.
-
void _discard(kc::ks_ptr<kc::Base> &base) override#
Discard the StatePropagator.
- Parameters:
base – A base pointer to the StatePropagator to discard.
Protected Attributes
-
kc::ks_ptr<km::Integrator> _integrator = nullptr#
the integrator
-
km::Ktime _tolerance = km::Ktime(100)#
the time tolerance to use to conclude that we are close enough to the zero-crossing condition, and do not need to get any closer.
-
struct Counters#
Struct to track state propagation statistics.
-
class SpOptions : public Karana::Dynamics::ModelManager::MMOptions#
Options for the state propagator.
Public Functions
Public Members
-
km::Ktime max_step_size = km::Ktime(0)#
Define the step size that advanceTo() should use to break up the overall time advancement into sub-steps. This is especially useful for fixed-step integrators to ensure that integrator steps are not too large. Also for cases where external interactions and data logging needs to be done at fixed step intervals.
-
bool update_state_derivatives_hop_end = false#
If true, then update the multibody state derivatives with the integrator states at the end of each hop.
-
km::Ktime max_step_size = km::Ktime(0)#
-
enum class SpStatusEnum#