A B C D E F G H I J K L M N O P Q R S T U V W X Y

A

a - Variable in class javaslam.filter.Linearization
The constant term in the affine-Gaussian approximation g(x) = a + B x + w
A - Variable in class javaslam.filter.LinearGaussianFunction
The linear coefficient.
AbstractSLAMFilter - class javaslam.slam.AbstractSLAMFilter.
An abstract class extended by classes that implement filters for the Simultaneous Localization and Mapping (SLAM) problem.
AbstractSLAMFilter(int) - Constructor for class javaslam.slam.AbstractSLAMFilter
Constructor.
add(int, int) - Static method in class javaslam.util.Flops
Counts the number of floating point operations used to add two n-by-m matrices.
add(int, Object) - Method in class javaslam.util.ListSet
Inserts the specified element at the specified position in this set (optional operation).
add(Object) - Method in class javaslam.util.ListSet
Appends the specified element to the end of this set if it is not already in the set (optional operation).
add(Variable) - Method in class javaslam.tjt.JunctionTree
Adds a variable to this junction tree.
addAll(Collection) - Method in class javaslam.util.ListSet
Appends all of the elements in the specified collection to the end of this set, in the order that they are returned by the specified collection's iterator.
addAll(int, Collection) - Method in class javaslam.util.ListSet
Inserts all of the elements in the specified collection into this set at the specified position (optional operation).
addEdge(Edge) - Method in class javaslam.tjt.graph.Node
Adds an edge from this node to another node.
addLandmark(int, int) - Method in class javaslam.slam.AbstractSLAMFilter
Adds a new landmark to the map and returns its state variable.
addLandmark(int, int) - Method in class javaslam.slam.LinearizedSLAMFilter
Adds a new landmark to the map and returns its state variable.
addLandmark(int, int) - Method in interface javaslam.slam.SLAMFilter
Adds a new landmark to the map and returns its state variable.
asList() - Method in class javaslam.util.ListSet
Returns an unmodifiable view of this set as a list.

B

B - Variable in class javaslam.filter.Linearization
The linear coefficient in the affine-Gaussian approximation g(x) = a + B x + w
backSubst(int, int, int) - Static method in class javaslam.util.Flops
Counts the number of floating point operations used to solve for X via back substitution in the matrix equation AX = B where A is upper triangular.
bearing - Variable in class javaslam.slam.ExampleModel.InverseMeasurementModel
The noisy bearing measurement.
BEARING_NOISE - Static variable in class javaslam.slam.ExampleModel.LandmarkMeasurementModel
 
BEARING_NOISE - Static variable in class javaslam.slam.ExampleModel.InverseMeasurementModel
 
bestCover(Set) - Method in class javaslam.tjt.JunctionTree
Returns the cluster whose intersection with the supplied set of variables is largest and whose size is the smallest.
bestCoverToExtend(Set) - Method in class javaslam.tjt.JunctionTree
Returns the cluster that, if extended with the variables in vars, would cause the fewest number of cluster enlargements.
beta(double, double, Random) - Static method in class javaslam.prob.Sample
Returns a sample from Beta(a, b).
binomial(int, double, Random) - Static method in class javaslam.prob.Sample
Returns a sample from Binomial(n, p).
blather - Static variable in class javaslam.util.TJTF
A flag indicating whether mundane status messages should be displayed.
BreadthFirstTraversal - class javaslam.tjt.graph.BreadthFirstTraversal.
An iterator that traverses the nodes of a graph in breadth-first (siblings before children) order.
BreadthFirstTraversal(Node) - Constructor for class javaslam.tjt.graph.BreadthFirstTraversal
Constructor.

C

checkValid() - Method in class javaslam.tjt.JunctionTree
Tests to see if the junction tree is valid.
chol(int) - Static method in class javaslam.util.Flops
Counts the number of floating point operations used to compute the Cholesky decomposition of an n-by-n symmetric positive definite matrix.
clear() - Method in class javaslam.prob.Gaussian
Clears all variables from this Gaussian.
clear() - Method in class javaslam.util.ListSet
Removes all of the elements from this set (optional operation).
clear() - Method in class javaslam.util.PriorityQueue
Removes all items from this queue.
clone(JunctionTree.Cluster) - Method in class javaslam.tjt.ThinJunctionTree
Duplicates the supplied cluster and attaches the duplicate as a leaf off of the original cluster.
clusters - Variable in class javaslam.tjt.JunctionTree
The Clusters in this junction tree.
clustersBySize - Variable in class javaslam.tjt.ThinJunctionTree
A priority queue of clusters prioritized by their size.
collectEvidence(JunctionTree.Cluster, boolean) - Method in class javaslam.tjt.JunctionTree.Cluster
Collects evidence to this cluster.
compareTo(Object) - Method in class javaslam.util.PriorityQueue.QueueElement
Compares this object with the specified object for order.
complement(Set) - Method in class javaslam.util.ListSet
Creates an ordered set that is the complement of this set in the supplied set of objects.
computeError() - Method in class javaslam.tjt.ThinJunctionTree.Contraction
Computes the approximation error introduced by a variable contraction along an edge e = Ci -> Cj.
condition(ListSet, Matrix, boolean) - Method in class javaslam.prob.Gaussian
Conditions on a subset of the variables in this Gaussian.
consistent() - Method in class javaslam.tjt.JunctionTree
Tests to see if the junction tree is consistent.
consistent() - Method in class javaslam.tjt.JunctionTree.JTEdge
Returns true iff this edge is consistent.
contains(int) - Method in class javaslam.slam.AbstractSLAMFilter
Return true if this filter contains the landmark with the supplied identifier.
contains(int) - Method in class javaslam.slam.LinearizedSLAMFilter
Return true if this filter contains the landmark with the supplied identifier.
contains(int) - Method in interface javaslam.slam.SLAMFilter
Return true if this filter contains the landmark with the supplied identifier.
contains(Object) - Method in class javaslam.util.ListSet
Returns true if this set contains the specified element.
contains(Set) - Method in class javaslam.tjt.JunctionTree.Cluster
Returns true if this cluster contains the supplied set of variables.
contains(Variable) - Method in class javaslam.tjt.JunctionTree
Returns true if this junction tree contains the supplied variable.
contains(Variable) - Method in class javaslam.tjt.JunctionTree.Cluster
Returns true if this cluster contains the supplied variable.
containsAll(Collection) - Method in class javaslam.util.ListSet
Returns true if this set contains all of the elements of the specified collection.
containsAny(Collection) - Method in class javaslam.util.ListSet
Returns true if this set contains any of the elements of the specified collection.
contract(Variable) - Method in class javaslam.tjt.ThinJunctionTree
Contracts var from all clusters but one and returns that cluster.
contractTo(Variable, JunctionTree.Cluster) - Method in class javaslam.tjt.ThinJunctionTree
Contracts var from all clusters but cluster (which must contain var).
count() - Static method in class javaslam.util.Flops
Returns the number of floating point operations performed by code in the tjtf package since the virtual machine was started.
count(long) - Static method in class javaslam.util.Flops
Increments the flop counter by f.
countFlops - Static variable in class javaslam.util.Flops
A flag that determines whether Flops.count(long) will increment the flop count.
createCover(Set) - Method in class javaslam.tjt.JunctionTree
Updates this junction tree so that it has a cluster containing the supplied set of variables, while preserving validity and consistency.
current - Variable in class javaslam.tjt.graph.Traversal
The most recently returned node, or null if next() has not yet been called.
current() - Method in class javaslam.tjt.graph.Traversal
Returns the current node without advancing the iterator.
cycle - Variable in class javaslam.tjt.graph.Traversal
If true, then this iterator has traversed a node more than once.

D

data - Variable in class javaslam.tjt.graph.NodeFilter
An arbitrary piece of data used by the predicate.
DBL_EPSILON - Static variable in class javaslam.prob.Sample
Analogous to eps in Matlab.
debug - Static variable in class javaslam.util.TJTF
A flag indicating whether special (expensive) checks should be made to ensure that everything is operating correctly.
DEL_X - Static variable in class javaslam.slam.ExampleModel.LandmarkMeasurementModel
 
DEL_X - Static variable in class javaslam.slam.ExampleModel.InverseMeasurementModel
 
DEL_Y - Static variable in class javaslam.slam.ExampleModel.LandmarkMeasurementModel
 
DEL_Y - Static variable in class javaslam.slam.ExampleModel.InverseMeasurementModel
 
DepthFirstTraversal - class javaslam.tjt.graph.DepthFirstTraversal.
An iterator that traverses the nodes of a graph in depth-first (children before siblings) order.
DepthFirstTraversal(Node) - Constructor for class javaslam.tjt.graph.DepthFirstTraversal
Constructor.
dequeue() - Method in class javaslam.util.PriorityQueue
Dequeues the item with the highest priority.
dequeue() - Method in class javaslam.tjt.graph.BreadthFirstTraversal
Dequeues a node to visit.
dequeue() - Method in class javaslam.tjt.graph.DepthFirstTraversal
Dequeues a node to visit.
dequeue() - Method in class javaslam.tjt.graph.Traversal
Dequeues a node to visit.
descendants - Variable in class javaslam.tjt.ThinJunctionTree.Contraction
If not null, this is a list of ThinJunctionTree.Contractions that must first be executed before this contraction can be executed.
det(int, boolean) - Static method in class javaslam.util.Flops
Counts the number of floating point operations used to compute the determinant of an n-by-n matrix that is possibly symmetric positive definite.
dim - Variable in class javaslam.prob.Variable
The dimension of this variable.
dimension(Set) - Static method in class javaslam.prob.Variable
Computes the sum dimension of a set of Variables.
distributeEvidence(JunctionTree.Cluster) - Method in class javaslam.tjt.JunctionTree.Cluster
Distributes evidence from this cluster.
distributeEvidence(JunctionTree.Cluster, double) - Method in class javaslam.tjt.JunctionTree.Cluster
Distributes evidence from this cluster so long as the propagated messages are having a significant effect on the belief state.
div(Gaussian, boolean) - Method in class javaslam.prob.Gaussian
Divides two Gaussians (in the canonical parameterization).
doubling - Variable in class javaslam.prob.Gaussian
If true, then the capacity (i.e., the actual dimension of Gaussian.vP and Gaussian.mP) of this Gaussian is doubled when it must be increased to accomodate new variables; otherwise it is increased only enough to admit the new variables.

E

e - Variable in class javaslam.tjt.ThinJunctionTree.Contraction
The edge along which the variable is to be contracted.
Edge - class javaslam.tjt.graph.Edge.
A directed edge in a graph.
edge() - Method in class javaslam.tjt.graph.Traversal
Returns the edge traversed to arrive at the current node.
Edge(Node, Node) - Constructor for class javaslam.tjt.graph.Edge
Default constructor.
edges - Variable in class javaslam.tjt.graph.Node
A mapping from neighbor Nodes to the Edges to them.
edges - Variable in class javaslam.tjt.graph.Traversal
A mapping from each node to the Edge used to arrive at that node (most recently).
edges() - Method in class javaslam.tjt.graph.Node
Returns (an unmodifiable view of) the set of Edges incident from this node.
elements - Variable in class javaslam.util.PriorityQueue
A list of QueueElement objects ordered by their priorities.
enlarge(JunctionTree.Cluster, Variable) - Method in class javaslam.tjt.JunctionTree
Extends the supplied cluster so that it contains the supplied variable without preserving consistency or the running-intersection property.
enlarge(JunctionTree.Cluster, Variable) - Method in class javaslam.tjt.ThinJunctionTree
Extends the supplied cluster so that it contains the supplied variable without preserving consistency or the running-intersection property.
enqueue(Node) - Method in class javaslam.tjt.graph.BreadthFirstTraversal
Enqueues a node for later visit.
enqueue(Node) - Method in class javaslam.tjt.graph.DepthFirstTraversal
Enqueues a node for later visit.
enqueue(Node) - Method in class javaslam.tjt.graph.Traversal
Enqueues a node for later visit.
enqueue(Object, Comparable) - Method in class javaslam.util.PriorityQueue
Enqueues a new item with the supplied priority.
entropy() - Method in class javaslam.prob.Gaussian
Computes the differential entropy H of this Gaussian.
equals(Object) - Method in class javaslam.prob.Variable
Finalizes the definition of equals so that two variable references are equal iff they refer to the same object.
equals(Object) - Method in class javaslam.util.PriorityQueue.QueueElement
Returns true if two elements are the same, which is true only when the corresponding items are equal.
equals(Object) - Method in class javaslam.tjt.ThinJunctionTree.Contraction
Returns true if this and the supplied object are equal.
equals(Object) - Method in class javaslam.tjt.graph.Edge
Redefines equals so that two edges are equal if their termini are the equal.
equals(Object) - Method in class javaslam.tjt.graph.Node
Finalizes the definition of equals so that two nodes are equal iff they are the same object.
err - Variable in class javaslam.tjt.ThinJunctionTree.Contraction
The approximation error induced by this contraction.
error() - Method in class javaslam.tjt.ThinJunctionTree.Contraction
Returns the approximation error that will result if this contraction is executed, which is the relative entropy (or Kullback-Lieblier divergence) from the original distribution to the resulting distribution.
evaluate(double[]) - Method in class javaslam.filter.LinearGaussianFunction
Evaluates this function at the supplied input.
evaluate(double[]) - Method in interface javaslam.filter.VectorFunction
Evaluates this function at the supplied input.
evaluate(double[]) - Method in class javaslam.slam.ExampleModel.MotionModel
Evaluates this function at the supplied input.
evaluate(double[]) - Method in class javaslam.slam.ExampleModel.OdometryModel
Evaluates this function at the supplied input.
evaluate(double[]) - Method in class javaslam.slam.ExampleModel.LandmarkMeasurementModel
Evaluates this function at the supplied input.
evaluate(double[]) - Method in class javaslam.slam.ExampleModel.InverseMeasurementModel
Evaluates this function at the supplied input.
ExampleModel - class javaslam.slam.ExampleModel.
A SLAM model for a robot that can rotate about its vertical axis and translate along its current heading and which receives differential odometry measurements and range-bearing landmark measurements.
ExampleModel.InverseMeasurementModel - class javaslam.slam.ExampleModel.InverseMeasurementModel.
The inverse landmark measurement model of the robot.
ExampleModel.InverseMeasurementModel(double[]) - Constructor for class javaslam.slam.ExampleModel.InverseMeasurementModel
Constructor.
ExampleModel.LandmarkMeasurementModel - class javaslam.slam.ExampleModel.LandmarkMeasurementModel.
The landmark measurement model of the robot.
ExampleModel.LandmarkMeasurementModel() - Constructor for class javaslam.slam.ExampleModel.LandmarkMeasurementModel
 
ExampleModel.MotionModel - class javaslam.slam.ExampleModel.MotionModel.
The motion model of the robot.
ExampleModel.MotionModel(double[]) - Constructor for class javaslam.slam.ExampleModel.MotionModel
Constructor.
ExampleModel.OdometryModel - class javaslam.slam.ExampleModel.OdometryModel.
The odometry model of the robot.
ExampleModel.OdometryModel() - Constructor for class javaslam.slam.ExampleModel.OdometryModel
 
ExampleModel() - Constructor for class javaslam.slam.ExampleModel
Constructor.
execute() - Method in class javaslam.tjt.ThinJunctionTree.Contraction
Executes the edge contraction.
exp() - Static method in class javaslam.util.Flops
Counts the number of floating point operations used to compute the exponential of a number.
extend(JunctionTree.Cluster, Variable) - Method in class javaslam.tjt.JunctionTree
Minimally alters the structure and parameterization of the junction tree so that cluster covers var and validity and consistency are preserved.
extend(Set) - Method in class javaslam.prob.Gaussian
Extends this Gaussian to include a new set of variables.
extend(Set) - Method in class javaslam.tjt.JunctionTree.Cluster
Extends this cluster to contain the supplied set of Variables.
ExtendedTransformation - class javaslam.filter.ExtendedTransformation.
The extended transformation for linearizing functions with Gaussian-distributed inputs.
ExtendedTransformation(NoisyVectorFunction, Gaussian) - Constructor for class javaslam.filter.ExtendedTransformation
Constructor.
ExtendedVectorFunction - interface javaslam.filter.ExtendedVectorFunction.
A vector-valued function that takes a vector input and which can compute its Jacobian at any input.

F

f - Static variable in class javaslam.slam.LGSLAMFilterCanvas
 
factory - Static variable in class javaslam.filter.ExtendedTransformation
A factory for creating linearizations using the extended transformation.
factory - Static variable in class javaslam.filter.UnscentedTransformation
A factory for creating linearizations using the unscented transformation.
filter - Variable in class javaslam.filter.LinearizedFilter
The underlying linear-Gaussian filter.
filter - Variable in class javaslam.slam.LGSLAMFilterCanvas
The underlying filter.
filter - Variable in class javaslam.slam.LinearizedSLAMFilter
The underlying linear-Gaussian SLAM filter.
Filter - interface javaslam.filter.Filter.
A linear-Gaussian filter.
flops - Static variable in class javaslam.util.Flops
A counter of the number of floating-point operations performed.
Flops - class javaslam.util.Flops.
A class containing methods for counting floating point operations.
Flops() - Constructor for class javaslam.util.Flops
 
forwardSubst(int, int, int) - Static method in class javaslam.util.Flops
Counts the number of floating point operations used to solve for X via back substitution in the matrix equation AX = B where A is unit lower triangular.
frame(LGSLAMFilterCanvas) - Static method in class javaslam.slam.LGSLAMFilterCanvas
 
from - Variable in class javaslam.tjt.graph.Edge
The start of this edge.

G

G - Variable in class javaslam.filter.Linearization
The covariance of the white noise variable w in the affine-Gaussian approximation g(x) = a + B x + w
gamma(double, Random) - Static method in class javaslam.prob.Sample
Samples from the Gamma(a) distribution.
Gaussian - class javaslam.prob.Gaussian.
A Gaussian probability density over a set of vector-valued variables.
Gaussian(boolean) - Constructor for class javaslam.prob.Gaussian
Default constructor.
Gaussian(boolean, int) - Constructor for class javaslam.prob.Gaussian
Default constructor.
Gaussian(Gaussian) - Constructor for class javaslam.prob.Gaussian
Copy constructor.
Gaussian(Gaussian, Gaussian) - Constructor for class javaslam.prob.Gaussian
Separator Gaussian constructor.
Gaussian(ListSet, double[], double[][], boolean) - Constructor for class javaslam.prob.Gaussian
Constructor.
Gaussian(ListSet, Matrix, Matrix, boolean) - Constructor for class javaslam.prob.Gaussian
Constructor.
Gaussian(Set, boolean) - Constructor for class javaslam.prob.Gaussian
Creates an uninformative Gaussian density over the supplied set of variables.
get(int) - Method in class javaslam.util.ListSet
Returns the element at the specified position in this set.
getClusters() - Method in class javaslam.tjt.JunctionTree
Returns a Sets of the JunctionTree.Clusters of this junction tree.
getClustersWith(Variable) - Method in class javaslam.tjt.JunctionTree
Returns an unmodifiable set of Clusters containing the supplied variable.
getCoefficient() - Method in class javaslam.filter.Linearization
Returns the linear coefficient B in the affine-Gaussian approximation g(x) = a + B x + w
getCoefficient(Variable) - Method in class javaslam.filter.Linearization
Returns the submatrix of B in the affine-Gaussian approximation g(x) = a + B x + w that corresponds to the subvariable u of x.
getConditionalGaussian(ListSet, Matrix, Matrix, Matrix, Matrix) - Static method in class javaslam.filter.InformationFilter
Creates a linear-Gaussian measurement potential.
getConstantTerm() - Method in class javaslam.filter.Linearization
Returns the constant term in the affine-Gaussian approximation g(x) = a + B x + w
getContraction(JunctionTree.JTEdge, Variable) - Method in class javaslam.tjt.ThinJunctionTree
Creates a variable contraction of the supplied variable along the supplied edge.
getCover(Set) - Method in class javaslam.tjt.JunctionTree
Returns the smallest cluster containing the supplied variables, or null if there is no such cluster.
getDimension() - Method in class javaslam.prob.Gaussian
Gets the sum of the dimensions of all variables bound by this Gaussian.
getDimension() - Method in class javaslam.tjt.JunctionTree.Cluster
Returns the dimension of this cluster, which is the dimension of its potential.
getDistribution() - Method in class javaslam.filter.InformationFilter
Returns the current filtered belief state.
getDistribution() - Method in class javaslam.filter.KalmanFilter
Returns the current filtered belief state.
getDistribution() - Method in class javaslam.filter.Linearization
Returns a Gaussian approximation of the distribution over the function's inputs and output.
getEdge(Node) - Method in class javaslam.tjt.graph.Node
Gets the edge from this node to the supplied node; if no such edge exists, null is returned.
getEta(ListSet) - Method in class javaslam.prob.Gaussian
Gets a subvector of h.
getFactory() - Static method in class javaslam.filter.ExtendedTransformation
Returns a handle on a factory for creating linearizations using the extended transformation.
getFactory() - Static method in class javaslam.filter.UnscentedTransformation
Returns a handle on a factory for creating linearizations using the unscented transformation.
getIndices(ListSet) - Method in class javaslam.prob.Gaussian
Gets an array of indices into the parameters that corresponds to the supplied set of variables.
getInputDim() - Method in class javaslam.filter.LinearGaussianFunction
Returns the input dimension of this function.
getInputDim() - Method in interface javaslam.filter.VectorFunction
Returns the input dimension of this function.
getInputDim() - Method in class javaslam.slam.ExampleModel.MotionModel
Returns the input dimension of this function.
getInputDim() - Method in class javaslam.slam.ExampleModel.OdometryModel
Returns the input dimension of this function.
getInputDim() - Method in class javaslam.slam.ExampleModel.LandmarkMeasurementModel
Returns the input dimension of this function.
getInputDim() - Method in class javaslam.slam.ExampleModel.InverseMeasurementModel
Returns the input dimension of this function.
getInverseMeasurementModel(double[]) - Method in class javaslam.slam.ExampleModel
Returns the landmark observation model.
getInverseMeasurementModel(double[]) - Method in interface javaslam.slam.Model
Returns the inverse of the landmark observation model (at zti = z) with respect to the landmark state: lj = h-1 z(xt, u).
getJunctionTree() - Method in class javaslam.tjt.JunctionTree.Cluster
Returns the junction tree this cluster resides in.
getJunctionTree() - Method in class javaslam.filter.JTFilter
Gets the junction tree representation of the belief state.
getJunctionTree() - Method in class javaslam.slam.TJTSLAMFilter
Gets the junction tree representation of the belief state.
getKalmanFilter() - Method in class javaslam.slam.KalmanSLAMFilter
Returns the underlying Kalman filter used by this SLAM filter.
getLambda(ListSet, ListSet) - Method in class javaslam.prob.Gaussian
Gets a submatrix of L.
getLandmarkDim() - Method in class javaslam.slam.ExampleModel
Returns the dimension of each landmark's state.
getLandmarkDim() - Method in interface javaslam.slam.Model
Returns the dimension of each landmark's state.
getLandmarkEstimate(int) - Method in class javaslam.slam.AbstractSLAMFilter
Returns the filtered estimate of a landmark's state.
getLandmarkEstimate(int) - Method in class javaslam.slam.LGSLAMFilter
Returns the filtered estimate of a landmark's state.
getLandmarkEstimate(int) - Method in class javaslam.slam.LinearizedSLAMFilter
Returns the filtered estimate of a landmark's state.
getLandmarkEstimate(int) - Method in interface javaslam.slam.SLAMFilter
Returns the filtered estimate of a landmark's state.
getLandmarkId(Variable) - Method in class javaslam.slam.AbstractSLAMFilter
Gets the identifier associated with the supplied landmark state variable.
getLandmarkId(Variable) - Method in class javaslam.slam.LinearizedSLAMFilter
Gets the identifier associated with the supplied landmark state variable.
getLandmarkId(Variable) - Method in interface javaslam.slam.SLAMFilter
Gets the identifier associated with the supplied landmark state variable.
getLandmarkIds() - Method in class javaslam.slam.AbstractSLAMFilter
Returns the IDs of landmarks known to this filter.
getLandmarkIds() - Method in class javaslam.slam.LinearizedSLAMFilter
Returns the IDs of landmarks known to this filter.
getLandmarkIds() - Method in interface javaslam.slam.SLAMFilter
Returns the IDs of landmarks known to this filter.
getLandmarkMarginal(int) - Method in class javaslam.slam.InformationSLAMFilter
Returns the filtered marginal potential over a landmark's state (in the moment parameterization).
getLandmarkMarginal(int) - Method in class javaslam.slam.KalmanSLAMFilter
Returns the filtered marginal potential over a landmark's state (in the moment parameterization).
getLandmarkMarginal(int) - Method in class javaslam.slam.LGSLAMFilter
Returns the filtered marginal potential over a landmark's state (in the moment parameterization).
getLandmarkMarginal(int) - Method in class javaslam.slam.TJTSLAMFilter
Returns the filtered marginal potential over a landmark's state (in the moment parameterization).
getLandmarkMarginals(int[]) - Method in class javaslam.slam.InformationSLAMFilter
Given a collection of landmark state variables, this method returns the set of filtered marginal potentials over each individual landmark's state.
getLandmarkMarginals(int[]) - Method in class javaslam.slam.LGSLAMFilter
Given a collection of landmark state variables, this method returns the set of filtered marginal potentials over each individual landmark's state.
getLandmarkMarginals(int[]) - Method in class javaslam.slam.TJTSLAMFilter
Given a collection of landmark state variables, this method returns the set of filtered marginal potentials over each individual landmark's state.
getLandmarkNoiseModel() - Static method in class javaslam.slam.ExampleModel
Creates a landmark measurement noise model using parameters specified by system properties or default values (when the properties are not defined).
getLandmarkNoiseModel(double, double, double) - Static method in class javaslam.slam.ExampleModel
Creates a landmark measurement noise model.
getLandmarkVariable(int) - Method in class javaslam.slam.AbstractSLAMFilter
Gets the state variable associated with the landmark with the supplied identifier.
getLandmarkVariable(int) - Method in class javaslam.slam.LinearizedSLAMFilter
Gets the state variable associated with the landmark with the supplied identifier.
getLandmarkVariable(int) - Method in interface javaslam.slam.SLAMFilter
Gets the state variable associated with the landmark with the supplied identifier.
getLGFilter() - Method in class javaslam.slam.LinearizedSLAMFilter
Returns the underlying linear-Gaussian filter, which can be used to access the filtered belief state.
getMarginal(Set) - Method in interface javaslam.filter.Filter
Extracts the filtered marginal distribution.
getMarginal(Set) - Method in class javaslam.filter.InformationFilter
Extracts the filtered marginal distribution.
getMarginal(Set) - Method in class javaslam.filter.JTFilter
Extracts the filtered marginal distribution.
getMarginal(Set) - Method in class javaslam.filter.KalmanFilter
Extracts the filtered marginal distribution.
getMarginal(Set, boolean) - Method in class javaslam.tjt.JunctionTree
Extracts the marginal from the junction tree.
getMarginals(Collection) - Method in class javaslam.tjt.JunctionTree
Extracts a set of unary marginals from the junction tree without inverting any cluster potential more than once.
getMarginals(Collection) - Method in interface javaslam.filter.Filter
Extracts a set of unary marginals.
getMarginals(Collection) - Method in class javaslam.filter.InformationFilter
Extracts a set of unary marginals.
getMarginals(Collection) - Method in class javaslam.filter.JTFilter
Extracts a set of unary marginals.
getMarginals(Collection) - Method in class javaslam.filter.KalmanFilter
Extracts a set of unary marginals.
getMeasurementModel() - Method in class javaslam.slam.ExampleModel
Returns the landmark observation model.
getMeasurementModel() - Method in interface javaslam.slam.Model
Returns the landmark observation model zti = h(xt, lj, u).
getMotionModel(double[]) - Method in class javaslam.slam.ExampleModel
Returns the motion model.
getMotionModel(double[]) - Method in interface javaslam.slam.Model
Returns the motion model xt + 1 = f(xt, w).
getMotionNoiseModel() - Static method in class javaslam.slam.ExampleModel
Creates a motion noise model using parameters specified by system properties or default values (when the properties are not defined).
getMotionNoiseModel(double, double, double, double) - Static method in class javaslam.slam.ExampleModel
Creates a motion noise model.
getMu(ListSet) - Method in class javaslam.prob.Gaussian
Gets a subvector of m.
getNoiseCovariance() - Method in class javaslam.filter.Linearization
Returns the covariance matrix of the noise term w in the affine-Gaussian approximation g(x) = a + B x + w
getNoiseModel() - Method in class javaslam.filter.LinearGaussianFunction
Returns the Gaussian distribution over the noise input.
getNoiseModel() - Method in interface javaslam.filter.NoisyVectorFunction
Returns the Gaussian distribution over the noise input.
getNoiseModel() - Method in class javaslam.slam.ExampleModel.MotionModel
Returns the distribution over the noise variables for this motion model.
getNoiseModel() - Method in class javaslam.slam.ExampleModel.OdometryModel
Returns the distribution over the noise variables for this motion model.
getNoiseModel() - Method in class javaslam.slam.ExampleModel.LandmarkMeasurementModel
Returns the distribution over the noise variables for this motion model.
getNoiseModel() - Method in class javaslam.slam.ExampleModel.InverseMeasurementModel
Returns the distribution over the noise variables for this model.
getNumLandmarks() - Method in class javaslam.slam.AbstractSLAMFilter
Returns the number of landmarks known to this filter.
getNumLandmarks() - Method in class javaslam.slam.LinearizedSLAMFilter
Returns the number of landmarks known to this filter.
getNumLandmarks() - Method in interface javaslam.slam.SLAMFilter
Returns the number of landmarks known to this filter.
getOdometryModel() - Method in class javaslam.slam.ExampleModel
Returns the odometry model.
getOdometryModel() - Method in interface javaslam.slam.Model
Returns the odometry model yt = g(xt, v).
getOdometryNoiseModel() - Static method in class javaslam.slam.ExampleModel
Creates an odometry noise model using parameters specified by system properties or default values (when the properties are not defined).
getOdometryNoiseModel(double, double, double, double) - Static method in class javaslam.slam.ExampleModel
Creates an odometry noise model.
getOutputDim() - Method in class javaslam.filter.LinearGaussianFunction
Returns the output dimension of this function.
getOutputDim() - Method in interface javaslam.filter.VectorFunction
Returns the output dimension of this function.
getOutputDim() - Method in class javaslam.slam.ExampleModel.MotionModel
Returns the output dimension of this function.
getOutputDim() - Method in class javaslam.slam.ExampleModel.OdometryModel
Returns the output dimension of this function.
getOutputDim() - Method in class javaslam.slam.ExampleModel.LandmarkMeasurementModel
Returns the output dimension of this function.
getOutputDim() - Method in class javaslam.slam.ExampleModel.InverseMeasurementModel
Returns the output dimension of this function.
getOutputVariable() - Method in class javaslam.filter.Linearization
Returns the variable representing the output of the random function.
getPotential() - Method in class javaslam.tjt.JunctionTree.Cluster
Returns this cluster's potential.
getPotential() - Method in class javaslam.tjt.JunctionTree.JTEdge
Returns the separator potential.
getReverse() - Method in class javaslam.tjt.JunctionTree.JTEdge
Returns the complement of this edge, i.e., the edge that emanates from this edge's terminus and terminates on this edge's origin (and which shares this edge's separator potential).
getRobotDim() - Method in class javaslam.slam.ExampleModel
Returns the dimension of the robot's state.
getRobotDim() - Method in interface javaslam.slam.Model
Returns the dimension of the robot's state.
getRobotEstimate() - Method in class javaslam.slam.AbstractSLAMFilter
Returns the filtered estimate of the robot's state.
getRobotEstimate() - Method in class javaslam.slam.LGSLAMFilter
Returns the filtered estimate of the robot's state.
getRobotEstimate() - Method in class javaslam.slam.LinearizedSLAMFilter
Returns the filtered estimate of the robot's state.
getRobotEstimate() - Method in interface javaslam.slam.SLAMFilter
Returns the filtered estimate of the robot's state.
getRobotLandmarkMarginal(int) - Method in class javaslam.slam.InformationSLAMFilter
This method computes the joint filtered distribution over the states of the robot and a landmark.
getRobotLandmarkMarginal(int) - Method in class javaslam.slam.KalmanSLAMFilter
This method computes the joint filtered distribution over the states of the robot and a landmark.
getRobotLandmarkMarginal(int) - Method in class javaslam.slam.LGSLAMFilter
This method computes the joint filtered distribution over the states of the robot and a landmark.
getRobotLandmarkMarginal(int) - Method in class javaslam.slam.TJTSLAMFilter
This method computes the joint filtered distribution over the states of the robot and a landmark.
getRobotLandmarkMarginals(int[]) - Method in class javaslam.slam.InformationSLAMFilter
Given a set of landmarks { l1, ..., lk}, this method computes a set of potentials over (x, l1), ..., (x, lk).
getRobotLandmarkMarginals(int[]) - Method in class javaslam.slam.LGSLAMFilter
Given a set of landmarks { l1, ..., lk}, this method computes a set of potentials over (x, l1), ..., (x, lk).
getRobotLandmarkMarginals(int[]) - Method in class javaslam.slam.TJTSLAMFilter
Given a set of landmarks { l1, ..., lk}, this method computes a set of potentials over (x, l1), ..., (x, lk).
getRobotMarginal() - Method in class javaslam.slam.InformationSLAMFilter
Returns the filtered marginal potential (in the moment parameterization) over the robot's state.
getRobotMarginal() - Method in class javaslam.slam.KalmanSLAMFilter
Returns the filtered marginal potential over the robot's state.
getRobotMarginal() - Method in class javaslam.slam.LGSLAMFilter
Returns the filtered marginal potential over the robot's state (in the moment parameterization).
getRobotMarginal() - Method in class javaslam.slam.TJTSLAMFilter
Returns the filtered marginal potential (in the moment parameterization) over the robot's state.
getRobotVariable() - Method in class javaslam.slam.AbstractSLAMFilter
Gets the state variable associated with the robot.
getRobotVariable() - Method in class javaslam.slam.LinearizedSLAMFilter
Gets the state variable associated with the robot.
getRobotVariable() - Method in interface javaslam.slam.SLAMFilter
Gets the state variable associated with the robot.
getShortestPath(NodeFilter) - Method in class javaslam.tjt.graph.Node
Computes the shortest path from this node to another node satisfying a particular property.
getSigma(ListSet, ListSet) - Method in class javaslam.prob.Gaussian
Gets a submatrix of S.
getSize() - Method in class javaslam.prob.Gaussian
Returns the number of variables bound by this Gaussian.
getSize() - Method in class javaslam.tjt.JunctionTree.Cluster
Returns the size of this cluster, which is the size of its potential.
getSubsumedNeighbor() - Method in class javaslam.tjt.JunctionTree.Cluster
Searches for an adjacent cluster that whose variables are all contained in this cluster.
getSubsumingNeighbor() - Method in class javaslam.tjt.JunctionTree.Cluster
Searches for an adjacent cluster that contains all the variables contained in this cluster.
getUnconditionalGaussian(ListSet, ListSet, Matrix, Matrix, Matrix) - Static method in class javaslam.filter.InformationFilter
Constructs a linear-Gaussian potential that introduces a set of new unobserved variables.
getVariables() - Method in class javaslam.prob.Gaussian
Returns an unmodifiable ordered set of the Variables bound by this Gaussian.
getVariables() - Method in class javaslam.tjt.JunctionTree
Gets an unmodifiable set of the Variables in this junction tree.
getVariables() - Method in class javaslam.tjt.JunctionTree.Cluster
Returns an unmodifiable set of this cluster's variables.
getVariables() - Method in class javaslam.tjt.JunctionTree.JTEdge
Returns an unmodifiable set of this edge's separator variables.
getVariables() - Method in interface javaslam.filter.Filter
Gets an unmodifiable set of the Variables in the filtered belief state.
getVariables() - Method in class javaslam.filter.InformationFilter
Gets an unmodifiable set of the Variables in the filtered belief state.
getVariables() - Method in class javaslam.filter.JTFilter
Gets an unmodifiable set of the Variables in the filtered belief state.
getVariables() - Method in class javaslam.filter.KalmanFilter
Gets an unmodifiable set of the Variables in the filtered belief state.

H

hashCode() - Method in class javaslam.prob.Variable
Finalizes the definition of hashCode.
hashCode() - Method in class javaslam.util.PriorityQueue.QueueElement
Returns the hash code of this element's item.
hashCode() - Method in class javaslam.tjt.ThinJunctionTree.Contraction
Returns the hash code of this edge contraction.
hashCode() - Method in class javaslam.tjt.graph.Edge
Redefines hashCode so the hash code of an edge is the sum of the hash codes of its nodes.
hashCode() - Method in class javaslam.tjt.graph.Node
Finalizes the definition of hashCode to be the same as that of hashCode.
hasNext() - Method in class javaslam.util.PriorityQueue.QueueItemIterator
Returns true if this iterator has more items.
hasNext() - Method in class javaslam.tjt.graph.BreadthFirstTraversal
Returns true if the iteration has more elements.
hasNext() - Method in class javaslam.tjt.graph.DepthFirstTraversal
Returns true if the iteration has more elements.
hasNext() - Method in class javaslam.tjt.graph.Traversal
Returns true if the iteration has more elements.
HEADING - Static variable in class javaslam.slam.ExampleModel.MotionModel
 
HEADING - Static variable in class javaslam.slam.ExampleModel.OdometryModel
 
HEADING - Static variable in class javaslam.slam.ExampleModel.LandmarkMeasurementModel
 
HEADING - Static variable in class javaslam.slam.ExampleModel.InverseMeasurementModel
 
highest() - Method in class javaslam.util.PriorityQueue
Returns the priority of the highest priority item in the queue.

I

i - Variable in class javaslam.util.PriorityQueue.QueueItemIterator
The underlying iterator over elements.
id2lm - Variable in class javaslam.slam.AbstractSLAMFilter
A map from Integer landmark identifiers to Variables representing the corresponding landmark's state.
indexOf(Object) - Method in class javaslam.util.ListSet
Returns the index in this set of the specified element, or -1 if this set does not contain this element.
InformationFilter - class javaslam.filter.InformationFilter.
An Information filter.
InformationFilter(Gaussian) - Constructor for class javaslam.filter.InformationFilter
Constructor.
InformationSLAMFilter - class javaslam.slam.InformationSLAMFilter.
An information filter for the Simultaneous Localization and Mapping (SLAM) problem.
InformationSLAMFilter(double[], double[][]) - Constructor for class javaslam.slam.InformationSLAMFilter
Constructor.
initialize(JunctionTree.JTEdge, Variable, boolean) - Method in class javaslam.tjt.ThinJunctionTree.Contraction
Initializer.
initialize(ListSet, Matrix, Matrix) - Method in class javaslam.prob.Gaussian
Initializes this Gaussian using the supplied arguments.
INPUT_DIM - Static variable in class javaslam.slam.ExampleModel.MotionModel
The input dimension of the motion model.
INPUT_DIM - Static variable in class javaslam.slam.ExampleModel.OdometryModel
The input dimension of the odometry model.
INPUT_DIM - Static variable in class javaslam.slam.ExampleModel.LandmarkMeasurementModel
The input dimension of the landmark measurement model.
INPUT_DIM - Static variable in class javaslam.slam.ExampleModel.InverseMeasurementModel
The input dimension of the model.
inv(int, boolean) - Static method in class javaslam.util.Flops
Counts the number of floating point operations used to invert an n-by-n matrix that is possibly symmetric positive definite.
isCanonical() - Method in class javaslam.prob.Gaussian
Returns true if this Gaussian is represented using the canonical parameterization, i.e., using the vector h and the (positive definite) matrix L.
isCyclic() - Method in class javaslam.tjt.graph.Traversal
Returns true if the traversal has visited a node more than once, implying the existence of a cycle if the graph is undirected.
isEmpty() - Method in class javaslam.util.ListSet
Returns true if this set contains no elements.
isEmpty() - Method in class javaslam.util.PriorityQueue
Returns true iff this queue is empty.
isLeaf() - Method in class javaslam.tjt.JunctionTree.Cluster
Returns true if this cluster is a leaf.
isMoment - Variable in class javaslam.prob.Gaussian
A field indicating whether this Gaussian is currently represented in the moment parameterization.
isMoment() - Method in class javaslam.prob.Gaussian
Returns true if this Gaussian is represented using the moment parameterization, i.e., using the mean vector m and the (positive definite) covariance matrix S.
isSubtreeLeaf(JunctionTree.Cluster, Variable) - Method in class javaslam.tjt.ThinJunctionTree
Determines if the supplied cluster is a non-root leaf of the subtree induced by the supplied variable.
item - Variable in class javaslam.util.PriorityQueue.QueueElement
The actual item.
itemsToElements - Variable in class javaslam.util.PriorityQueue
Maps items to their elements.
iterator() - Method in class javaslam.util.ListSet
Returns an iterator over the elements in this set in proper sequence.
iterator() - Method in class javaslam.util.PriorityQueue
Returns an iterator over the items in this priority queue in order of decreasing priority.

J

jacobian(double[]) - Method in interface javaslam.filter.ExtendedVectorFunction
Evaluates the Jacobian of this function at the supplied input.
jacobian(double[]) - Method in class javaslam.filter.LinearGaussianFunction
Evaluates the Jacobian of this function at the supplied input.
jacobian(double[]) - Method in class javaslam.slam.ExampleModel.MotionModel
Evaluates the Jacobian of this function at the supplied input.
jacobian(double[]) - Method in class javaslam.slam.ExampleModel.OdometryModel
Evaluates the Jacobian of this function at the supplied input.
jacobian(double[]) - Method in class javaslam.slam.ExampleModel.LandmarkMeasurementModel
Evaluates the Jacobian of this function at the supplied input.
jacobian(double[]) - Method in class javaslam.slam.ExampleModel.InverseMeasurementModel
Evaluates the Jacobian of this function at the supplied input.
javaslam.filter - package javaslam.filter
Contains data structures and algorithms for linear-Gaussian filtering and linearizing nonlinear functions.
javaslam.prob - package javaslam.prob
Contains data structures and algorithms relating to probability theory.
javaslam.slam - package javaslam.slam
Contains data structures and algorithms for filtering approaches to the Simultaneous Localization and Mapping (SLAM) problem (with known data association).
javaslam.tjt - package javaslam.tjt
Contains data structures and algorithms for incremental junction tree maintenance and junction tree thinning.
javaslam.tjt.graph - package javaslam.tjt.graph
Contains a simple graph data structure and methods for search.
javaslam.util - package javaslam.util
Contains generic data structures and algorithms.
joseph(ListSet, double[], double[][], double[][], double[]) - Method in class javaslam.filter.KalmanFilter
Performs a linear-Gaussian measurement update using the Joseph form of the covariance update, which is numerically more stable.
jt - Variable in class javaslam.filter.JTFilter
The junction tree used to represent the belief state.
jt - Variable in class javaslam.slam.TJTSLAMFilter
The thin junction tree used to represent the filtered belief state.
JTFilter - class javaslam.filter.JTFilter.
A junction tree filter.
JTFilter(JunctionTree) - Constructor for class javaslam.filter.JTFilter
Default constructor.
JunctionTree - class javaslam.tjt.JunctionTree.
A junction tree for a Gaussian graphical model.
JunctionTree.Cluster - class javaslam.tjt.JunctionTree.Cluster.
A cluster of a junction tree.
JunctionTree.Cluster() - Constructor for class javaslam.tjt.JunctionTree.Cluster
Creates an empty cluster.
JunctionTree.Cluster(Gaussian) - Constructor for class javaslam.tjt.JunctionTree.Cluster
Creates a cluster with the supplied potential.
JunctionTree.Cluster(JunctionTree.Cluster) - Constructor for class javaslam.tjt.JunctionTree.Cluster
Copy constructor.
JunctionTree.JTEdge - class javaslam.tjt.JunctionTree.JTEdge.
A (directed) edge from one cluster to another in a junction tree.
JunctionTree.JTEdge(JunctionTree.Cluster, JunctionTree.Cluster, Gaussian) - Constructor for class javaslam.tjt.JunctionTree.JTEdge
Constructor.
JunctionTree() - Constructor for class javaslam.tjt.JunctionTree
Default constructor.

K

k - Variable in class javaslam.filter.Linearization
The dimension of the output vector.
KalmanFilter - class javaslam.filter.KalmanFilter.
A Kalman filter.
KalmanFilter(Gaussian) - Constructor for class javaslam.filter.KalmanFilter
Constructor.
KalmanSLAMFilter - class javaslam.slam.KalmanSLAMFilter.
A Kalman filter for the Simultaneous Localization and Mapping (SLAM) problem.
KalmanSLAMFilter(double[], double[][]) - Constructor for class javaslam.slam.KalmanSLAMFilter
Constructor.
kf - Variable in class javaslam.slam.KalmanSLAMFilter
The underlying Kalman filter.
kl(Gaussian) - Method in class javaslam.prob.Gaussian
Computes the relative entropy (Kullback-Liebler divergence) from this Gaussian to the supplied Gaussian.

L

label - Variable in class javaslam.prob.Variable
The label for this variable.
LANDMARK_DIM - Static variable in class javaslam.slam.ExampleModel
The dimension of each landmark's state.
landmarkMeasurementModel - Variable in class javaslam.slam.ExampleModel
The landmark measurement model.
landmarkNoiseModel - Variable in class javaslam.slam.ExampleModel
A distribution over the noise variables of the landmark measurement model.
largestCluster() - Method in class javaslam.tjt.ThinJunctionTree
Returns the cluster with largest size in the junction tree.
lastIndexOf(Object) - Method in class javaslam.util.ListSet
Returns the index in this set of the specified element, or -1 if this set does not contain this element.
LGSLAMFilter - class javaslam.slam.LGSLAMFilter.
A linear-Gaussian filter for the Simultaneous Localization and Mapping (SLAM) problem.
LGSLAMFilter(int) - Constructor for class javaslam.slam.LGSLAMFilter
Constructor.
LGSLAMFilterCanvas - class javaslam.slam.LGSLAMFilterCanvas.
 
LGSLAMFilterCanvas(LGSLAMFilter) - Constructor for class javaslam.slam.LGSLAMFilterCanvas
Constructor.
likelihood(double[]) - Method in class javaslam.prob.Gaussian
Computes the likelihood of a particular value under this distribution.
LinearGaussianFunction - class javaslam.filter.LinearGaussianFunction.
A vector-valued function that takes a vector input, the bottom part of which is a white noise vector.
LinearGaussianFunction(Matrix, Gaussian) - Constructor for class javaslam.filter.LinearGaussianFunction
Constructor.
linearization - Variable in class javaslam.filter.LinearizedFilter
The factory for creating linearizations.
linearization - Variable in class javaslam.slam.LinearizedSLAMFilter
The factory for creating linearizations.
Linearization - class javaslam.filter.Linearization.
A linear-Gaussian approximation to a nonlinear vector-valued function of Gaussian-distributed inputs.
Linearization(NoisyVectorFunction, Gaussian) - Constructor for class javaslam.filter.Linearization
Constructor.
LinearizationFactory - interface javaslam.filter.LinearizationFactory.
A factory for linearization objects.
linearize(NoisyVectorFunction, Gaussian) - Method in interface javaslam.filter.LinearizationFactory
Creates a new linearization.
LinearizedFilter - class javaslam.filter.LinearizedFilter.
A filter for nonlinear systems that uses local linearizations of the dynamics and measurement models so that a linear-Gaussian filter can be used to maintain an approximate Gaussian belief state.
LinearizedFilter(Filter, LinearizationFactory) - Constructor for class javaslam.filter.LinearizedFilter
Constructor.
LinearizedSLAMFilter - class javaslam.slam.LinearizedSLAMFilter.
A nonlinear filter for the Simultaneous Localization and Mapping SLAM problem that uses a linear-Gaussian filter with a technique for linearizing nonlinear motion and measurement models.
LinearizedSLAMFilter(LGSLAMFilter) - Constructor for class javaslam.slam.LinearizedSLAMFilter
Constructor.
LinearizedSLAMFilter(LGSLAMFilter, LinearizationFactory) - Constructor for class javaslam.slam.LinearizedSLAMFilter
Constructor.
link(JunctionTree.Cluster, JunctionTree.Cluster) - Method in class javaslam.tjt.JunctionTree
Adds a new pair of edges between the supplied clusters.
list - Variable in class javaslam.util.ListSet
The underlying list.
listIterator() - Method in class javaslam.util.ListSet
Returns a list iterator of the elements in this set (in proper sequence).
listIterator(int) - Method in class javaslam.util.ListSet
Returns a list iterator of the elements in this list (in proper sequence), starting at the specified position in this set.
ListSet - class javaslam.util.ListSet.
A set implemented by a list, or equivalently, a list with no duplicate elements.
ListSet() - Constructor for class javaslam.util.ListSet
Constructor.
ListSet(Collection) - Constructor for class javaslam.util.ListSet
Constructor.
ListSet(Object) - Constructor for class javaslam.util.ListSet
Constructor.
ListSet(Object[]) - Constructor for class javaslam.util.ListSet
Constructor.
LM_XPOS - Static variable in class javaslam.slam.ExampleModel.LandmarkMeasurementModel
 
LM_XPOS - Static variable in class javaslam.slam.ExampleModel.InverseMeasurementModel
 
LM_YPOS - Static variable in class javaslam.slam.ExampleModel.LandmarkMeasurementModel
 
LM_YPOS - Static variable in class javaslam.slam.ExampleModel.InverseMeasurementModel
 
lm2id - Variable in class javaslam.slam.AbstractSLAMFilter
A map from Variables representing landmarks' states to Integer identifiers of the corresponding landmarks .
log() - Static method in class javaslam.util.Flops
Counts the number of floating point operations used to compute the logarithm of a number.
lu(int) - Static method in class javaslam.util.Flops
Counts the number of floating point operations used to compute the LU decomposition of an n-by-n square matrix.

M

m - Variable in class javaslam.filter.Linearization
The sum dimension of the noise vector.
main(String[]) - Static method in class javaslam.slam.LGSLAMFilterCanvas
 
marginalize(Set, boolean) - Method in class javaslam.prob.Gaussian
Marginalizes out a subset of the variables in this Gaussian.
marginalizeOut(Set) - Method in class javaslam.prob.Gaussian
Marginalizes a set of variables out of this Gaussian (in place).
marginalizeOut(Set) - Method in class javaslam.tjt.JunctionTree.Cluster
Marginalizes out a set of variables from this cluster.
marginalizeOut(Set) - Method in interface javaslam.filter.Filter
Marginalizes a set of variables out of the belief state.
marginalizeOut(Set) - Method in class javaslam.filter.InformationFilter
Marginalizes a set of variables out of the belief state.
marginalizeOut(Set) - Method in class javaslam.filter.JTFilter
Marginalizes a set of variables out of the belief state.
marginalizeOut(Set) - Method in class javaslam.filter.KalmanFilter
Marginalizes a set of variables out of the belief state.
marginalizeOut(Variable) - Method in class javaslam.tjt.JunctionTree
Marginalizes a variable out of this junction tree.
measurement(int, double[], double[][], double[][], double[][], double[]) - Method in class javaslam.slam.InformationSLAMFilter
Performs a linear-Gaussian landmark measurement update.
measurement(int, double[], double[][], double[][], double[][], double[]) - Method in class javaslam.slam.KalmanSLAMFilter
Performs a linear-Gaussian landmark measurement update.
measurement(int, double[], double[][], double[][], double[][], double[]) - Method in class javaslam.slam.LGSLAMFilter
Performs a linear-Gaussian landmark measurement update.
measurement(int, double[], double[][], double[][], double[][], double[]) - Method in class javaslam.slam.TJTSLAMFilter
Performs a linear-Gaussian landmark measurement update.
measurement(ListSet, double[], double[][], double[][], double[]) - Method in interface javaslam.filter.Filter
Performs a linear-Gaussian measurement update.
measurement(ListSet, double[], double[][], double[][], double[]) - Method in class javaslam.filter.InformationFilter
Performs a linear-Gaussian measurement update.
measurement(ListSet, double[], double[][], double[][], double[]) - Method in class javaslam.filter.JTFilter
Performs a linear-Gaussian measurement update.
measurement(ListSet, double[], double[][], double[][], double[]) - Method in class javaslam.filter.KalmanFilter
Performs a linear-Gaussian measurement update.
measurement(ListSet, NoisyVectorFunction, double[]) - Method in class javaslam.filter.LinearizedFilter
Performs an approximate nonlinear measurement update.
measurement(ListSet, NoisyVectorFunction, double[]) - Method in interface javaslam.filter.NonlinearFilter
Performs an approximate nonlinear measurement update.
measurement(NoisyVectorFunction, NoisyVectorFunction, int, double[]) - Method in class javaslam.slam.LinearizedSLAMFilter
Performs a landmark measurement update assuming a known data association.
measurement(NoisyVectorFunction, NoisyVectorFunction, int, double[]) - Method in interface javaslam.slam.NonlinearSLAMFilter
Performs a landmark measurement update assuming a known data association.
merge(JunctionTree.JTEdge) - Method in class javaslam.tjt.JunctionTree
Merges the two clusters that are incident to the supplied edge.
mergeClustersWith(Variable) - Method in class javaslam.tjt.JunctionTree
Merges all clusters containing a particular variable.
Model - interface javaslam.slam.Model.
Represents a SLAM model.
motion(double[], double[][], double[][]) - Method in class javaslam.slam.InformationSLAMFilter
Performs a linear-Gaussian motion update.
motion(double[], double[][], double[][]) - Method in class javaslam.slam.KalmanSLAMFilter
Performs a linear-Gaussian motion update.
motion(double[], double[][], double[][]) - Method in class javaslam.slam.LGSLAMFilter
Performs a linear-Gaussian motion update.
motion(double[], double[][], double[][]) - Method in class javaslam.slam.TJTSLAMFilter
Performs a linear-Gaussian motion update.
motion(NoisyVectorFunction) - Method in class javaslam.slam.LinearizedSLAMFilter
Performs a motion update.
motion(NoisyVectorFunction) - Method in interface javaslam.slam.NonlinearSLAMFilter
Performs a motion update.
motionNoiseModel - Variable in class javaslam.slam.ExampleModel
A distribution over the noise variables of the motion model.
mP - Variable in class javaslam.prob.Gaussian
The positive definite matrix parameter; this is S if Gaussian.isMoment is true and L otherwise.
mult(int, int, int) - Static method in class javaslam.util.Flops
Counts the number of floating point operations used to compute the product of two matrices A and B.
mutualInformation(Set, Set, Set) - Method in class javaslam.prob.Gaussian
Computes the (conditional) mutual information I(x;y - x|z) in nats (natural logarithmic units).

N

n - Variable in class javaslam.filter.Linearization
The sum dimension of the input vector.
newLeaf(JunctionTree.Cluster) - Method in class javaslam.tjt.JunctionTree
Creates an empty cluster and attaches it as a leaf off of the supplied cluster.
newLeaf(JunctionTree.Cluster) - Method in class javaslam.tjt.ThinJunctionTree
Creates an empty cluster and attaches it as a leaf off of the supplied cluster.
next() - Method in class javaslam.util.PriorityQueue.QueueItemIterator
Returns the next item in this iteration.
next() - Method in class javaslam.tjt.graph.Traversal
Returns the next Node in the iteration.
Node - class javaslam.tjt.graph.Node.
A node in a graph.
Node() - Constructor for class javaslam.tjt.graph.Node
Default constructor.
NodeFilter - class javaslam.tjt.graph.NodeFilter.
A predicate over graph nodes.
NodeFilter(Object) - Constructor for class javaslam.tjt.graph.NodeFilter
Constructor.
NoisyVectorFunction - interface javaslam.filter.NoisyVectorFunction.
A vector-valued function that takes a vector input, the bottom part of which is a white noise vector.
NonlinearFilter - interface javaslam.filter.NonlinearFilter.
A filter for nonlinear systems that maintains an approximate Gaussian belief state.
NonlinearSLAMFilter - interface javaslam.slam.NonlinearSLAMFilter.
An interface implemented by classes that implement nonlinear filters for the Simultaneous Localization and Mapping (SLAM) problem.

O

ODO_RVEL - Static variable in class javaslam.slam.ExampleModel.OdometryModel
 
ODO_TVEL - Static variable in class javaslam.slam.ExampleModel.OdometryModel
 
odometry(double[], double[][], double[][], double[]) - Method in class javaslam.slam.InformationSLAMFilter
Performs a linear-Gaussian odometry update.
odometry(double[], double[][], double[][], double[]) - Method in class javaslam.slam.KalmanSLAMFilter
Performs a linear-Gaussian odometry update.
odometry(double[], double[][], double[][], double[]) - Method in class javaslam.slam.LGSLAMFilter
Performs a linear-Gaussian odometry update.
odometry(double[], double[][], double[][], double[]) - Method in class javaslam.slam.TJTSLAMFilter
Performs a linear-Gaussian odometry update.
odometry(NoisyVectorFunction, double[]) - Method in class javaslam.slam.LinearizedSLAMFilter
Performs an odometry update.
odometry(NoisyVectorFunction, double[]) - Method in interface javaslam.slam.NonlinearSLAMFilter
Performs an odometry update.
odometryModel - Variable in class javaslam.slam.ExampleModel
The odometry model.
odometryNoiseModel - Variable in class javaslam.slam.ExampleModel
A distribution over the noise variables of the odometry model.
OUTPUT_DIM - Static variable in class javaslam.slam.ExampleModel.MotionModel
The output dimension of the motion model.
OUTPUT_DIM - Static variable in class javaslam.slam.ExampleModel.OdometryModel
The output dimension of the odometry model.
OUTPUT_DIM - Static variable in class javaslam.slam.ExampleModel.LandmarkMeasurementModel
The output dimension of the landmark measurement model.
OUTPUT_DIM - Static variable in class javaslam.slam.ExampleModel.InverseMeasurementModel
The output dimension of the model.
overlap - Variable in class javaslam.slam.TJTSLAMFilter
When the active cluster is cloned to admit a new landmark variable, this is the size of its separator.

P

p - Variable in class javaslam.tjt.JunctionTree.Cluster
The potential of this cluster.
p - Variable in class javaslam.filter.InformationFilter
The canonical potential representing the belief state.
p - Variable in class javaslam.filter.KalmanFilter
The moment potential representing the belief state.
paint(Graphics) - Method in class javaslam.slam.LGSLAMFilterCanvas
 
paint(Graphics2D, double) - Method in class javaslam.prob.Gaussian
Paints a 2D confidence ellipse for the first two dimensions of this Gaussian distribution.
parents() - Method in class javaslam.tjt.JunctionTree
Returns a directed representation of the junction tree.
passFlow() - Method in class javaslam.tjt.JunctionTree.JTEdge
Passes a flow along this edge.
passFlows() - Method in class javaslam.tjt.JunctionTree
Restores consistency; all clusters into new potentials have been multiplied that have not yet distributed their evidence do so.
path() - Method in class javaslam.tjt.graph.Traversal
Returns a list of Edges that were traversed in order to reach the Node most recently returned by next().
peek() - Method in class javaslam.util.PriorityQueue
Returns the item with the highest priority without removing it from the queue.
pf - Variable in class javaslam.slam.InformationSLAMFilter
The thin junction tree used to represent the filtered belief state.
priority - Variable in class javaslam.util.PriorityQueue.QueueElement
The priority of the item.
PriorityQueue - class javaslam.util.PriorityQueue.
A priority queue.
PriorityQueue.QueueElement - class javaslam.util.PriorityQueue.QueueElement.
An item in a priority queue.
PriorityQueue.QueueElement(Object, Comparable) - Constructor for class javaslam.util.PriorityQueue.QueueElement
Constructor.
PriorityQueue.QueueItemIterator - class javaslam.util.PriorityQueue.QueueItemIterator.
An iterator over queue items.
PriorityQueue.QueueItemIterator(Iterator) - Constructor for class javaslam.util.PriorityQueue.QueueItemIterator
Constructor.
PriorityQueue() - Constructor for class javaslam.util.PriorityQueue
Constructor.

Q

q - Variable in class javaslam.filter.LinearGaussianFunction
The noise model.
q - Variable in class javaslam.filter.Linearization
A Gaussian distribution (in the moment parameterization) that approximates p(x, v, y).
queue - Variable in class javaslam.tjt.graph.BreadthFirstTraversal
A queue of nodes to be visited in this search.
queue - Variable in class javaslam.tjt.graph.DepthFirstTraversal
A queue of nodes to be visited in this search.

R

rand() - Static method in class javaslam.util.Flops
Counts the number of floating point operations used to compute a random double-precision floating point number between 0.0 and 1.0 using a simple linear-congruential formula xi + 1 = a xi + b (mod c).
randn() - Static method in class javaslam.util.Flops
Counts the number of floating point operations used to compute a sample from the standard normal using the Box-Muller method.
randnorm(int, int) - Static method in class javaslam.util.Flops
Counts the number of floating point operations used to compute n samples from a k-dimensional multivariate Gaussian distribution represented using a covariance matrix.
range - Variable in class javaslam.slam.ExampleModel.InverseMeasurementModel
The noisy range measurement.
RANGE_ABS_NOISE - Static variable in class javaslam.slam.ExampleModel.LandmarkMeasurementModel
 
RANGE_ABS_NOISE - Static variable in class javaslam.slam.ExampleModel.InverseMeasurementModel
 
RANGE_REL_NOISE - Static variable in class javaslam.slam.ExampleModel.LandmarkMeasurementModel
 
RANGE_REL_NOISE - Static variable in class javaslam.slam.ExampleModel.InverseMeasurementModel
 
reduce(JunctionTree.Cluster, Variable) - Method in class javaslam.tjt.JunctionTree
Reduces the supplied cluster so that it no longer contains the supplied variable.
reduce(JunctionTree.Cluster, Variable) - Method in class javaslam.tjt.ThinJunctionTree
Reduces the supplied cluster so that it no longer contains the supplied variable.
regularize(Matrix, double) - Static method in class javaslam.util.TJTF
Regularizes a covariance matrix so that its condition number is no greater than a specified value.
remove() - Method in class javaslam.util.PriorityQueue.QueueItemIterator
This operation is unsupported.
remove(int) - Method in class javaslam.util.ListSet
Removes the element at the specified position in this set (optional operation).
remove(JunctionTree.Cluster) - Method in class javaslam.tjt.JunctionTree
Removes a cluster from this junction tree.
remove(JunctionTree.Cluster) - Method in class javaslam.tjt.ThinJunctionTree
Removes a cluster from this junction tree.
remove(Object) - Method in class javaslam.util.ListSet
Removes the the specified element from this set (optional operation).
remove(Object) - Method in class javaslam.util.PriorityQueue
Removes a particular item from the queue, if it exists.
remove(Variable) - Method in class javaslam.tjt.JunctionTree
Removes a variable from this junction tree.
removeAll(Collection) - Method in class javaslam.util.ListSet
Removes from this set all the elements that are contained in the specified collection (optional operation).
removeEdge(Edge) - Method in class javaslam.tjt.graph.Node
Removes the supplied edge from this node to the supplied node (if such an edge exists).
rename(Variable, Variable) - Method in class javaslam.prob.Gaussian
Renames a variable in this Gaussian.
rename(Variable, Variable) - Method in class javaslam.tjt.JunctionTree
Renames a variable in this junction tree.
rename(Variable, Variable) - Method in class javaslam.tjt.JunctionTree.Cluster
Renames a variable in this cluster.
rename(Variable, Variable) - Method in class javaslam.tjt.JunctionTree.JTEdge
Renames a variable in the separator of this edge.
reparameterize(boolean) - Method in class javaslam.prob.Gaussian
Reparameterizes this Gaussian; i.e., the parameterization will be switched from the canonical to the moment parameterization, or vice-versa.
reprioritize(Object, Comparable) - Method in class javaslam.util.PriorityQueue
Updates the priority of an item already in the queue.
reset() - Static method in class javaslam.util.Flops
A method that resets the flop count.
retainAll(Collection) - Method in class javaslam.util.ListSet
Retains only the elements in this set that are contained in the specified collection (optional operation).
ROBOT_DIM - Static variable in class javaslam.slam.ExampleModel
The dimension of the robot state.
RVEL - Static variable in class javaslam.slam.ExampleModel.MotionModel
 
RVEL - Static variable in class javaslam.slam.ExampleModel.OdometryModel
 
RVEL - Static variable in class javaslam.slam.ExampleModel.LandmarkMeasurementModel
 
RVEL - Static variable in class javaslam.slam.ExampleModel.InverseMeasurementModel
 
RVEL_ABS_NOISE - Static variable in class javaslam.slam.ExampleModel.MotionModel
 
RVEL_ABS_NOISE - Static variable in class javaslam.slam.ExampleModel.OdometryModel
 
RVEL_REL_NOISE - Static variable in class javaslam.slam.ExampleModel.MotionModel
 
RVEL_REL_NOISE - Static variable in class javaslam.slam.ExampleModel.OdometryModel
 
rVelCtrl - Variable in class javaslam.slam.ExampleModel.MotionModel
The current rotational velocity control (in radians per second).

S

Sample - class javaslam.prob.Sample.
A utility class containing methods for sampling from various probability distributions.
Sample() - Constructor for class javaslam.prob.Sample
 
sample(int, Random) - Method in class javaslam.prob.Gaussian
Samples from this Gaussian distribution.
satisfies(Node) - Method in class javaslam.tjt.graph.NodeFilter
Returns true if the supplied node satisfies this predicate.
say(String) - Static method in class javaslam.util.TJTF
A method that reports a message.
set(Gaussian) - Method in class javaslam.prob.Gaussian
Sets this Gaussian equal to the supplied Gaussian.
set(int, Object) - Method in class javaslam.util.ListSet
Replaces the element at the specified position in this set with the specified element (optional operation).
setBlather(boolean) - Static method in class javaslam.util.TJTF
Determines whether mundane status messages should be displayed.
setDebug(boolean) - Static method in class javaslam.util.TJTF
Determines whether special (expensive) checks should be made to ensure that everything is operating correctly.
setDoubling(boolean) - Method in class javaslam.prob.Gaussian
Controls the memory allocation behavior of this Gaussian.
setEta(ListSet, Matrix) - Method in class javaslam.prob.Gaussian
Sets a subvector of h.
setLambda(ListSet, ListSet, Matrix) - Method in class javaslam.prob.Gaussian
Sets a submatrix of L.
setMu(ListSet, Matrix) - Method in class javaslam.prob.Gaussian
Sets a subvector of m.
setSigma(ListSet, ListSet, Matrix) - Method in class javaslam.prob.Gaussian
Sets a submatrix of S.
setSignificance(double) - Method in class javaslam.tjt.JunctionTree
Sets a threshold used in adaptive message passing.
setVerbose(boolean) - Static method in class javaslam.util.TJTF
Determines whether routine status messages should be displayed.
significance - Variable in class javaslam.tjt.JunctionTree
A threshold used in adaptive message passing.
size() - Method in class javaslam.util.ListSet
Returns the number of elements in this set.
size() - Method in class javaslam.util.PriorityQueue
Returns the number of items in this queue.
size() - Method in class javaslam.tjt.graph.Traversal
Returns the number of nodes traversed thus far.
SLAMFilter - interface javaslam.slam.SLAMFilter.
An interface implemented by filters for the Simultaneous Localization and Mapping (SLAM) problem.
solve(int, int, int, boolean) - Static method in class javaslam.util.Flops
Counts the number of floating point operations used to solve for X in the matrix equation AX = B where A is possibly symmetric positive definite.
sqrt() - Static method in class javaslam.util.Flops
Counts the number of floating point operations used to compute the square root of a number.
subList(int, int) - Method in class javaslam.util.ListSet
Returns a view of the portion of this set between the specified fromIndex, inclusive, and toIndex, exclusive.
swingEdge(Edge, Node) - Method in class javaslam.tjt.graph.Node
Changes an edge emanating from this node so that it emanates from the supplied node.
swingEdgesTo(Node) - Method in class javaslam.tjt.graph.Node
Changes the origin of all (directed and undirected) edges emanating from this node to the supplied node.
symmetrize(Matrix) - Static method in class javaslam.util.TJTF
Transforms an asymmetric matrix M into a symmetric matrix by setting it to (M + MT)/2.

T

thin(int) - Method in class javaslam.tjt.ThinJunctionTree
Thins the junction tree via a sequence of variable contractions so that no clusters have a size greater than limit.
thin(JunctionTree.Cluster, int, Variable) - Method in class javaslam.tjt.ThinJunctionTree
Removes variables from the supplied cluster so as to ensure its size is no greater than limit.
ThinJunctionTree - class javaslam.tjt.ThinJunctionTree.
A thin (approximate) junction tree for a Gaussian graphical model.
ThinJunctionTree.Contraction - class javaslam.tjt.ThinJunctionTree.Contraction.
Represents a variable contraction of a variable v along an edge e = Ci -> Cj.
ThinJunctionTree.Contraction(JunctionTree.JTEdge, Variable) - Constructor for class javaslam.tjt.ThinJunctionTree.Contraction
Constructor.
ThinJunctionTree.Contraction(JunctionTree.JTEdge, Variable, boolean) - Constructor for class javaslam.tjt.ThinJunctionTree.Contraction
Constructor.
ThinJunctionTree.Contraction(JunctionTree.JTEdge, Variable, boolean, double) - Constructor for class javaslam.tjt.ThinJunctionTree.Contraction
Constructor.
ThinJunctionTree() - Constructor for class javaslam.tjt.ThinJunctionTree
Default constructor.
time(ListSet, double[], double[][], double[][]) - Method in interface javaslam.filter.Filter
Performs a linear-Gaussian time update.
time(ListSet, double[], double[][], double[][]) - Method in class javaslam.filter.InformationFilter
Performs a linear-Gaussian time update.
time(ListSet, double[], double[][], double[][]) - Method in class javaslam.filter.JTFilter
Performs a linear-Gaussian time update.
time(ListSet, double[], double[][], double[][]) - Method in class javaslam.filter.KalmanFilter
Performs a linear-Gaussian time update.
time(ListSet, NoisyVectorFunction) - Method in class javaslam.filter.LinearizedFilter
Performs an approximate nonlinear time update.
time(ListSet, NoisyVectorFunction) - Method in interface javaslam.filter.NonlinearFilter
Performs an approximate nonlinear time update.
times(Gaussian) - Method in class javaslam.tjt.JunctionTree
Multiplies a new potential into the junction tree and restores validity (but not consistency).
times(Gaussian, boolean) - Method in class javaslam.prob.Gaussian
Multiplies two Gaussians.
times(Gaussian, JunctionTree.Cluster) - Method in class javaslam.tjt.JunctionTree
Multiplies a new potential into a particular cluster of this junction tree and restores validity (but not consistency).
TJTF - class javaslam.util.TJTF.
A class containing package-level utilities.
TJTF() - Constructor for class javaslam.util.TJTF
 
TJTSLAMFilter - class javaslam.slam.TJTSLAMFilter.
A thin junction tree filter for the Simultaneous Localization and Mapping (SLAM) problem.
TJTSLAMFilter(int, int, double[], double[][]) - Constructor for class javaslam.slam.TJTSLAMFilter
Constructor.
to - Variable in class javaslam.tjt.graph.Edge
The end of this edge.
toArray() - Method in class javaslam.util.ListSet
Returns an array containing all of the elements in this set in proper sequence.
toArray(Object[]) - Method in class javaslam.util.ListSet
Returns an array containing all of the elements in this set in proper sequence; the runtime type of the returned array is that of the specified array.
toString() - Method in class javaslam.prob.Gaussian
Creates a simple String representation of this Gaussian that prints out its parameters using Matlab notation.
toString() - Method in class javaslam.prob.Variable
Returns the string representation of this variable's label.
toString() - Method in class javaslam.util.PriorityQueue
Returns a string representation of this priority queue.
toString() - Method in class javaslam.util.PriorityQueue.QueueElement
Returns a string representation of this queue element.
toString() - Method in class javaslam.tjt.JunctionTree
Returns a String representation of this junction tree.
toString() - Method in class javaslam.tjt.JunctionTree.Cluster
Returns a string representation of this cluster.
toString() - Method in class javaslam.tjt.ThinJunctionTree
Returns a String representation of this thin junction tree.
toString() - Method in class javaslam.tjt.graph.Edge
Returns a string representation of this edge.
toString() - Method in class javaslam.filter.JTFilter
Returns a string representation of this filter.
toString(Matrix) - Static method in class javaslam.util.TJTF
Creates a Matlab string representation of a matrix.
trace(int) - Static method in class javaslam.util.Flops
Counts the number of floating point operations used to compute the trace of a square matrix A.
Traversal - class javaslam.tjt.graph.Traversal.
An iterator that traverses the nodes of a graph.
Traversal(Node) - Constructor for class javaslam.tjt.graph.Traversal
Constructor.
TVEL - Static variable in class javaslam.slam.ExampleModel.MotionModel
 
TVEL - Static variable in class javaslam.slam.ExampleModel.OdometryModel
 
TVEL - Static variable in class javaslam.slam.ExampleModel.LandmarkMeasurementModel
 
TVEL - Static variable in class javaslam.slam.ExampleModel.InverseMeasurementModel
 
TVEL_ABS_NOISE - Static variable in class javaslam.slam.ExampleModel.MotionModel
 
TVEL_ABS_NOISE - Static variable in class javaslam.slam.ExampleModel.OdometryModel
 
TVEL_REL_NOISE - Static variable in class javaslam.slam.ExampleModel.MotionModel
 
TVEL_REL_NOISE - Static variable in class javaslam.slam.ExampleModel.OdometryModel
 
tVelCtrl - Variable in class javaslam.slam.ExampleModel.MotionModel
The current translational velocity control (in meters per second).

U

UnscentedTransformation - class javaslam.filter.UnscentedTransformation.
The Unscented Transformation for linearizing functions with Gaussian-distributed inputs.
UnscentedTransformation(NoisyVectorFunction, Gaussian) - Constructor for class javaslam.filter.UnscentedTransformation
Constructor.
UnscentedTransformation(NoisyVectorFunction, Gaussian, double, double, double) - Constructor for class javaslam.filter.UnscentedTransformation
Constructor.
updateClusterSize(JunctionTree.Cluster) - Method in class javaslam.tjt.ThinJunctionTree
Updates the clustersBySize index of cluster sizes.
updated - Variable in class javaslam.tjt.JunctionTree
The set of clusters that have been updated with new evidence but have not yet distributed their evidence (due to lazy or adaptive message passing).

V

v - Variable in class javaslam.tjt.ThinJunctionTree.Contraction
The variable to contracted.
Variable - class javaslam.prob.Variable.
A Gaussian vector variable.
Variable(int) - Constructor for class javaslam.prob.Variable
Constructor.
Variable(Object, int) - Constructor for class javaslam.prob.Variable
Default constructor.
variables - Variable in class javaslam.prob.Gaussian
An unmodifiable ordered set whose elements are the Variables bound by this Gaussian.
variables - Variable in class javaslam.tjt.JunctionTree
The Variables present in this junction tree.
vars - Variable in class javaslam.prob.Gaussian
An ordered set whose elements are the Variables bound by this Gaussian.
varsToStarts - Variable in class javaslam.prob.Gaussian
A map whose keys are the Variables bound by this Gaussian and whose values are Integers giving the starting index of the corresponding subvectors of Gaussian.vP and subblocks of Gaussian.mP.
varToClusters - Variable in class javaslam.tjt.JunctionTree
Maps each Variable to the Set of Clusters containing it.
VectorFunction - interface javaslam.filter.VectorFunction.
A vector-valued function of a vector input.
verbose - Static variable in class javaslam.util.TJTF
A flag indicating whether routine status messages should be displayed.
vP - Variable in class javaslam.prob.Gaussian
The vector parameter; this is m if Gaussian.isMoment is true and h otherwise.
vSet - Variable in class javaslam.filter.Linearization
A list of random variables representing the noise inputs of the function.

W

width - Variable in class javaslam.slam.TJTSLAMFilter
The cluster size limit of the thin junction tree.
width() - Method in class javaslam.tjt.ThinJunctionTree
Computes the width of this junction tree.

X

x - Variable in class javaslam.slam.AbstractSLAMFilter
The variable x, which represents the state of the robot.
XPOS - Static variable in class javaslam.slam.ExampleModel.MotionModel
 
XPOS - Static variable in class javaslam.slam.ExampleModel.OdometryModel
 
XPOS - Static variable in class javaslam.slam.ExampleModel.LandmarkMeasurementModel
 
XPOS - Static variable in class javaslam.slam.ExampleModel.InverseMeasurementModel
 
xSet - Variable in class javaslam.filter.Linearization
A list of random variables representing the inputs of the function.

Y

y - Variable in class javaslam.filter.Linearization
A random variable representing the output of the function.
YPOS - Static variable in class javaslam.slam.ExampleModel.MotionModel
 
YPOS - Static variable in class javaslam.slam.ExampleModel.OdometryModel
 
YPOS - Static variable in class javaslam.slam.ExampleModel.LandmarkMeasurementModel
 
YPOS - Static variable in class javaslam.slam.ExampleModel.InverseMeasurementModel
 
ySet - Variable in class javaslam.filter.Linearization
A list set containing only Linearization.y (for convenience).

A B C D E F G H I J K L M N O P Q R S T U V W X Y