navlie.lib.models.Altitude¶
- class navlie.lib.models.Altitude(R: ndarray, minimum=None, bias=0.0)¶
Bases:
MeasurementModel
A model that returns the z component of a position vector. This model is of the form
\[\mathbf{y} = [0, 0, 1] \mathbf{r}\]where \(\mathbf{r}\) is the position of the robot.
Compatible with
SE3State, SE23State, IMUState
.- Parameters:
R (np.ndarray) – variance associated with the measurement
minimum (float, optional) – Minimal height for the measurement to be valid, by default None
bias (float, optional) – Fixed sensor bias, by default 0.0. This bias will be added to the z component of position to create the modelled measurement.
- evaluate(x: MatrixLieGroupState)¶
Evaluates the measurement model \(\mathbf{g}(\mathcal{X})\).
- jacobian(x: MatrixLieGroupState)¶
Evaluates the measurement model Jacobian with respect to the state.
\[\mathbf{G} = \frac{D \mathbf{g}(\mathcal{X})}{D \mathcal{X}}\]
- covariance(x: MatrixLieGroupState) → ndarray¶
Returns the covariance \(\mathbf{R}\) associated with additive Gaussian noise.
- evaluate_with_jacobian(x: State) → Tuple[ndarray, ndarray]¶
Evaluates the measurement 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.