modest package¶
Subpackages¶
- modest.plots package
- modest.setupfunctions package
- modest.signals package
- Submodules
- modest.signals.oneDimensionalObject module
- modest.signals.periodicxraysource module
- modest.signals.pointsource module
- modest.signals.poissonsource module
- modest.signals.signalsource module
- modest.signals.staticxraypointsource module
- modest.signals.uniformnoisexraysource module
- modest.signals.xraysource module
- Module contents
- modest.spacecraft package
- modest.substates package
- modest.utils package
Submodules¶
modest.modularfilter module¶
synopsis: | This package contains the ModularFilter class. |
---|
-
class
modest.modularfilter.
ModularFilter
(measurementValidationThreshold=0.001, time=0, covarianceStorage='covariance')[source]¶ Bases:
object
This class is designed to facilitate a variety of estimation algorithms in a modular way, i.e. in a way that allows maximum amount of flexibility with minimum amount of code duplication.
The idea behind this class is that all of the functions which are “generic” to an estimation algorithm can be written just once, as a part of this class. Then the code contained here can be implemented on a variety of different estimation problems without having to duplicate code.
The basic estimation model implemented here works as follows. The overall state, i.e. all of the quantities to be estimated, are represented by
SubState
objects. Measurements of these states are represented bySignalSource
objects. The ModularFilter class is responsible for doing time-updates and measurement-updates on these states. These objects are responsible for doing all of the things that are particular to those states, and those signals, respectively. For instance, generation of time-update and measurement update matrices is handled by theSubState
objects.-
totalDimension
(int)¶ Type: Dimension of joint state vector (sum of all substate dimensions)
-
covarianceMatrix
(covarianceContainer)¶ Type: Object which stores covariance matrix
-
subStates
(dict)¶ Type: Dictionary of all substate objects
-
signalSources
(dict)¶ Type: Dictionary of all signal source objects
-
tCurrent
(float)¶ Type: Current filter time
-
measurementValidationThreshold
(float)¶ Type: Probability below which a signal source is rejected
-
measurementList
(list)¶ Type: A list of measurements used by the filter
-
lastStateVectorID
(int)¶ Type: A tag used to specify what the “last” state vector was
-
covarianceStroage
(str)¶ Type: String specifying how state error covariance is to be stored
-
plotHandle
¶ Type: Handle for real-time state plotting
-
addSignalSource
(name, signalSourceObject)[source]¶ addSignalSource is a utility function used to add a signal source to the joint estimator.
Parameters: - name (str) – The name by which the signal source can be referenced (must be unique)
- signalSourceObject (SignalSource) – An object that contains the signal source and is responsible for performing various tasks related to the substate.
-
addStates
(name, stateObject)[source]¶ addStates is a utility function used to add a state to the ModularFilter.
Parameters: - name (str) – The name by which the state can be referenced (must be unique)
- stateObject (substate) – An object that contains the sub-state and is responsible for performing various tasks related to the substate.
-
computeAssociationProbabilities
(measurement)[source]¶ computeAssociationProbabilities is responsible for computing the probability that a measurement originated from each of the signal sources being tracked by the estimator.
The function assumes that each signal source object has a member function which will compute the probability of origination, given the measurement and the prior state values,
SignalSource()
. Additionally, it assumes that the objects take a validation threshold as an optional argument.It is up to each individual signal source to determine it’s own probability of association given the current state vector. For some signal sources the probability may be zero, particularly if the measurement does not contain anything that could have possibly originated from that signal source (e.g. a signal source that measures only velocity would have zero probability of association with a position measurement).
Parameters: measurement (dict) – The measurement for which the probability is to be computed. Example:
myFilter.computeAssociationProbabilities( { 'position': {'value': [0, 0, 100], 'var' [0.01, 0.01, 0.01]} } )
-
getGlobalStateVector
()[source]¶ This function collects the substate vectors from each substate, and assembles the global state vector.
-
measurementUpdateEKF
(measurement, sourceName)[source]¶ measurementUpdateEKF performs a standard Extended Kalman Filter measurement update.
This function only works when the signal source is known, which may or may not be a realistic assumption, depending on the problem. Alternatively, it can be used for comparison to other data association methods.
As with other update methods, the updated state and covariance are returned. However the function also stores and distributes the state and covariance to the substates, so the user does not need to do anything with the returned state and covariance.
Note that there is no time associated with the measurement; the filter assumes that the measurement is occuring at the current time. Therefore it is the user’s responsibility to time-update the state to the current time before doing the measurement update.
Parameters: - measurement (dict) – Dictionary containing all the relevant measurable quanties labeled in a way that the substates and signal source objects understand.
- sourceName (str) – A string that contains the name of the signal source from which the measurement originated. This must be the name of one of the signal sources that have been added to the estimator.
Returns: The measurement-updated state vector and covariance
Return type: numpy.array, covarianceContainer
Example:
myFilter.computeAssociationProbabilities( { 'position': {'value': [0, 0, 100], 'var' [0.01, 0.01, 0.01]}, }, 'range1' )
-
measurementUpdateJPDAF
(measurement)[source]¶ measurementUpdateJPDAF performs a measurement using the joint probabilistic data association framework.
The first step is to assemble the global state vector from each sub-state vector. This is performed using
getGlobalStateVector()
.This function then computes the probability of association of the measurement with each signal source using
computeAssociationProbabilities()
. Associations with probabilities lower thanmeasurementValidationThreshold
.Finally, the updated state vector and covariance matrix is distributed to the substates using
storeGlobalStateVector()
.As with other update methods, the updated state and covariance are returned. However the function also stores and distributes the state and covariance to the substates, so the user does not need to do anything with the returned state and covariance.
Note that there is no time associated with the measurement; the filter assumes that the measurement is occuring at the current time. Therefore it is the user’s responsibility to time-update the state to the current time before doing the measurement update.
Parameters: measurement (dict) – Dictionary containing all the relevant measurable quanties labeled in a way that the substates and signal source objects understand. Returns: Dictionary containing all the relevant measurable quanties labeled in a way that the substates and signal source objects understand. Return type: measurement (dict) Example:
myFilter.computeAssociationProbabilities( { 'position': {'value': [0, 0, 100], 'var' [0.01, 0.01, 0.01]}, } )
-
measurementUpdateML
(measurement)[source]¶ measurementUpdateML performs a maximum-likelhood measurement update
The first step is to assemble the global state vector from each sub-state vector. This is performed using
getGlobalStateVector()
.This function first computes the probability of association of the measurement with each signal source using
computeAssociationProbabilities()
. Whichever signal is most likely is assumed to be the correct measurement source and is used to update the state (assuming the probability is abovemeasurementValidationThreshold
).Finally, the updated state vector and covariance matrix is distributed to the substates using
storeGlobalStateVector()
.As with other update methods, the updated state and covariance are returned. However the function also stores and distributes the state and covariance to the substates, so the user does not need to do anything with the returned state and covariance.
Note that there is no time associated with the measurement; the filter assumes that the measurement is occuring at the current time. Therefore it is the user’s responsibility to time-update the state to the current time before doing the measurement update.
Parameters: measurement (dict) – Dictionary containing all the relevant measurable quanties labeled in a way that the substates and signal source objects understand. Returns: Dictionary containing all the relevant measurable quanties labeled in a way that the substates and signal source objects understand. Return type: measurement (dict) Example:
myFilter.computeAssociationProbabilities( { 'position': {'value': [0, 0, 100], 'var' [0.01, 0.01, 0.01]}, } )
-
timeUpdateEKF
(dT, dynamics={})[source]¶ Performs a standard extended Kalman filter time-update using information found in dynamcs, and over time-interval dT.
Following the general framework for the ModularFilter, this function only performs the tasks that are universal across all the substates. It is up to the substates to process the dynamics infromation and build the appropriate time-update matrices ($F$ and $Q$). This is done by calling
timeUpdate()
for each substate.Once the substate time update matrices are received, they are combined to form a single set of time-update matrices, and then the state vector and covariance are updated. The updated states and covariances are then passed back to the substates for them to do any nescessary post-processing.
This function allows for a variable-length time update, so it is up to the user to determine what length of time is appropriate. Often, the time-update will simply update the state to the next measurement time, if the time between measurements is short. If the time between measurements is longer, then the length of time-update will most likely depend upon what time-regime the dynamics dictionary is valid over. For example if the dynamics dict contains acceleration information, the user should specify a dT over which the acceleration is approximately constant.
While values are returned containing the time-updated state vector and covariance, these are also automatically stored and dissimenated to the substates for additional processing, so the user does not need to do anything with these returned values. They are returned merely for convenience and monitoring by the user as desired.
Parameters: Returns: The time-updated state vector and covariance
Return type: numpy.array, covarianceContainer
Example:
myFilter.timeUpdateEKF( 0.01, dynamics={ 'acceleration': {'value': [0, 0, -9.81], 'var' [0.01, 0.01, 0.01]} } )
This command would pass the dynamics dict containing a three-dimensional acceleration vector and associated variances to the substates, and perform a time update from the current time to time pluse 0.01. Note that it is up to the substates to decide what to do (if anything) with the dynamics information.
-
Module contents¶
-
class
modest.
ModularFilter
(measurementValidationThreshold=0.001, time=0, covarianceStorage='covariance')[source]¶ Bases:
object
This class is designed to facilitate a variety of estimation algorithms in a modular way, i.e. in a way that allows maximum amount of flexibility with minimum amount of code duplication.
The idea behind this class is that all of the functions which are “generic” to an estimation algorithm can be written just once, as a part of this class. Then the code contained here can be implemented on a variety of different estimation problems without having to duplicate code.
The basic estimation model implemented here works as follows. The overall state, i.e. all of the quantities to be estimated, are represented by
SubState
objects. Measurements of these states are represented bySignalSource
objects. The ModularFilter class is responsible for doing time-updates and measurement-updates on these states. These objects are responsible for doing all of the things that are particular to those states, and those signals, respectively. For instance, generation of time-update and measurement update matrices is handled by theSubState
objects.-
totalDimension
(int)¶ Type: Dimension of joint state vector (sum of all substate dimensions)
-
covarianceMatrix
(covarianceContainer)¶ Type: Object which stores covariance matrix
-
subStates
(dict)¶ Type: Dictionary of all substate objects
-
signalSources
(dict)¶ Type: Dictionary of all signal source objects
-
tCurrent
(float)¶ Type: Current filter time
-
measurementValidationThreshold
(float)¶ Type: Probability below which a signal source is rejected
-
measurementList
(list)¶ Type: A list of measurements used by the filter
-
lastStateVectorID
(int)¶ Type: A tag used to specify what the “last” state vector was
-
covarianceStroage
(str)¶ Type: String specifying how state error covariance is to be stored
-
plotHandle
¶ Type: Handle for real-time state plotting
-
addSignalSource
(name, signalSourceObject)[source]¶ addSignalSource is a utility function used to add a signal source to the joint estimator.
Parameters: - name (str) – The name by which the signal source can be referenced (must be unique)
- signalSourceObject (SignalSource) – An object that contains the signal source and is responsible for performing various tasks related to the substate.
-
addStates
(name, stateObject)[source]¶ addStates is a utility function used to add a state to the ModularFilter.
Parameters: - name (str) – The name by which the state can be referenced (must be unique)
- stateObject (substate) – An object that contains the sub-state and is responsible for performing various tasks related to the substate.
-
computeAssociationProbabilities
(measurement)[source]¶ computeAssociationProbabilities is responsible for computing the probability that a measurement originated from each of the signal sources being tracked by the estimator.
The function assumes that each signal source object has a member function which will compute the probability of origination, given the measurement and the prior state values,
SignalSource()
. Additionally, it assumes that the objects take a validation threshold as an optional argument.It is up to each individual signal source to determine it’s own probability of association given the current state vector. For some signal sources the probability may be zero, particularly if the measurement does not contain anything that could have possibly originated from that signal source (e.g. a signal source that measures only velocity would have zero probability of association with a position measurement).
Parameters: measurement (dict) – The measurement for which the probability is to be computed. Example:
myFilter.computeAssociationProbabilities( { 'position': {'value': [0, 0, 100], 'var' [0.01, 0.01, 0.01]} } )
-
getGlobalStateVector
()[source]¶ This function collects the substate vectors from each substate, and assembles the global state vector.
-
measurementUpdateEKF
(measurement, sourceName)[source]¶ measurementUpdateEKF performs a standard Extended Kalman Filter measurement update.
This function only works when the signal source is known, which may or may not be a realistic assumption, depending on the problem. Alternatively, it can be used for comparison to other data association methods.
As with other update methods, the updated state and covariance are returned. However the function also stores and distributes the state and covariance to the substates, so the user does not need to do anything with the returned state and covariance.
Note that there is no time associated with the measurement; the filter assumes that the measurement is occuring at the current time. Therefore it is the user’s responsibility to time-update the state to the current time before doing the measurement update.
Parameters: - measurement (dict) – Dictionary containing all the relevant measurable quanties labeled in a way that the substates and signal source objects understand.
- sourceName (str) – A string that contains the name of the signal source from which the measurement originated. This must be the name of one of the signal sources that have been added to the estimator.
Returns: The measurement-updated state vector and covariance
Return type: numpy.array, covarianceContainer
Example:
myFilter.computeAssociationProbabilities( { 'position': {'value': [0, 0, 100], 'var' [0.01, 0.01, 0.01]}, }, 'range1' )
-
measurementUpdateJPDAF
(measurement)[source]¶ measurementUpdateJPDAF performs a measurement using the joint probabilistic data association framework.
The first step is to assemble the global state vector from each sub-state vector. This is performed using
getGlobalStateVector()
.This function then computes the probability of association of the measurement with each signal source using
computeAssociationProbabilities()
. Associations with probabilities lower thanmeasurementValidationThreshold
.Finally, the updated state vector and covariance matrix is distributed to the substates using
storeGlobalStateVector()
.As with other update methods, the updated state and covariance are returned. However the function also stores and distributes the state and covariance to the substates, so the user does not need to do anything with the returned state and covariance.
Note that there is no time associated with the measurement; the filter assumes that the measurement is occuring at the current time. Therefore it is the user’s responsibility to time-update the state to the current time before doing the measurement update.
Parameters: measurement (dict) – Dictionary containing all the relevant measurable quanties labeled in a way that the substates and signal source objects understand. Returns: Dictionary containing all the relevant measurable quanties labeled in a way that the substates and signal source objects understand. Return type: measurement (dict) Example:
myFilter.computeAssociationProbabilities( { 'position': {'value': [0, 0, 100], 'var' [0.01, 0.01, 0.01]}, } )
-
measurementUpdateML
(measurement)[source]¶ measurementUpdateML performs a maximum-likelhood measurement update
The first step is to assemble the global state vector from each sub-state vector. This is performed using
getGlobalStateVector()
.This function first computes the probability of association of the measurement with each signal source using
computeAssociationProbabilities()
. Whichever signal is most likely is assumed to be the correct measurement source and is used to update the state (assuming the probability is abovemeasurementValidationThreshold
).Finally, the updated state vector and covariance matrix is distributed to the substates using
storeGlobalStateVector()
.As with other update methods, the updated state and covariance are returned. However the function also stores and distributes the state and covariance to the substates, so the user does not need to do anything with the returned state and covariance.
Note that there is no time associated with the measurement; the filter assumes that the measurement is occuring at the current time. Therefore it is the user’s responsibility to time-update the state to the current time before doing the measurement update.
Parameters: measurement (dict) – Dictionary containing all the relevant measurable quanties labeled in a way that the substates and signal source objects understand. Returns: Dictionary containing all the relevant measurable quanties labeled in a way that the substates and signal source objects understand. Return type: measurement (dict) Example:
myFilter.computeAssociationProbabilities( { 'position': {'value': [0, 0, 100], 'var' [0.01, 0.01, 0.01]}, } )
-
timeUpdateEKF
(dT, dynamics={})[source]¶ Performs a standard extended Kalman filter time-update using information found in dynamcs, and over time-interval dT.
Following the general framework for the ModularFilter, this function only performs the tasks that are universal across all the substates. It is up to the substates to process the dynamics infromation and build the appropriate time-update matrices ($F$ and $Q$). This is done by calling
timeUpdate()
for each substate.Once the substate time update matrices are received, they are combined to form a single set of time-update matrices, and then the state vector and covariance are updated. The updated states and covariances are then passed back to the substates for them to do any nescessary post-processing.
This function allows for a variable-length time update, so it is up to the user to determine what length of time is appropriate. Often, the time-update will simply update the state to the next measurement time, if the time between measurements is short. If the time between measurements is longer, then the length of time-update will most likely depend upon what time-regime the dynamics dictionary is valid over. For example if the dynamics dict contains acceleration information, the user should specify a dT over which the acceleration is approximately constant.
While values are returned containing the time-updated state vector and covariance, these are also automatically stored and dissimenated to the substates for additional processing, so the user does not need to do anything with these returned values. They are returned merely for convenience and monitoring by the user as desired.
Parameters: Returns: The time-updated state vector and covariance
Return type: numpy.array, covarianceContainer
Example:
myFilter.timeUpdateEKF( 0.01, dynamics={ 'acceleration': {'value': [0, 0, -9.81], 'var' [0.01, 0.01, 0.01]} } )
This command would pass the dynamics dict containing a three-dimensional acceleration vector and associated variances to the substates, and perform a time update from the current time to time pluse 0.01. Note that it is up to the substates to decide what to do (if anything) with the dynamics information.
-