59 SharedGaussian model_inlier_;
60 SharedGaussian model_outlier_;
63 double prior_outlier_;
65 bool flag_bump_up_near_zero_probs_;
66 mutable bool start_with_M_step_;
69 GTSAM_CONCEPT_LIE_TYPE(T)
70 GTSAM_CONCEPT_TESTABLE_TYPE(T)
75 typedef typename boost::shared_ptr<TransformBtwRobotsUnaryFactorEM>
shared_ptr;
83 const SharedGaussian& model_inlier,
const SharedGaussian& model_outlier,
84 const double prior_inlier,
const double prior_outlier,
85 const bool flag_bump_up_near_zero_probs =
false,
86 const bool start_with_M_step =
false) :
87 Base(cref_list_of<1>(key)), key_(key), measured_(measured), keyA_(keyA), keyB_(keyB),
88 model_inlier_(model_inlier), model_outlier_(model_outlier),
89 prior_inlier_(prior_inlier), prior_outlier_(prior_outlier), flag_bump_up_near_zero_probs_(flag_bump_up_near_zero_probs),
90 start_with_M_step_(false){
100 virtual NonlinearFactor::shared_ptr
clone()
const {
return boost::make_shared<This>(*
this); }
106 virtual void print(
const std::string& s,
const KeyFormatter& keyFormatter = DefaultKeyFormatter)
const {
107 std::cout << s <<
"TransformBtwRobotsUnaryFactorEM(" 108 << keyFormatter(key_) <<
")\n";
109 std::cout <<
"MR between factor keys: " 110 << keyFormatter(keyA_) <<
"," 111 << keyFormatter(keyB_) <<
"\n";
112 measured_.print(
" measured: ");
113 model_inlier_->print(
" noise model inlier: ");
114 model_outlier_->print(
" noise model outlier: ");
115 std::cout <<
"(prior_inlier, prior_outlier_) = (" 116 << prior_inlier_ <<
"," 117 << prior_outlier_ <<
")\n";
123 const This *t = dynamic_cast<const This*> (&f);
126 return key_ == t->key_ && measured_.
equals(t->measured_) &&
129 prior_outlier_ == t->prior_outlier_ && prior_inlier_ == t->prior_inlier_;
139 throw(
"something is wrong!");
155 return whitenedError(x).squaredNorm();
168 return boost::shared_ptr<JacobianFactor>();
172 std::vector<Matrix> A(this->
size());
173 Vector b = -whitenedError(x, A);
182 Vector whitenedError(
const Values& x,
183 boost::optional<std::vector<Matrix>&> H = boost::none)
const {
187 Matrix H_compose, H_between1, H_dummy;
189 T orgA_T_currA = valA_.
at<T>(keyA_);
190 T orgB_T_currB = valB_.
at<T>(keyB_);
192 T orgA_T_orgB = x.
at<T>(key_);
194 T orgA_T_currB = orgA_T_orgB.compose(orgB_T_currB, H_compose, H_dummy);
196 T currA_T_currB_pred = orgA_T_currA.between(orgA_T_currB, H_dummy, H_between1);
198 T currA_T_currB_msr = measured_;
200 Vector err = currA_T_currB_msr.localCoordinates(currA_T_currB_pred);
203 Vector p_inlier_outlier = calcIndicatorProb(x, err);
204 double p_inlier = p_inlier_outlier[0];
205 double p_outlier = p_inlier_outlier[1];
207 if (start_with_M_step_){
208 start_with_M_step_ =
false;
214 Vector err_wh_inlier = model_inlier_->whiten(err);
215 Vector err_wh_outlier = model_outlier_->whiten(err);
217 Matrix invCov_inlier = model_inlier_->R().transpose() * model_inlier_->R();
218 Matrix invCov_outlier = model_outlier_->R().transpose() * model_outlier_->R();
221 err_wh_eq.resize(err_wh_inlier.rows()*2);
222 err_wh_eq << sqrt(p_inlier) * err_wh_inlier.array() , sqrt(p_outlier) * err_wh_outlier.array();
224 Matrix H_unwh = H_compose * H_between1;
228 Matrix H_inlier = sqrt(p_inlier)*model_inlier_->Whiten(H_unwh);
229 Matrix H_outlier = sqrt(p_outlier)*model_outlier_->Whiten(H_unwh);
230 Matrix H_aug =
stack(2, &H_inlier, &H_outlier);
232 (*H)[0].resize(H_aug.rows(),H_aug.cols());
249 Vector calcIndicatorProb(
const Values& x)
const {
251 Vector err = unwhitenedError(x);
253 return this->calcIndicatorProb(x, err);
257 Vector calcIndicatorProb(
const Values& x,
const Vector& err)
const {
260 Vector err_wh_inlier = model_inlier_->whiten(err);
261 Vector err_wh_outlier = model_outlier_->whiten(err);
263 Matrix invCov_inlier = model_inlier_->R().transpose() * model_inlier_->R();
264 Matrix invCov_outlier = model_outlier_->R().transpose() * model_outlier_->R();
266 double p_inlier = prior_inlier_ * sqrt(invCov_inlier.norm()) * exp( -0.5 * err_wh_inlier.dot(err_wh_inlier) );
267 double p_outlier = prior_outlier_ * sqrt(invCov_outlier.norm()) * exp( -0.5 * err_wh_outlier.dot(err_wh_outlier) );
269 double sumP = p_inlier + p_outlier;
273 if (flag_bump_up_near_zero_probs_){
276 if (p_inlier < minP || p_outlier < minP){
279 if (p_outlier < minP)
281 sumP = p_inlier + p_outlier;
287 return (Vector(2) << p_inlier, p_outlier).finished();
291 Vector unwhitenedError(
const Values& x)
const {
293 T orgA_T_currA = valA_.
at<T>(keyA_);
294 T orgB_T_currB = valB_.
at<T>(keyB_);
296 T orgA_T_orgB = x.at<T>(key_);
298 T orgA_T_currB = orgA_T_orgB.compose(orgB_T_currB);
300 T currA_T_currB_pred = orgA_T_currA.between(orgA_T_currB);
302 T currA_T_currB_msr = measured_;
304 return currA_T_currB_msr.localCoordinates(currA_T_currB_pred);
308 SharedGaussian get_model_inlier()
const {
309 return model_inlier_;
313 SharedGaussian get_model_outlier()
const {
314 return model_outlier_;
318 Matrix get_model_inlier_cov()
const {
319 return (model_inlier_->R().transpose()*model_inlier_->R()).
inverse();
323 Matrix get_model_outlier_cov()
const {
324 return (model_outlier_->R().transpose()*model_outlier_->R()).
inverse();
328 void updateNoiseModels(
const Values& values,
const Marginals& marginals) {
332 Keys.push_back(keyA_);
333 Keys.push_back(keyB_);
334 JointMarginal joint_marginal12 = marginals.jointMarginalCovariance(Keys);
335 Matrix cov1 = joint_marginal12(keyA_, keyA_);
336 Matrix cov2 = joint_marginal12(keyB_, keyB_);
337 Matrix cov12 = joint_marginal12(keyA_, keyB_);
339 updateNoiseModels_givenCovs(values, cov1, cov2, cov12);
343 void updateNoiseModels(
const Values& values,
const NonlinearFactorGraph& graph){
355 Marginals marginals(graph, values, Marginals::QR);
357 this->updateNoiseModels(values, marginals);
361 void updateNoiseModels_givenCovs(
const Values& values,
const Matrix& cov1,
const Matrix& cov2,
const Matrix& cov12){
371 const T& p1 = values.at<T>(keyA_);
372 const T& p2 = values.at<T>(keyB_);
375 p1.between(p2, H1, H2);
378 H.resize(H1.rows(), H1.rows()+H2.rows());
382 joint_cov.resize(cov1.rows()+cov2.rows(), cov1.cols()+cov2.cols());
383 joint_cov << cov1, cov12,
384 cov12.transpose(), cov2;
386 Matrix cov_state = H*joint_cov*H.transpose();
391 Matrix covRinlier = (model_inlier_->R().transpose()*model_inlier_->R()).
inverse();
394 Matrix covRoutlier = (model_outlier_->R().transpose()*model_outlier_->R()).
inverse();
409 virtual size_t dim()
const {
410 return model_inlier_->R().rows() + model_inlier_->R().cols();
417 template<
class ARCHIVE>
418 void serialize(ARCHIVE & ar,
const unsigned int ) {
419 ar & boost::serialization::make_nvp(
"NonlinearFactor",
420 boost::serialization::base_object<Base>(*
this));
426 template<
class VALUE>
428 public Testable<TransformBtwRobotsUnaryFactorEM<VALUE> > {
virtual bool equals(const NonlinearFactor &f, double tol=1e-9) const
equals
Definition: TransformBtwRobotsUnaryFactorEM.h:122
boost::shared_ptr< TransformBtwRobotsUnaryFactorEM > shared_ptr
concept check by type
Definition: TransformBtwRobotsUnaryFactorEM.h:75
This is the base class for all factor types.
Definition: Factor.h:54
A non-templated config holding any types of Manifold-group elements.
Definition: Values.h:70
ValueType at(Key j) const
Retrieve a variable by key j.
Definition: Values-inl.h:342
virtual void print(const std::string &s, const KeyFormatter &keyFormatter=DefaultKeyFormatter) const
implement functions needed for Testable
Definition: TransformBtwRobotsUnaryFactorEM.h:106
std::uint64_t Key
Integer nonlinear key type.
Definition: types.h:57
friend class boost::serialization::access
Serialization function.
Definition: TransformBtwRobotsUnaryFactorEM.h:416
A helper that implements the traits interface for GTSAM types.
Definition: Testable.h:150
virtual bool equals(const NonlinearFactor &f, double tol=1e-9) const
Check if two factors are equal.
Definition: NonlinearFactor.cpp:36
bool exists(Key j) const
Check if a value exists with key j.
Definition: Values.cpp:97
boost::function< std::string(Key)> KeyFormatter
Typedef for a function to format a key, i.e. to convert it to a string.
Definition: Key.h:33
Definition: TransformBtwRobotsUnaryFactorEM.h:37
T inverse(const T &t)
unary functions
Definition: lieProxies.h:43
Factor Graph Constsiting of non-linear factors.
Nonlinear factor base class.
Definition: NonlinearFactor.h:50
A class for computing marginals in a NonlinearFactorGraph.
virtual boost::shared_ptr< GaussianFactor > linearize(const Values &x) const
Linearize a non-linearFactorN to get a GaussianFactor, Hence .
Definition: TransformBtwRobotsUnaryFactorEM.h:165
static shared_ptr Create(size_t dim)
Create a unit covariance noise model.
Definition: NoiseModel.h:601
void setValAValB(const Values &valA, const Values &valB)
implement functions needed to derive from Factor
Definition: TransformBtwRobotsUnaryFactorEM.h:137
TransformBtwRobotsUnaryFactorEM(Key key, const VALUE &measured, Key keyA, Key keyB, const Values &valA, const Values &valB, const SharedGaussian &model_inlier, const SharedGaussian &model_outlier, const double prior_inlier, const double prior_outlier, const bool flag_bump_up_near_zero_probs=false, const bool start_with_M_step=false)
Constructor.
Definition: TransformBtwRobotsUnaryFactorEM.h:81
FastVector< Key > KeyVector
Define collection type once and for all - also used in wrappers.
Definition: Key.h:56
A manifold defines a space in which there is a notion of a linear tangent space that can be centered ...
Definition: concepts.h:30
Non-linear factor base classes.
A Gaussian factor in the squared-error form.
Definition: JacobianFactor.h:87
virtual size_t dim() const
get the dimension of the factor (number of rows on linearization)
Definition: TransformBtwRobotsUnaryFactorEM.h:409
Matrix stack(size_t nrMatrices,...)
create a matrix by stacking other matrices Given a set of matrices: A1, A2, A3...
Definition: Matrix.cpp:392
virtual bool active(const Values &) const
Checks whether a factor should be used based on a set of values.
Definition: NonlinearFactor.h:113
std::size_t size() const
number of variables attached to this factor
Definition: TransformBtwRobotsUnaryFactorEM.h:405
A factor with a quadratic error function - a Gaussian.
virtual NonlinearFactor::shared_ptr clone() const
Clone.
Definition: TransformBtwRobotsUnaryFactorEM.h:100
Global functions in a separate testing namespace.
Definition: chartTesting.h:28
Concept check for values that can be used in unit tests.
static shared_ptr Covariance(const Matrix &covariance, bool smart=true)
A Gaussian noise model created by specifying a covariance matrix.
Definition: NoiseModel.cpp:112
virtual double error(const Values &x) const
Calculate the error of the factor This is typically equal to log-likelihood, e.g.
Definition: TransformBtwRobotsUnaryFactorEM.h:154
Base class and basic functions for Lie types.
bool equals(const This &other, double tol=1e-9) const
check equality
Definition: Factor.cpp:42
boost::shared_ptr< This > shared_ptr
shared_ptr to this class
Definition: GaussianFactor.h:42
TransformBtwRobotsUnaryFactorEM()
default constructor - only use for serialization
Definition: TransformBtwRobotsUnaryFactorEM.h:78