#include <betweenFactorMaxMix.h>
Public Member Functions | |
BetweenFactorMaxMix () | |
BetweenFactorMaxMix (gtsam::Key key1, gtsam::Key key2, const VALUE &measured, const gtsam::SharedNoiseModel &model, const gtsam::SharedNoiseModel &model2, double w) | |
gtsam::Vector | evaluateError (const VALUE &p1, const VALUE &p2, boost::optional< gtsam::Matrix & > H1=boost::none, boost::optional< gtsam::Matrix & > H2=boost::none) const |
Private Attributes | |
gtsam::BetweenFactor< VALUE > | betweenFactor |
gtsam::SharedNoiseModel | nullHypothesisModel |
double | weight |
Definition at line 17 of file betweenFactorMaxMix.h.
vertigo::BetweenFactorMaxMix< VALUE >::BetweenFactorMaxMix | ( | ) | [inline] |
Definition at line 20 of file betweenFactorMaxMix.h.
vertigo::BetweenFactorMaxMix< VALUE >::BetweenFactorMaxMix | ( | gtsam::Key | key1, |
gtsam::Key | key2, | ||
const VALUE & | measured, | ||
const gtsam::SharedNoiseModel & | model, | ||
const gtsam::SharedNoiseModel & | model2, | ||
double | w | ||
) | [inline] |
Definition at line 21 of file betweenFactorMaxMix.h.
gtsam::Vector vertigo::BetweenFactorMaxMix< VALUE >::evaluateError | ( | const VALUE & | p1, |
const VALUE & | p2, | ||
boost::optional< gtsam::Matrix & > | H1 = boost::none , |
||
boost::optional< gtsam::Matrix & > | H2 = boost::none |
||
) | const [inline] |
Definition at line 25 of file betweenFactorMaxMix.h.
gtsam::BetweenFactor<VALUE> vertigo::BetweenFactorMaxMix< VALUE >::betweenFactor [private] |
Definition at line 56 of file betweenFactorMaxMix.h.
gtsam::SharedNoiseModel vertigo::BetweenFactorMaxMix< VALUE >::nullHypothesisModel [private] |
Definition at line 60 of file betweenFactorMaxMix.h.
double vertigo::BetweenFactorMaxMix< VALUE >::weight [private] |
Definition at line 61 of file betweenFactorMaxMix.h.