navlie

  • Home
  • Tutorial
  • API
  • navlie.composite
    • navlie.composite.CompositeInput
    • navlie.composite.CompositeMeasurement
    • navlie.composite.CompositeMeasurementModel
    • navlie.composite.CompositeProcessModel
    • navlie.composite.CompositeState
  • navlie.datagen
    • navlie.datagen.generate_measurement
    • navlie.datagen.DataGenerator
  • navlie.filters
    • navlie.filters.check_outlier
    • navlie.filters.generate_sigmapoints
    • navlie.filters.mean_state
    • navlie.filters.run_filter
    • navlie.filters.run_gsf_filter
    • navlie.filters.run_imm_filter
    • navlie.filters.CubatureKalmanFilter
    • navlie.filters.ExtendedKalmanFilter
    • navlie.filters.GaussHermiteKalmanFilter
    • navlie.filters.GaussianSumFilter
    • navlie.filters.InteractingModelFilter
    • navlie.filters.IteratedKalmanFilter
    • navlie.filters.SigmaPointKalmanFilter
    • navlie.filters.UnscentedKalmanFilter
  • navlie.types
    • navlie.types.Dataset
    • navlie.types.Input
    • navlie.types.Measurement
    • navlie.types.MeasurementModel
    • navlie.types.ProcessModel
    • navlie.types.State
    • navlie.types.StateWithCovariance
  • navlie.utils
    • navlie.utils.alignment
      • navlie.utils.alignment.associate_and_align_trajectories
      • navlie.utils.alignment.evo_traj_to_state_list
      • navlie.utils.alignment.state_list_to_evo_traj
    • navlie.utils.common
      • navlie.utils.common.associate_stamps
      • navlie.utils.common.find_nearest_stamp_idx
      • navlie.utils.common.jacobian
      • navlie.utils.common.load_tum_trajectory
      • navlie.utils.common.monte_carlo
      • navlie.utils.common.randvec
      • navlie.utils.common.schedule_sequential_measurements
      • navlie.utils.common.state_interp
      • navlie.utils.common.van_loans
      • navlie.utils.common.GaussianResult
      • navlie.utils.common.GaussianResultList
      • navlie.utils.common.MixtureResult
      • navlie.utils.common.MixtureResultList
      • navlie.utils.common.MonteCarloResult
    • navlie.utils.mixture
      • navlie.utils.mixture.gaussian_mixing
      • navlie.utils.mixture.gaussian_mixing_vectorspace
      • navlie.utils.mixture.reparametrize_gaussians_about_X_par
      • navlie.utils.mixture.update_X
    • navlie.utils.plot
      • navlie.utils.plot.plot_camera_poses
      • navlie.utils.plot.plot_error
      • navlie.utils.plot.plot_meas
      • navlie.utils.plot.plot_meas_by_model
      • navlie.utils.plot.plot_nees
      • navlie.utils.plot.plot_poses
      • navlie.utils.plot.set_axes_equal
      • navlie.utils.plot.CameraPoseVisualizer
  • navlie.batch
    • navlie.batch.estimator
      • navlie.batch.estimator.BatchEstimator
    • navlie.batch.gaussian_mixtures
      • navlie.batch.gaussian_mixtures.GaussianMixtureResidual
      • navlie.batch.gaussian_mixtures.HessianSumMixtureResidual
      • navlie.batch.gaussian_mixtures.MaxMixtureResidual
      • navlie.batch.gaussian_mixtures.MaxSumMixtureResidual
      • navlie.batch.gaussian_mixtures.SumMixtureResidual
    • navlie.batch.losses
      • navlie.batch.losses.CauchyLoss
      • navlie.batch.losses.L2Loss
      • navlie.batch.losses.LossFunction
    • navlie.batch.problem
      • navlie.batch.problem.OptimizationSummary
      • navlie.batch.problem.Problem
    • navlie.batch.residuals
      • navlie.batch.residuals.MeasurementResidual
      • navlie.batch.residuals.PriorResidual
      • navlie.batch.residuals.ProcessResidual
      • navlie.batch.residuals.Residual
  • navlie.lib
    • navlie.lib.camera
      • navlie.lib.camera.PinholeCamera
      • navlie.lib.camera.PoseMatrix
    • navlie.lib.datasets
      • navlie.lib.datasets.generate_landmark_positions
      • navlie.lib.datasets.SimulatedInertialGPSDataset
      • navlie.lib.datasets.SimulatedInertialLandmarkDataset
      • navlie.lib.datasets.SimulatedPoseRangingDataset
    • navlie.lib.imu
      • navlie.lib.imu.G_matrix
      • navlie.lib.imu.G_matrix_inv
      • navlie.lib.imu.L_matrix
      • navlie.lib.imu.M_matrix
      • navlie.lib.imu.N_matrix
      • navlie.lib.imu.U_matrix
      • navlie.lib.imu.U_matrix_inv
      • navlie.lib.imu.U_tilde_matrix
      • navlie.lib.imu.adjoint_IE3
      • navlie.lib.imu.delta_matrix
      • navlie.lib.imu.get_unbiased_imu
      • navlie.lib.imu.inverse_IE3
      • navlie.lib.imu.IMU
      • navlie.lib.imu.IMUKinematics
      • navlie.lib.imu.IMUState
    • navlie.lib.models
      • navlie.lib.models.AbsolutePosition
      • navlie.lib.models.AbsoluteVelocity
      • navlie.lib.models.Altitude
      • navlie.lib.models.BodyFrameVelocity
      • navlie.lib.models.CameraProjection
      • navlie.lib.models.DoubleIntegrator
      • navlie.lib.models.DoubleIntegratorWithBias
      • navlie.lib.models.GlobalPosition
      • navlie.lib.models.Gravitometer
      • navlie.lib.models.InvariantMeasurement
      • navlie.lib.models.InvariantPointRelativePosition
      • navlie.lib.models.LinearMeasurement
      • navlie.lib.models.Magnetometer
      • navlie.lib.models.OneDimensionalPositionVelocityRange
      • navlie.lib.models.PointRelativePosition
      • navlie.lib.models.PointRelativePositionSLAM
      • navlie.lib.models.RangePointToAnchor
      • navlie.lib.models.RangePoseToAnchor
      • navlie.lib.models.RangePoseToPose
      • navlie.lib.models.RangeRelativePose
      • navlie.lib.models.RelativeBodyFrameVelocity
      • navlie.lib.models.SingleIntegrator
    • navlie.lib.preintegration
      • navlie.lib.preintegration.AngularVelocityIncrement
      • navlie.lib.preintegration.BodyVelocityIncrement
      • navlie.lib.preintegration.IMUIncrement
      • navlie.lib.preintegration.LinearIncrement
      • navlie.lib.preintegration.PreintegratedAngularVelocity
      • navlie.lib.preintegration.PreintegratedBodyVelocity
      • navlie.lib.preintegration.PreintegratedIMUKinematics
      • navlie.lib.preintegration.PreintegratedLinearModel
      • navlie.lib.preintegration.PreintegratedWheelOdometry
      • navlie.lib.preintegration.RelativeMotionIncrement
      • navlie.lib.preintegration.WheelOdometryIncrement
    • navlie.lib.states
      • navlie.lib.states.MatrixLieGroupState
      • navlie.lib.states.MixtureState
      • navlie.lib.states.SE23State
      • navlie.lib.states.SE2State
      • navlie.lib.states.SE3State
      • navlie.lib.states.SL3State
      • navlie.lib.states.SO2State
      • navlie.lib.states.SO3State
      • navlie.lib.states.StampedValue
      • navlie.lib.states.VectorInput
      • navlie.lib.states.VectorState
  • navlie.bspline
    • navlie.bspline.SE3Bspline
On this page
  • MatrixLieGroupState
    • MatrixLieGroupState.direction
    • MatrixLieGroupState.group
    • MatrixLieGroupState.value
    • MatrixLieGroupState.plus()
    • MatrixLieGroupState.minus()
    • MatrixLieGroupState.copy()
    • MatrixLieGroupState.plus_jacobian()
    • MatrixLieGroupState.minus_jacobian()
    • MatrixLieGroupState.dot()
    • MatrixLieGroupState.attitude
    • MatrixLieGroupState.position
    • MatrixLieGroupState.velocity
    • MatrixLieGroupState.jacobian_from_blocks()
    • MatrixLieGroupState.dof
    • MatrixLieGroupState.minus_jacobian_fd()
    • MatrixLieGroupState.plus_jacobian_fd()
    • MatrixLieGroupState.stamp
    • MatrixLieGroupState.state_id

navlie.lib.states.MatrixLieGroupState¶

class navlie.lib.states.MatrixLieGroupState(value: ndarray, group: MatrixLieGroup, stamp: float | None = None, state_id: Any | None = None, direction='right')¶

Bases: State

The MatrixLieGroupState class. Although this class can technically be used directly, it is recommended to use one of the subclasses instead, such as SE2State or SO3State.

Parameters:
  • value (np.ndarray) – Value of of the state. If the value has as many elements as the DOF of the group, then it is assumed to be a vector of exponential coordinates. Otherwise, the value must be a 2D numpy array representing a direct element of the group in matrix form.

  • group (MatrixLieGroup) – A pymlg.MatrixLieGroup class, such as pymlg.SE2 or pymlg.SO3.

  • stamp (float, optional) – timestamp, by default None

  • state_id (Any, optional) – optional state ID, by default None

  • direction (str, optional) –

    either “left” or “right”, by default “right”. Defines the perturbation \(\delta \mathbf{x}\) as either

    \[ \begin{align}\begin{aligned}\mathbf{X} = \mathbf{X} \exp(\delta \mathbf{x}^\wedge) ext{ (right)}\\\mathbf{X} = \exp(\delta \mathbf{x}^\wedge) \mathbf{X} ext{ (left)}\end{aligned}\end{align} \]

direction¶
group¶
value: ndarray¶

State value

Type:

Any

plus(dx: ndarray) → MatrixLieGroupState¶

A generic “addition” operation given a dx numpy array with as many elements as the dof of this state.

minus(x: MatrixLieGroupState) → ndarray¶

A generic “subtraction” operation given another State object of the same type, always returning a numpy array.

copy() → MatrixLieGroupState¶

Returns a copy of this State instance.

plus_jacobian(dx: ndarray) → ndarray¶

Jacobian of the plus operator. That is, using Lie derivative notation,

\[\mathbf{J} = \frac{D (\mathcal{X} \oplus \delta \mathbf{x})}{D \delta \mathbf{x}}\]

For Lie groups, this is known as the group Jacobian.

minus_jacobian(x: MatrixLieGroupState) → ndarray¶

Jacobian of the minus operator with respect to self.

\[\mathbf{J} = \frac{D (\mathcal{Y} \ominus \mathcal{X})}{D \mathcal{Y}}\]

That is, if dx = y.minus(x) then this is the Jacobian of dx with respect to y. For Lie groups, this is the inverse of the group Jacobian evaluated at dx = x1.minus(x2).

dot(other: MatrixLieGroupState) → MatrixLieGroupState¶
property attitude: ndarray¶
property position: ndarray¶
property velocity: ndarray¶
jacobian_from_blocks(**kwargs) → ndarray¶
dof¶

Degree of freedom of the state

Type:

int

minus_jacobian_fd(x: State, step_size=1e-08) → ndarray¶

Calculates the minus jacobian with finite difference.

plus_jacobian_fd(dx, step_size=1e-08) → ndarray¶

Calculates the plus jacobian with finite difference.

stamp¶

Timestamp

Type:

float

state_id¶

previous

navlie.lib.states

next

navlie.lib.states.MixtureState

© Copyright 2022.

Created using Sphinx 7.1.2.