navlie.lib.preintegration.PreintegratedBodyVelocity¶
- class navlie.lib.preintegration.PreintegratedBodyVelocity¶
Bases:
ProcessModel
Process model that performs prediction of the state given an RMI \(\Delta \mathbf{U}_{ij}\) according to the equation
\[\mathbf{T}_{j} = \mathbf{T}_{i} \Delta \mathbf{U}_{ij}.\]The covariance is also propagated accordingly
- evaluate(x: MatrixLieGroupState, rmi: BodyVelocityIncrement, dt=None) → MatrixLieGroupState¶
Implementation of \({f}(\mathcal{X}_{k-1}, \mathbf{u}, \Delta t)\).
- jacobian(x: MatrixLieGroupState, rmi: BodyVelocityIncrement, dt=None) → ndarray¶
Implementation of the process model Jacobian with respect to the state.
\[\mathbf{F} = \frac{D {f}(\mathcal{X}_{k-1}, \mathbf{u}, \Delta t)}{D \mathcal{X}_{k-1}}\]
- covariance(x: MatrixLieGroupState, rmi: BodyVelocityIncrement, dt=None) → ndarray¶
Covariance matrix \(\mathbf{Q}_k\) of the additive Gaussian noise \(\mathbf{w}_{k} \sim \mathcal{N}(\mathbf{0}, \mathbf{Q}_k)\). If this method is not overridden, the covariance of the process model error is approximated from the input covariance using a linearization procedure, with the input Jacobian evaluated using finite difference.
- evaluate_with_jacobian(x: ~navlie.types.State, u: ~navlie.types.Input, dt: float) -> (<class 'navlie.types.State'>, <class 'numpy.ndarray'>)¶
Evaluates the process model and simultaneously returns the Jacobian as its second output argument. This is useful to override for performance reasons when the model evaluation and Jacobian have a lot of common calculations, and it is more efficient to calculate them in the same function call.
- input_covariance(x: State, u: Input, dt: float) → ndarray¶
Covariance matrix of additive noise on the input.
- input_jacobian_fd(x: State, u: Input, dt: float, step_size=1e-06, *args, **kwargs) → ndarray¶
Calculates the input jacobian with finite difference.