navlie.lib.preintegration.WheelOdometryIncrement¶
- class navlie.lib.preintegration.WheelOdometryIncrement(Q: ndarray, bias: ndarray | None = None, state_id=None)¶
Bases:
BodyVelocityIncrement
This is a preintegration class for wheel odometry measurements on SE(n). The preintegrated process model is of the form
\[\mathbf{T}_{j} = \mathbf{T}_{i} \Delta \mathbf{V}_{ij},\]where \(\Delta \mathbf{V}_{ij}\) is the preintegrated increment given by
\[\Delta \mathbf{V}_{ij} = \prod_{k=i}^{j-1} \exp(\Delta t \mathbf{\varpi}_{k}^\wedge)\]and \(\mathbf{\varpi}_{k} = [\mathbf{\omega}_k^T \; \mathbf{v}_k^T]^T\) is the angular and translational velocity of the robot at time \(k\).
- new() → WheelOdometryIncrement¶
- Returns:
A new WheelOdometryIncrement with reinitialized values
- Return type:
- covariance¶
the covariance matrix of the RMI
- Type:
np.ndarray
- state_id¶
an ID associated with the RMI
- Type:
Any
- copy()¶
- Returns:
A copy of the RMI
- Return type:
- increment(u: VectorInput, dt)¶
In-place updating the RMI given an input measurement u and a duration dt over which to preintegrate.
- plus(w: ndarray)¶
Adds noise to the RMI
- Parameters:
w (np.ndarray) – The noise to add
- Returns:
The updated RMI
- Return type:
- property stamp¶
The later timestamp \(j\) of the RMI.
- symmetrize()¶
Symmetrize the covariance matrix of the RMI.
- update_bias(new_bias: ndarray)¶
Internally updates the RMI given a new bias.
- Parameters:
new_bias (np.ndarray) – New bias values
- property value¶
returns: The RMI matrix \(\Delta \mathbf{U}_{ij}\). :rtype: numpy.ndarray