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
  • CompositeState
    • CompositeState.value
    • CompositeState.stamp
    • CompositeState.state_id
    • CompositeState.dof
    • CompositeState.get_index_by_id()
    • CompositeState.get_slices()
    • CompositeState.add_state()
    • CompositeState.remove_state_by_id()
    • CompositeState.get_slice_by_id()
    • CompositeState.get_matrix_block_by_ids()
    • CompositeState.set_matrix_block_by_ids()
    • CompositeState.get_value_by_id()
    • CompositeState.get_state_by_id()
    • CompositeState.get_dof_by_id()
    • CompositeState.get_stamp_by_id()
    • CompositeState.set_stamp_by_id()
    • CompositeState.set_state_by_id()
    • CompositeState.set_value_by_id()
    • CompositeState.set_stamp_for_all()
    • CompositeState.to_list()
    • CompositeState.copy()
    • CompositeState.plus()
    • CompositeState.minus()
    • CompositeState.plus_by_id()
    • CompositeState.jacobian_from_blocks()
    • CompositeState.plus_jacobian()
    • CompositeState.minus_jacobian()
    • CompositeState.minus_jacobian_fd()
    • CompositeState.plus_jacobian_fd()

navlie.composite.CompositeState¶

class navlie.composite.CompositeState(state_list: List[State], stamp: float | None = None, state_id=None)¶

Bases: State

A “composite” state object intended to hold a list of State objects as a single conceptual “state”. The intended use is to hold a list of states as a single state at a specific time, of potentially different types, and this class will take care of defining the appropriate operations on the composite state such as the plus and minus methods, as well as the plus_jacobian and minus_jacobian methods.

Each state in the provided list has an index (the index in the list), as well as a state_id, which is found as an attribute in the corresponding State object.

It is possible to access sub-states in the composite states both by index and by ID.

Parameters:
  • state_list (List[State]) – List of State that forms this composite state

  • stamp (float, optional) – Timestamp of the composite state. This can technically be different from the timestamps of the substates.

  • state_id (Any, optional) – State ID of the composite state. This can be different from the state IDs of the substates.

value¶

The substates are the CompositeState’s value.

Type:

List[State]

stamp¶

Timestamp

Type:

float

state_id¶
dof¶

Degree of freedom of the state

Type:

int

get_index_by_id(state_id)¶

Get index of a particular state_id in the list of states.

get_slices() → List[slice]¶

Get slices for each state in the list of states.

add_state(state: State, stamp: float | None = None, state_id=None)¶

Adds a state and it’s corresponding slice to the composite state.

remove_state_by_id(state_id)¶

Removes a given state by ID.

get_slice_by_id(state_id, slices=None)¶

Get slice of a particular state_id in the list of states.

get_matrix_block_by_ids(mat: ndarray, state_id_1: Any, state_id_2: Any | None = None) → ndarray¶

Gets the portion of a matrix corresponding to two states.

This function is useful when extract specific blocks of a covariance matrix, for example.

Parameters:
  • mat (np.ndarray) – N x N matrix

  • state_id_1 (Any) – State ID of state 1.

  • state_id_2 (Any, optional) – State ID of state 2. If None, state_id_2 is set to state_id_1.

Returns:

Subblock of mat corrsponding to slices of state_id_1 and state_id_2.

Return type:

np.ndarray

set_matrix_block_by_ids(new_mat_block: ndarray, mat: ndarray, state_id_1: Any, state_id_2: Any | None = None) → ndarray¶

Sets the portion of the covariance block corresponding to two states.

Parameters:
  • new_mat_block (np.ndarray) – A subblock to be entered into mat.

  • mat (np.ndarray) – Full matrix.

  • state_id_1 (Any) – State ID of state 1.

  • state_id_2 (Any, optional) – State ID of state 2. If None, state_id_2 is set to state_id_1.

Returns:

mat with updated subblock.

Return type:

np.ndarray

get_value_by_id(state_id) → Any¶

Get state value by id.

get_state_by_id(state_id) → State¶

Get state object by id.

get_dof_by_id(state_id) → int¶

Get degrees of freedom of sub-state by id.

get_stamp_by_id(state_id) → float¶

Get timestamp of sub-state by id.

set_stamp_by_id(stamp: float, state_id)¶

Set the timestamp of a sub-state by id.

set_state_by_id(state: State, state_id)¶

Set the whole sub-state by id.

set_value_by_id(value: Any, state_id: Any)¶

Set the value of a sub-state by id.

set_stamp_for_all(stamp: float)¶

Set the timestamp of all substates.

to_list()¶

Converts the CompositeState object back into a list of states.

copy() → CompositeState¶

Returns a new composite state object where the state values have also been copied.

plus(dx, new_stamp: float | None = None) → CompositeState¶

Updates the value of each sub-state given a dx. Interally parses the dx vector.

minus(x: CompositeState) → ndarray¶

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

plus_by_id(dx, state_id: int, new_stamp: float | None = None) → CompositeState¶

Updates a specific sub-state.

jacobian_from_blocks(block_dict: dict)¶

Returns the jacobian of the entire composite state given jacobians associated with some of the substates. These are provided as a dictionary with the the keys being the substate IDs.

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: CompositeState) → 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).

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.

previous

navlie.composite.CompositeProcessModel

next

navlie.datagen

© Copyright 2022.

Created using Sphinx 7.1.2.