betweenFactorMaxMix.h
Go to the documentation of this file.
1 /*
2  * betweenFactorMaxMix.h
3  *
4  * Created on: 14.08.2012
5  * Author: niko
6  */
7 
8 #ifndef BETWEENFACTORMAXMIX_H_
9 #define BETWEENFACTORMAXMIX_H_
10 
11 #include <gtsam/linear/NoiseModel.h>
12 #include <Eigen/Eigen>
13 
14 namespace vertigo {
15 
16  template<class VALUE>
17  class BetweenFactorMaxMix : public gtsam::NoiseModelFactor2<VALUE, VALUE>
18  {
19  public:
21  BetweenFactorMaxMix(gtsam::Key key1, gtsam::Key key2, const VALUE& measured, const gtsam::SharedNoiseModel& model, const gtsam::SharedNoiseModel& model2, double w)
22  : gtsam::NoiseModelFactor2<VALUE, VALUE>(model, key1, key2), weight(w), nullHypothesisModel(model2),
23  betweenFactor(key1, key2, measured, model) { };
24 
25  gtsam::Vector evaluateError(const VALUE& p1, const VALUE& p2,
26  boost::optional<gtsam::Matrix&> H1 = boost::none,
27  boost::optional<gtsam::Matrix&> H2 = boost::none) const
28  {
29 
30  // calculate error
31  gtsam::Vector error = betweenFactor.evaluateError(p1, p2, H1, H2);
32 
33 
34 
35  // which hypothesis is more likely
36  double m1 = this->noiseModel_->distance(error);
37  gtsam::noiseModel::Gaussian::shared_ptr g1 = this->noiseModel_;
38  gtsam::Matrix info1(g1->R().transpose()*g1->R());
39  double nu1 = 1.0/sqrt(gtsam::inverse(info1).determinant());
40  double l1 = nu1 * exp(-0.5*m1);
41 
42  double m2 = nullHypothesisModel->distance(error);
43  gtsam::noiseModel::Gaussian::shared_ptr g2 = nullHypothesisModel;
44  gtsam::Matrix info2(g2->R().transpose()*g2->R());
45  double nu2 = 1.0/sqrt(gtsam::inverse(info2).determinant());
46  double l2 = nu2 * exp(-0.5*m2);
47 
48  // if the null hypothesis is more likely, than proceed by applying the weight ...
49  if (l2>l1) {
50  if (H1) *H1 = *H1 * weight;
51  if (H2) *H2 = *H2 * weight;
52  error *= sqrt(weight);
53  }
54 
55  return error;
56  };
57 
58  private:
59  gtsam::BetweenFactor<VALUE> betweenFactor;
60  gtsam::SharedNoiseModel nullHypothesisModel;
61  double weight;
62 
63  };
64 }
65 
66 
67 #endif /* BETWEENFACTORMAXMIX_H_ */
GLM_FUNC_DECL vecType< T, P > sqrt(vecType< T, P > const &x)
GLM_FUNC_DECL T determinant(matType< T, P > const &m)
gtsam::BetweenFactor< VALUE > betweenFactor
gtsam::Vector evaluateError(const VALUE &p1, const VALUE &p2, boost::optional< gtsam::Matrix & > H1=boost::none, boost::optional< gtsam::Matrix & > H2=boost::none) const
gtsam::SharedNoiseModel nullHypothesisModel
GLM_FUNC_DECL genType exp(genType const &x)
BetweenFactorMaxMix(gtsam::Key key1, gtsam::Key key2, const VALUE &measured, const gtsam::SharedNoiseModel &model, const gtsam::SharedNoiseModel &model2, double w)
GLM_FUNC_DECL matType< T, P > inverse(matType< T, P > const &m)


rtabmap
Author(s): Mathieu Labbe
autogenerated on Wed Jun 5 2019 22:41:30