navlie.lib.preintegration.IMUIncrement¶
- class navlie.lib.preintegration.IMUIncrement(input_covariance: ndarray, gyro_bias: ndarray, accel_bias: ndarray, state_id: Any | None = None, gravity=None)¶
Bases:
RelativeMotionIncrement
Initializes an “identity” IMU RMI.
- Parameters:
input_covariance (np.ndarray with shape (12, 12) or (6, 6)) – If a 6 x 6 array is provided, this is the covariance of gyro, accel measurements. If a 12 x 12 array is provided, this is the covariance of gyro, accel, gyro bias random walk, and accel bias random walk.
- covariance¶
the covariance matrix of the RMI
- Type:
np.ndarray
- original_value¶
- original_bias¶
- input_covariance¶
- bias_jacobian¶
- gravity¶
- state_id¶
an ID associated with the RMI
- Type:
Any
- new_bias¶
- property gyro_bias¶
- property accel_bias¶
- property value¶
- increment(u: IMU, dt: float)¶
In-place updating the RMI given an input measurement u and a duration dt over which to preintegrate.
- update_bias(new_bias: ndarray)¶
Updates the RMI given new bias values
- Parameters:
new_gyro_bias (np.ndarray with size 3) – new gyro bias value
new_accel_bias (np.ndarray with size 3) – new accel bias value
- plus(w: ndarray) → IMUIncrement¶
Adds noise to the RMI
- Parameters:
w (np.ndarray) – The noise to add
- Returns:
The updated RMI
- Return type:
- copy() → IMUIncrement¶
- Returns:
A copy of the RMI
- Return type:
- new(new_bias: ndarray | None = None, gyro_bias=None, accel_bias=None) → IMUIncrement¶
- Parameters:
new_bias (np.ndarray) – The new bias value stacked as [gyro_bias, accel_bias]
gyro_bias (np.ndarray) – The new gyro bias to use in this RMI (overwrites previous argument)
accel_bias (np.ndarray) – The new accel bias to use in this RMI (overwrites previous argument)
- Returns:
A copy of the RMI with reinitialized values
- Return type:
- property stamp¶
The later timestamp \(j\) of the RMI.
- symmetrize()¶
Symmetrize the covariance matrix of the RMI.