navlie.lib.models.PointRelativePositionSLAM¶
- class navlie.lib.models.PointRelativePositionSLAM(pose_state_id: Any, landmark_state_id: Any, R: ndarray)¶
Bases:
MeasurementModel
Measurement model describing the position of an unknown landmark relative to the robot, resolved in the body frame. That is, the state is the pose of the robot and the inertial lndmark position, and the measurement is relative landmark measurements resolved in the robot frame.
\[\mathbf{y} = \mathbf{C}_{ab}^T (\mathbf{r}_\ell - \mathbf{r})\]where \(\mathbf{C}\) is the attitude of the robot, \(\mathbf{r}_\ell\) is the position of the landmark, and \(\mathbf{r}\) is the position of the robot.
This class is comptabile with
SE2State, SE3State, SE23State, IMUState
.- evaluate(x: CompositeState) → ndarray¶
Evaluates the measurement model for the landmark state.
- jacobian(x: CompositeState) → ndarray¶
Evaluates the measurement model Jacobian with respect to the state.
\[\mathbf{G} = \frac{D \mathbf{g}(\mathcal{X})}{D \mathcal{X}}\]
- covariance(x: CompositeState) → 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.