8 #ifndef BETWEENFACTORMAXMIX_H_ 9 #define BETWEENFACTORMAXMIX_H_ 11 #include <gtsam/linear/NoiseModel.h> 12 #include <Eigen/Eigen> 21 BetweenFactorMaxMix(gtsam::Key key1, gtsam::Key key2,
const VALUE& measured,
const gtsam::SharedNoiseModel& model,
const gtsam::SharedNoiseModel& model2,
double w)
26 boost::optional<gtsam::Matrix&> H1 = boost::none,
27 boost::optional<gtsam::Matrix&> H2 = boost::none)
const 31 gtsam::Vector error =
betweenFactor.evaluateError(p1, p2, H1, H2);
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());
40 double l1 = nu1 *
exp(-0.5*m1);
44 gtsam::Matrix info2(g2->R().transpose()*g2->R());
46 double l2 = nu2 *
exp(-0.5*m2);
50 if (H1) *H1 = *H1 *
weight;
51 if (H2) *H2 = *H2 *
weight;
52 error *=
sqrt(weight);
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)