Namespaces | |
BFL | |
MatrixWrapper | |
Classes | |
class | AnalyticConditionalGaussian |
Abstract Class representing all FULL Analytical Conditional gaussians. More... | |
class | AnalyticConditionalGaussianAdditiveNoise |
Abstract Class representing all full Analytical Conditional gaussians with Additive Gaussian Noise. More... | |
class | AnalyticMeasurementModelGaussianUncertainty |
class | AnalyticSystemModelGaussianUncertainty |
Class for analytic system models with additive Gauss. uncertainty. More... | |
class | ASIRFilter |
ASIR: Auxiliary Particle Filter. More... | |
class | BackwardFilter |
Virtual Baseclass representing all bayesian backward filters. More... | |
class | bflToolkitPlugin |
class | BootstrapFilter |
Particular particle filter : Proposal PDF = SystemPDF. More... | |
class | ConditionalGaussian |
Abstract Class representing all Conditional gaussians. More... | |
class | ConditionalGaussianAdditiveNoise |
Abstract Class representing all Conditional Gaussians with additive gaussian noise. More... | |
class | ConditionalPdf |
Abstract Class representing conditional Pdfs P(x | ...) More... | |
class | ConditionalUniformMeasPdf1d |
class | DiscreteConditionalPdf |
Abstract Class representing all FULLY Discrete Conditional PDF's. More... | |
class | DiscretePdf |
Class representing a PDF on a discrete variable. More... | |
class | DiscreteSystemModel |
Class for discrete System Models. More... | |
class | EKFProposalDensity |
Proposal Density for non-linear systems with additive Gaussian Noise (using a EKF Filter) More... | |
class | EKFTest |
class | EKParticleFilter |
Particle filter using EKF for proposal step. More... | |
class | ExtendedKalmanFilter |
class | Filter |
Abstract class representing an interface for Bayesian Filters. More... | |
class | FilterProposalDensity |
Proposal Density for non-linear systems with additive Gaussian Noise (using a (analytic) Filter) More... | |
class | Gaussian |
Class representing Gaussian (or normal density) More... | |
struct | get_size |
class | HistogramFilter |
Class representing the histogram filter. More... | |
class | InnovationCheck |
Class implementing an innovationCheck used in IEKF. More... | |
class | IteratedExtendedKalmanFilter |
class | KalmanFilter |
Class representing the family of all Kalman Filters (EKF, IEKF, ...) More... | |
class | LinearAnalyticConditionalGaussian |
Linear Conditional Gaussian. More... | |
class | LinearAnalyticMeasurementModelGaussianUncertainty |
Class for linear analytic measurementmodels with additive gaussian noise. More... | |
class | LinearAnalyticMeasurementModelGaussianUncertainty_Implicit |
Class for linear analytic measurementmodels with additive gaussian noise. More... | |
class | LinearAnalyticSystemModelGaussianUncertainty |
Class for linear analytic systemmodels with additive gaussian noise. More... | |
struct | matrix_i_j_constructor |
struct | matrix_index |
struct | MatrixAssignChecker |
struct | MatrixIndexChecker |
struct | MatrixTypeInfo |
class | MCPdf |
Monte Carlo Pdf: Sample based implementation of Pdf. More... | |
class | MeasurementModel |
class | Mixture |
Class representing a mixture of PDFs, the mixture can contain different. More... | |
class | MixtureBootstrapFilter |
Particular mixture particle filter : Proposal PDF = SystemPDF. More... | |
class | MixtureParticleFilter |
Virtual Class representing all Mixture particle filters. More... | |
class | MobileRobot |
This is a class simulating a mobile robot. More... | |
class | NonLinearAnalyticConditionalGaussian_Ginac |
Conditional Gaussian for an analytic nonlinear system using Ginac: More... | |
class | NonLinearAnalyticConditionalGaussianMobile |
Non Linear Conditional Gaussian. More... | |
class | NonLinearAnalyticMeasurementModelGaussianUncertainty_Ginac |
Class for nonlinear analytic measurementmodels with additive gaussian noise. More... | |
class | NonLinearAnalyticSystemModelGaussianUncertainty_Ginac |
Class for nonlinear analytic systemmodels with additive gaussian noise. More... | |
class | NonlinearMeasurementPdf |
Non Linear Conditional Gaussian. More... | |
class | NonlinearSystemPdf |
Non Linear Conditional Gaussian. More... | |
class | NonminimalKalmanFilter |
class | OptimalImportanceDensity |
Optimal importance density for Nonlinear Gaussian SS Models. More... | |
class | Optimalimportancefilter |
Particular particle filter: Proposal PDF = Optimal Importance function. More... | |
class | ParticleFilter |
Virtual Class representing all particle filters. More... | |
class | ParticleSmoother |
Class representing a particle backward filter. More... | |
class | |
Class PDF: Virtual Base class representing Probability Density Functions. More... | |
class | Probability |
Class representing a probability (a double between 0 and 1) More... | |
struct | Probability_ctor |
struct | ProbabilityTypeInfo |
class | RauchTungStriebel |
Class representing all Rauch-Tung-Striebel backward filters. More... | |
struct | rget_size |
struct | rvector_index |
struct | rvector_index_constructor |
struct | RVectorTypeInfo |
class | Sample |
struct | Sample_ctor |
struct | SampleTypeInfo |
class | SRIteratedExtendedKalmanFilter |
struct | symmetricMatrix_index_constructor |
struct | SymmetricMatrixTypeInfo |
class | SystemModel |
class | Uniform |
Class representing uniform density. More... | |
struct | vector_index |
struct | vector_index_constructor |
struct | VectorAssignChecker |
struct | VectorTypeInfo |
class | WeightedSample |
struct | WeightedSample_ctor |
struct | WeightedSampleTypeInfo |
Functions | |
template<class T > | |
bool | composeProperty (const PropertyBag &bag, Sample< T > &sample) |
template<class T > | |
bool | composeProperty (const PropertyBag &bag, WeightedSample< T > &weightedSample) |
template<class T > | |
void | decomposeProperty (const Sample< T > &sample, PropertyBag &targetbag) |
template<class T > | |
void | decomposeProperty (const WeightedSample< T > &weightedSample, PropertyBag &targetbag) |
std::ostream & | operator<< (std::ostream &os, const Uniform &u) |
ostream & | operator<< (ostream &stream, Probability &prob) |
std::ostream & | operator<< (std::ostream &os, const Gaussian &g) |
std::ostream & | operator<< (std::ostream &os, NonLinearAnalyticConditionalGaussian_Ginac &p) |
template<typename S > | |
ostream & | operator<< (ostream &stream, WeightedSample< S > &mws) |
template<typename S > | |
ostream & | operator<< (ostream &stream, Sample< S > &my_sample) |
istream & | operator>> (istream &stream, Probability &prob) |
template<typename S > | |
istream & | operator>> (istream &stream, Sample< S > &my_sample) |
double | rnorm (const double &mu, const double &sigma) |
double | runif () |
double | runif (const double &min, const double &max) |
Variables | |
bflToolkitPlugin | bflToolkit |
bool BFL::composeProperty | ( | const PropertyBag & | bag, |
Sample< T > & | sample | ||
) |
A composeProperty method for composing a property of a vector<T> The dimension of the vector must be less than 100.
Definition at line 95 of file SampleComposition.hpp.
bool BFL::composeProperty | ( | const PropertyBag & | bag, |
WeightedSample< T > & | weightedSample | ||
) |
A composeProperty method for composing a property of a vector<T> The dimension of the vector must be less than 100.
Definition at line 224 of file SampleComposition.hpp.
void BFL::decomposeProperty | ( | const Sample< T > & | sample, |
PropertyBag & | targetbag | ||
) |
A decomposePropertyBag method for decomposing a sample<T> into a PropertyBag with Property<T>'s.
Definition at line 62 of file SampleComposition.hpp.
void BFL::decomposeProperty | ( | const WeightedSample< T > & | weightedSample, |
PropertyBag & | targetbag | ||
) |
A decomposePropertyBag method for decomposing a sample<T> into a PropertyBag with Property<T>'s.
Definition at line 188 of file SampleComposition.hpp.
std::ostream& BFL::operator<< | ( | std::ostream & | os, |
const Uniform & | u | ||
) |
Definition at line 54 of file uniform.cpp.
ostream& BFL::operator<< | ( | ostream & | stream, |
Probability & | prob | ||
) |
Definition at line 62 of file bfl_toolkit.cpp.
std::ostream& BFL::operator<< | ( | std::ostream & | os, |
const Gaussian & | g | ||
) |
Definition at line 62 of file gaussian.cpp.
std::ostream& BFL::operator<< | ( | std::ostream & | os, |
NonLinearAnalyticConditionalGaussian_Ginac & | p | ||
) |
Definition at line 116 of file nonlinearanalyticconditionalgaussian_ginac.cpp.
ostream& BFL::operator<< | ( | ostream & | stream, |
WeightedSample< S > & | mws | ||
) |
stream | the stream to be returned |
mws | the weighted sample to be printed |
Definition at line 116 of file weightedsample.h.
ostream& BFL::operator<< | ( | ostream & | stream, |
Sample< S > & | my_sample | ||
) |
istream& BFL::operator>> | ( | istream & | stream, |
Probability & | prob | ||
) |
Definition at line 68 of file bfl_toolkit.cpp.
istream& BFL::operator>> | ( | istream & | stream, |
Sample< S > & | my_sample | ||
) |
double BFL::rnorm | ( | const double & | mu, |
const double & | sigma | ||
) |
double BFL::runif | ( | ) |
double BFL::runif | ( | const double & | min, |
const double & | max | ||
) |
bflToolkitPlugin BFL::bflToolkit |
Definition at line 85 of file bfl_toolkit.cpp.