Merge branch 'svn/trunk'
Conflicts: gtsam_unstable/slam/BetweenFactorEM.h gtsam_unstable/slam/tests/testBetweenFactorEM.cpprelease/4.3a0
commit
d9c9682f6e
|
@ -73,7 +73,7 @@ Values BatchOptimize(const NonlinearFactorGraph& graph, const Values& theta, int
|
|||
|
||||
|
||||
/* ************************************************************************* */
|
||||
TEST( ConcurrentIncrementalSmoother, equals )
|
||||
TEST( ConcurrentIncrementalSmootherDL, equals )
|
||||
{
|
||||
// TODO: Test 'equals' more vigorously
|
||||
|
||||
|
@ -99,7 +99,7 @@ TEST( ConcurrentIncrementalSmoother, equals )
|
|||
}
|
||||
|
||||
/* ************************************************************************* */
|
||||
TEST( ConcurrentIncrementalSmoother, getFactors )
|
||||
TEST( ConcurrentIncrementalSmootherDL, getFactors )
|
||||
{
|
||||
// Create a Concurrent Batch Smoother
|
||||
ISAM2Params parameters;
|
||||
|
@ -150,7 +150,7 @@ TEST( ConcurrentIncrementalSmoother, getFactors )
|
|||
}
|
||||
|
||||
/* ************************************************************************* */
|
||||
TEST( ConcurrentIncrementalSmoother, getLinearizationPoint )
|
||||
TEST( ConcurrentIncrementalSmootherDL, getLinearizationPoint )
|
||||
{
|
||||
// Create a Concurrent Batch Smoother
|
||||
ISAM2Params parameters;
|
||||
|
@ -201,19 +201,19 @@ TEST( ConcurrentIncrementalSmoother, getLinearizationPoint )
|
|||
}
|
||||
|
||||
/* ************************************************************************* */
|
||||
TEST( ConcurrentIncrementalSmoother, getOrdering )
|
||||
TEST( ConcurrentIncrementalSmootherDL, getOrdering )
|
||||
{
|
||||
// TODO: Think about how to check ordering...
|
||||
}
|
||||
|
||||
/* ************************************************************************* */
|
||||
TEST( ConcurrentIncrementalSmoother, getDelta )
|
||||
TEST( ConcurrentIncrementalSmootherDL, getDelta )
|
||||
{
|
||||
// TODO: Think about how to check ordering...
|
||||
}
|
||||
|
||||
/* ************************************************************************* */
|
||||
TEST( ConcurrentIncrementalSmoother, calculateEstimate )
|
||||
TEST( ConcurrentIncrementalSmootherDL, calculateEstimate )
|
||||
{
|
||||
// Create a Concurrent Batch Smoother
|
||||
ISAM2Params parameters;
|
||||
|
@ -287,7 +287,7 @@ TEST( ConcurrentIncrementalSmoother, calculateEstimate )
|
|||
}
|
||||
|
||||
/* ************************************************************************* */
|
||||
TEST( ConcurrentIncrementalSmoother, update_empty )
|
||||
TEST( ConcurrentIncrementalSmootherDL, update_empty )
|
||||
{
|
||||
// Create a set of optimizer parameters
|
||||
ISAM2Params parameters;
|
||||
|
@ -300,7 +300,7 @@ TEST( ConcurrentIncrementalSmoother, update_empty )
|
|||
}
|
||||
|
||||
/* ************************************************************************* */
|
||||
TEST( ConcurrentIncrementalSmoother, update_multiple )
|
||||
TEST( ConcurrentIncrementalSmootherDL, update_multiple )
|
||||
{
|
||||
// Create a Concurrent Batch Smoother
|
||||
ISAM2Params parameters;
|
||||
|
@ -358,7 +358,7 @@ TEST( ConcurrentIncrementalSmoother, update_multiple )
|
|||
}
|
||||
|
||||
/* ************************************************************************* */
|
||||
TEST( ConcurrentIncrementalSmoother, synchronize_empty )
|
||||
TEST( ConcurrentIncrementalSmootherDL, synchronize_empty )
|
||||
{
|
||||
// Create a set of optimizer parameters
|
||||
ISAM2Params parameters;
|
||||
|
@ -388,7 +388,7 @@ TEST( ConcurrentIncrementalSmoother, synchronize_empty )
|
|||
}
|
||||
|
||||
/* ************************************************************************* */
|
||||
TEST( ConcurrentIncrementalSmoother, synchronize_1 )
|
||||
TEST( ConcurrentIncrementalSmootherDL, synchronize_1 )
|
||||
{
|
||||
// Create a set of optimizer parameters
|
||||
ISAM2Params parameters;
|
||||
|
@ -450,7 +450,7 @@ TEST( ConcurrentIncrementalSmoother, synchronize_1 )
|
|||
|
||||
|
||||
/* ************************************************************************* */
|
||||
TEST( ConcurrentIncrementalSmoother, synchronize_2 )
|
||||
TEST( ConcurrentIncrementalSmootherDL, synchronize_2 )
|
||||
{
|
||||
// Create a set of optimizer parameters
|
||||
ISAM2Params parameters;
|
||||
|
@ -531,7 +531,7 @@ TEST( ConcurrentIncrementalSmoother, synchronize_2 )
|
|||
|
||||
|
||||
/* ************************************************************************* */
|
||||
TEST( ConcurrentIncrementalSmoother, synchronize_3 )
|
||||
TEST( ConcurrentIncrementalSmootherDL, synchronize_3 )
|
||||
{
|
||||
// Create a set of optimizer parameters
|
||||
ISAM2Params parameters;
|
||||
|
|
|
@ -73,7 +73,7 @@ Values BatchOptimize(const NonlinearFactorGraph& graph, const Values& theta, int
|
|||
|
||||
|
||||
/* ************************************************************************* */
|
||||
TEST( ConcurrentIncrementalSmoother, equals )
|
||||
TEST( ConcurrentIncrementalSmootherGN, equals )
|
||||
{
|
||||
// TODO: Test 'equals' more vigorously
|
||||
|
||||
|
@ -99,7 +99,7 @@ TEST( ConcurrentIncrementalSmoother, equals )
|
|||
}
|
||||
|
||||
/* ************************************************************************* */
|
||||
TEST( ConcurrentIncrementalSmoother, getFactors )
|
||||
TEST( ConcurrentIncrementalSmootherGN, getFactors )
|
||||
{
|
||||
// Create a Concurrent Batch Smoother
|
||||
ISAM2Params parameters;
|
||||
|
@ -150,7 +150,7 @@ TEST( ConcurrentIncrementalSmoother, getFactors )
|
|||
}
|
||||
|
||||
/* ************************************************************************* */
|
||||
TEST( ConcurrentIncrementalSmoother, getLinearizationPoint )
|
||||
TEST( ConcurrentIncrementalSmootherGN, getLinearizationPoint )
|
||||
{
|
||||
// Create a Concurrent Batch Smoother
|
||||
ISAM2Params parameters;
|
||||
|
@ -201,19 +201,19 @@ TEST( ConcurrentIncrementalSmoother, getLinearizationPoint )
|
|||
}
|
||||
|
||||
/* ************************************************************************* */
|
||||
TEST( ConcurrentIncrementalSmoother, getOrdering )
|
||||
TEST( ConcurrentIncrementalSmootherGN, getOrdering )
|
||||
{
|
||||
// TODO: Think about how to check ordering...
|
||||
}
|
||||
|
||||
/* ************************************************************************* */
|
||||
TEST( ConcurrentIncrementalSmoother, getDelta )
|
||||
TEST( ConcurrentIncrementalSmootherGN, getDelta )
|
||||
{
|
||||
// TODO: Think about how to check ordering...
|
||||
}
|
||||
|
||||
/* ************************************************************************* */
|
||||
TEST( ConcurrentIncrementalSmoother, calculateEstimate )
|
||||
TEST( ConcurrentIncrementalSmootherGN, calculateEstimate )
|
||||
{
|
||||
// Create a Concurrent Batch Smoother
|
||||
ISAM2Params parameters;
|
||||
|
@ -287,7 +287,7 @@ TEST( ConcurrentIncrementalSmoother, calculateEstimate )
|
|||
}
|
||||
|
||||
/* ************************************************************************* */
|
||||
TEST( ConcurrentIncrementalSmoother, update_empty )
|
||||
TEST( ConcurrentIncrementalSmootherGN, update_empty )
|
||||
{
|
||||
// Create a set of optimizer parameters
|
||||
ISAM2Params parameters;
|
||||
|
@ -300,7 +300,7 @@ TEST( ConcurrentIncrementalSmoother, update_empty )
|
|||
}
|
||||
|
||||
/* ************************************************************************* */
|
||||
TEST( ConcurrentIncrementalSmoother, update_multiple )
|
||||
TEST( ConcurrentIncrementalSmootherGN, update_multiple )
|
||||
{
|
||||
// Create a Concurrent Batch Smoother
|
||||
ISAM2Params parameters;
|
||||
|
@ -358,7 +358,7 @@ TEST( ConcurrentIncrementalSmoother, update_multiple )
|
|||
}
|
||||
|
||||
/* ************************************************************************* */
|
||||
TEST( ConcurrentIncrementalSmoother, synchronize_empty )
|
||||
TEST( ConcurrentIncrementalSmootherGN, synchronize_empty )
|
||||
{
|
||||
// Create a set of optimizer parameters
|
||||
ISAM2Params parameters;
|
||||
|
@ -388,7 +388,7 @@ TEST( ConcurrentIncrementalSmoother, synchronize_empty )
|
|||
}
|
||||
|
||||
/* ************************************************************************* */
|
||||
TEST( ConcurrentIncrementalSmoother, synchronize_1 )
|
||||
TEST( ConcurrentIncrementalSmootherGN, synchronize_1 )
|
||||
{
|
||||
// Create a set of optimizer parameters
|
||||
ISAM2Params parameters;
|
||||
|
@ -450,7 +450,7 @@ TEST( ConcurrentIncrementalSmoother, synchronize_1 )
|
|||
|
||||
|
||||
/* ************************************************************************* */
|
||||
TEST( ConcurrentIncrementalSmoother, synchronize_2 )
|
||||
TEST( ConcurrentIncrementalSmootherGN, synchronize_2 )
|
||||
{
|
||||
// Create a set of optimizer parameters
|
||||
ISAM2Params parameters;
|
||||
|
@ -531,7 +531,7 @@ TEST( ConcurrentIncrementalSmoother, synchronize_2 )
|
|||
|
||||
|
||||
/* ************************************************************************* */
|
||||
TEST( ConcurrentIncrementalSmoother, synchronize_3 )
|
||||
TEST( ConcurrentIncrementalSmootherGN, synchronize_3 )
|
||||
{
|
||||
// Create a set of optimizer parameters
|
||||
ISAM2Params parameters;
|
||||
|
|
|
@ -1,299 +1,299 @@
|
|||
/* ----------------------------------------------------------------------------
|
||||
|
||||
* GTSAM Copyright 2010, Georgia Tech Research Corporation,
|
||||
* Atlanta, Georgia 30332-0415
|
||||
* All Rights Reserved
|
||||
* Authors: Frank Dellaert, et al. (see THANKS for the full author list)
|
||||
|
||||
* See LICENSE for the license information
|
||||
|
||||
* -------------------------------------------------------------------------- */
|
||||
|
||||
/**
|
||||
* @file BetweenFactorEM.h
|
||||
* @author Vadim Indelman
|
||||
**/
|
||||
#pragma once
|
||||
|
||||
#include <ostream>
|
||||
|
||||
#include <gtsam/base/Testable.h>
|
||||
#include <gtsam/base/Lie.h>
|
||||
#include <gtsam/nonlinear/NonlinearFactor.h>
|
||||
#include <gtsam/linear/GaussianFactor.h>
|
||||
|
||||
namespace gtsam {
|
||||
|
||||
/**
|
||||
* A class for a measurement predicted by "between(config[key1],config[key2])"
|
||||
* @tparam VALUE the Value type
|
||||
* @addtogroup SLAM
|
||||
*/
|
||||
template<class VALUE>
|
||||
class BetweenFactorEM: public NonlinearFactor {
|
||||
|
||||
public:
|
||||
|
||||
typedef VALUE T;
|
||||
|
||||
private:
|
||||
|
||||
typedef BetweenFactorEM<VALUE> This;
|
||||
typedef gtsam::NonlinearFactor Base;
|
||||
|
||||
gtsam::Key key1_;
|
||||
gtsam::Key key2_;
|
||||
|
||||
VALUE measured_; /** The measurement */
|
||||
|
||||
SharedGaussian model_inlier_;
|
||||
SharedGaussian model_outlier_;
|
||||
|
||||
double prior_inlier_;
|
||||
double prior_outlier_;
|
||||
|
||||
/** concept check by type */
|
||||
GTSAM_CONCEPT_LIE_TYPE(T)
|
||||
GTSAM_CONCEPT_TESTABLE_TYPE(T)
|
||||
|
||||
public:
|
||||
|
||||
// shorthand for a smart pointer to a factor
|
||||
typedef typename boost::shared_ptr<BetweenFactorEM> shared_ptr;
|
||||
|
||||
/** default constructor - only use for serialization */
|
||||
BetweenFactorEM() {}
|
||||
|
||||
/** Constructor */
|
||||
BetweenFactorEM(Key key1, Key key2, const VALUE& measured,
|
||||
const SharedGaussian& model_inlier, const SharedGaussian& model_outlier,
|
||||
const double prior_inlier, const double prior_outlier) :
|
||||
Base(cref_list_of<2>(key1)(key2)), key1_(key1), key2_(key2), measured_(measured),
|
||||
model_inlier_(model_inlier), model_outlier_(model_outlier),
|
||||
prior_inlier_(prior_inlier), prior_outlier_(prior_outlier){
|
||||
}
|
||||
|
||||
virtual ~BetweenFactorEM() {}
|
||||
|
||||
|
||||
/** implement functions needed for Testable */
|
||||
|
||||
/** print */
|
||||
virtual void print(const std::string& s, const KeyFormatter& keyFormatter = DefaultKeyFormatter) const {
|
||||
std::cout << s << "BetweenFactorEM("
|
||||
<< keyFormatter(key1_) << ","
|
||||
<< keyFormatter(key2_) << ")\n";
|
||||
measured_.print(" measured: ");
|
||||
model_inlier_->print(" noise model inlier: ");
|
||||
model_outlier_->print(" noise model outlier: ");
|
||||
std::cout << "(prior_inlier, prior_outlier_) = ("
|
||||
<< prior_inlier_ << ","
|
||||
<< prior_outlier_ << ")\n";
|
||||
// Base::print(s, keyFormatter);
|
||||
}
|
||||
|
||||
/** equals */
|
||||
virtual bool equals(const NonlinearFactor& f, double tol=1e-9) const {
|
||||
const This *t = dynamic_cast<const This*> (&f);
|
||||
|
||||
if(t && Base::equals(f))
|
||||
return key1_ == t->key1_ && key2_ == t->key2_ &&
|
||||
// model_inlier_->equals(t->model_inlier_ ) && // TODO: fix here
|
||||
// model_outlier_->equals(t->model_outlier_ ) &&
|
||||
prior_outlier_ == t->prior_outlier_ && prior_inlier_ == t->prior_inlier_ && measured_.equals(t->measured_);
|
||||
else
|
||||
return false;
|
||||
}
|
||||
|
||||
/** implement functions needed to derive from Factor */
|
||||
|
||||
/* ************************************************************************* */
|
||||
virtual double error(const gtsam::Values& x) const {
|
||||
return whitenedError(x).squaredNorm();
|
||||
}
|
||||
|
||||
/* ************************************************************************* */
|
||||
/**
|
||||
* Linearize a non-linearFactorN to get a gtsam::GaussianFactor,
|
||||
* \f$ Ax-b \approx h(x+\delta x)-z = h(x) + A \delta x - z \f$
|
||||
* Hence \f$ b = z - h(x) = - \mathtt{error\_vector}(x) \f$
|
||||
*/
|
||||
/* This version of linearize recalculates the noise model each time */
|
||||
virtual boost::shared_ptr<gtsam::GaussianFactor> linearize(const gtsam::Values& x) const {
|
||||
// Only linearize if the factor is active
|
||||
if (!this->active(x))
|
||||
return boost::shared_ptr<gtsam::JacobianFactor>();
|
||||
|
||||
//std::cout<<"About to linearize"<<std::endl;
|
||||
gtsam::Matrix A1, A2;
|
||||
std::vector<gtsam::Matrix> A(this->size());
|
||||
gtsam::Vector b = -whitenedError(x, A);
|
||||
A1 = A[0];
|
||||
A2 = A[1];
|
||||
|
||||
return gtsam::GaussianFactor::shared_ptr(
|
||||
new gtsam::JacobianFactor(key1_, A1, key2_, A2, b, gtsam::noiseModel::Unit::Create(b.size())));
|
||||
}
|
||||
|
||||
|
||||
/* ************************************************************************* */
|
||||
gtsam::Vector whitenedError(const gtsam::Values& x,
|
||||
boost::optional<std::vector<gtsam::Matrix>&> H = boost::none) const {
|
||||
|
||||
bool debug = true;
|
||||
|
||||
const T& p1 = x.at<T>(key1_);
|
||||
const T& p2 = x.at<T>(key2_);
|
||||
|
||||
Matrix H1, H2;
|
||||
|
||||
T hx = p1.between(p2, H1, H2); // h(x)
|
||||
// manifold equivalent of h(x)-z -> log(z,h(x))
|
||||
|
||||
Vector err = measured_.localCoordinates(hx);
|
||||
|
||||
// Calculate indicator probabilities (inlier and outlier)
|
||||
Vector p_inlier_outlier = calcIndicatorProb(x);
|
||||
double p_inlier = p_inlier_outlier[0];
|
||||
double p_outlier = p_inlier_outlier[1];
|
||||
|
||||
Vector err_wh_inlier = model_inlier_->whiten(err);
|
||||
Vector err_wh_outlier = model_outlier_->whiten(err);
|
||||
|
||||
Matrix invCov_inlier = model_inlier_->R().transpose() * model_inlier_->R();
|
||||
Matrix invCov_outlier = model_outlier_->R().transpose() * model_outlier_->R();
|
||||
|
||||
Vector err_wh_eq;
|
||||
err_wh_eq.resize(err_wh_inlier.rows()*2);
|
||||
err_wh_eq << sqrt(p_inlier) * err_wh_inlier.array() , sqrt(p_outlier) * err_wh_outlier.array();
|
||||
|
||||
if (H){
|
||||
// stack Jacobians for the two indicators for each of the key
|
||||
|
||||
Matrix H1_inlier = sqrt(p_inlier)*model_inlier_->Whiten(H1);
|
||||
Matrix H1_outlier = sqrt(p_outlier)*model_outlier_->Whiten(H1);
|
||||
Matrix H1_aug = gtsam::stack(2, &H1_inlier, &H1_outlier);
|
||||
|
||||
Matrix H2_inlier = sqrt(p_inlier)*model_inlier_->Whiten(H2);
|
||||
Matrix H2_outlier = sqrt(p_outlier)*model_outlier_->Whiten(H2);
|
||||
Matrix H2_aug = gtsam::stack(2, &H2_inlier, &H2_outlier);
|
||||
|
||||
(*H)[0].resize(H1_aug.rows(),H1_aug.cols());
|
||||
(*H)[1].resize(H2_aug.rows(),H2_aug.cols());
|
||||
|
||||
(*H)[0] = H1_aug;
|
||||
(*H)[1] = H2_aug;
|
||||
}
|
||||
|
||||
if (debug){
|
||||
// std::cout<<"unwhitened error: "<<err[0]<<" "<<err[1]<<" "<<err[2]<<std::endl;
|
||||
// std::cout<<"err_wh_inlier: "<<err_wh_inlier[0]<<" "<<err_wh_inlier[1]<<" "<<err_wh_inlier[2]<<std::endl;
|
||||
// std::cout<<"err_wh_outlier: "<<err_wh_outlier[0]<<" "<<err_wh_outlier[1]<<" "<<err_wh_outlier[2]<<std::endl;
|
||||
//
|
||||
// std::cout<<"p_inlier, p_outlier, sumP: "<<p_inlier<<" "<<p_outlier<<" " << sumP << std::endl;
|
||||
//
|
||||
// std::cout<<"prior_inlier_, prior_outlier_: "<<prior_inlier_<<" "<<prior_outlier_<< std::endl;
|
||||
//
|
||||
// double s_inl = -0.5 * err_wh_inlier.dot(err_wh_inlier);
|
||||
// double s_outl = -0.5 * err_wh_outlier.dot(err_wh_outlier);
|
||||
// std::cout<<"s_inl, s_outl: "<<s_inl<<" "<<s_outl<<std::endl;
|
||||
//
|
||||
// std::cout<<"norm of invCov_inlier, invCov_outlier: "<<invCov_inlier.norm()<<" "<<invCov_outlier.norm()<<std::endl;
|
||||
// double q_inl = invCov_inlier.norm() * exp( -0.5 * err_wh_inlier.dot(err_wh_inlier) );
|
||||
// double q_outl = invCov_outlier.norm() * exp( -0.5 * err_wh_outlier.dot(err_wh_outlier) );
|
||||
// std::cout<<"q_inl, q_outl: "<<q_inl<<" "<<q_outl<<std::endl;
|
||||
|
||||
// Matrix Cov_inlier = invCov_inlier.inverse();
|
||||
// Matrix Cov_outlier = invCov_outlier.inverse();
|
||||
// std::cout<<"Cov_inlier: "<<std::endl<<
|
||||
// Cov_inlier(0,0) << " " << Cov_inlier(0,1) << " " << Cov_inlier(0,2) <<std::endl<<
|
||||
// Cov_inlier(1,0) << " " << Cov_inlier(1,1) << " " << Cov_inlier(1,2) <<std::endl<<
|
||||
// Cov_inlier(2,0) << " " << Cov_inlier(2,1) << " " << Cov_inlier(2,2) <<std::endl;
|
||||
// std::cout<<"Cov_outlier: "<<std::endl<<
|
||||
// Cov_outlier(0,0) << " " << Cov_outlier(0,1) << " " << Cov_outlier(0,2) <<std::endl<<
|
||||
// Cov_outlier(1,0) << " " << Cov_outlier(1,1) << " " << Cov_outlier(1,2) <<std::endl<<
|
||||
// Cov_outlier(2,0) << " " << Cov_outlier(2,1) << " " << Cov_outlier(2,2) <<std::endl;
|
||||
// std::cout<<"===="<<std::endl;
|
||||
}
|
||||
|
||||
|
||||
return err_wh_eq;
|
||||
}
|
||||
|
||||
/* ************************************************************************* */
|
||||
gtsam::Vector calcIndicatorProb(const gtsam::Values& x) const {
|
||||
|
||||
Vector err = unwhitenedError(x);
|
||||
|
||||
// Calculate indicator probabilities (inlier and outlier)
|
||||
Vector err_wh_inlier = model_inlier_->whiten(err);
|
||||
Vector err_wh_outlier = model_outlier_->whiten(err);
|
||||
|
||||
Matrix invCov_inlier = model_inlier_->R().transpose() * model_inlier_->R();
|
||||
Matrix invCov_outlier = model_outlier_->R().transpose() * model_outlier_->R();
|
||||
|
||||
double p_inlier = prior_inlier_ * invCov_inlier.norm() * exp( -0.5 * err_wh_inlier.dot(err_wh_inlier) );
|
||||
double p_outlier = prior_outlier_ * invCov_outlier.norm() * exp( -0.5 * err_wh_outlier.dot(err_wh_outlier) );
|
||||
|
||||
double sumP = p_inlier + p_outlier;
|
||||
p_inlier /= sumP;
|
||||
p_outlier /= sumP;
|
||||
|
||||
// Bump up near-zero probabilities (as in linerFlow.h)
|
||||
double minP = 0.05; // == 0.1 / 2 indicator variables
|
||||
if (p_inlier < minP || p_outlier < minP){
|
||||
if (p_inlier < minP)
|
||||
p_inlier = minP;
|
||||
if (p_outlier < minP)
|
||||
p_outlier = minP;
|
||||
sumP = p_inlier + p_outlier;
|
||||
p_inlier /= sumP;
|
||||
p_outlier /= sumP;
|
||||
}
|
||||
|
||||
return Vector_(2, p_inlier, p_outlier);
|
||||
}
|
||||
|
||||
/* ************************************************************************* */
|
||||
gtsam::Vector unwhitenedError(const gtsam::Values& x) const {
|
||||
|
||||
bool debug = true;
|
||||
|
||||
const T& p1 = x.at<T>(key1_);
|
||||
const T& p2 = x.at<T>(key2_);
|
||||
|
||||
Matrix H1, H2;
|
||||
|
||||
T hx = p1.between(p2, H1, H2); // h(x)
|
||||
|
||||
return measured_.localCoordinates(hx);
|
||||
}
|
||||
|
||||
/* ************************************************************************* */
|
||||
/** return the measured */
|
||||
const VALUE& measured() const {
|
||||
return measured_;
|
||||
}
|
||||
|
||||
/** number of variables attached to this factor */
|
||||
std::size_t size() const {
|
||||
return 2;
|
||||
}
|
||||
|
||||
virtual size_t dim() const {
|
||||
return model_inlier_->R().rows() + model_inlier_->R().cols();
|
||||
}
|
||||
|
||||
private:
|
||||
|
||||
/** Serialization function */
|
||||
friend class boost::serialization::access;
|
||||
template<class ARCHIVE>
|
||||
void serialize(ARCHIVE & ar, const unsigned int version) {
|
||||
ar & boost::serialization::make_nvp("NonlinearFactor",
|
||||
boost::serialization::base_object<Base>(*this));
|
||||
ar & BOOST_SERIALIZATION_NVP(measured_);
|
||||
}
|
||||
}; // \class BetweenFactorEM
|
||||
|
||||
} /// namespace gtsam
|
||||
/* ----------------------------------------------------------------------------
|
||||
|
||||
* GTSAM Copyright 2010, Georgia Tech Research Corporation,
|
||||
* Atlanta, Georgia 30332-0415
|
||||
* All Rights Reserved
|
||||
* Authors: Frank Dellaert, et al. (see THANKS for the full author list)
|
||||
|
||||
* See LICENSE for the license information
|
||||
|
||||
* -------------------------------------------------------------------------- */
|
||||
|
||||
/**
|
||||
* @file BetweenFactorEM.h
|
||||
* @author Vadim Indelman
|
||||
**/
|
||||
#pragma once
|
||||
|
||||
#include <ostream>
|
||||
|
||||
#include <gtsam/base/Testable.h>
|
||||
#include <gtsam/base/Lie.h>
|
||||
#include <gtsam/nonlinear/NonlinearFactor.h>
|
||||
#include <gtsam/linear/GaussianFactor.h>
|
||||
|
||||
namespace gtsam {
|
||||
|
||||
/**
|
||||
* A class for a measurement predicted by "between(config[key1],config[key2])"
|
||||
* @tparam VALUE the Value type
|
||||
* @addtogroup SLAM
|
||||
*/
|
||||
template<class VALUE>
|
||||
class BetweenFactorEM: public NonlinearFactor {
|
||||
|
||||
public:
|
||||
|
||||
typedef VALUE T;
|
||||
|
||||
private:
|
||||
|
||||
typedef BetweenFactorEM<VALUE> This;
|
||||
typedef gtsam::NonlinearFactor Base;
|
||||
|
||||
gtsam::Key key1_;
|
||||
gtsam::Key key2_;
|
||||
|
||||
VALUE measured_; /** The measurement */
|
||||
|
||||
SharedGaussian model_inlier_;
|
||||
SharedGaussian model_outlier_;
|
||||
|
||||
double prior_inlier_;
|
||||
double prior_outlier_;
|
||||
|
||||
/** concept check by type */
|
||||
GTSAM_CONCEPT_LIE_TYPE(T)
|
||||
GTSAM_CONCEPT_TESTABLE_TYPE(T)
|
||||
|
||||
public:
|
||||
|
||||
// shorthand for a smart pointer to a factor
|
||||
typedef typename boost::shared_ptr<BetweenFactorEM> shared_ptr;
|
||||
|
||||
/** default constructor - only use for serialization */
|
||||
BetweenFactorEM() {}
|
||||
|
||||
/** Constructor */
|
||||
BetweenFactorEM(Key key1, Key key2, const VALUE& measured,
|
||||
const SharedGaussian& model_inlier, const SharedGaussian& model_outlier,
|
||||
const double prior_inlier, const double prior_outlier) :
|
||||
Base(cref_list_of<2>(key1)(key2)), key1_(key1), key2_(key2), measured_(measured),
|
||||
model_inlier_(model_inlier), model_outlier_(model_outlier),
|
||||
prior_inlier_(prior_inlier), prior_outlier_(prior_outlier){
|
||||
}
|
||||
|
||||
virtual ~BetweenFactorEM() {}
|
||||
|
||||
|
||||
/** implement functions needed for Testable */
|
||||
|
||||
/** print */
|
||||
virtual void print(const std::string& s, const KeyFormatter& keyFormatter = DefaultKeyFormatter) const {
|
||||
std::cout << s << "BetweenFactorEM("
|
||||
<< keyFormatter(key1_) << ","
|
||||
<< keyFormatter(key2_) << ")\n";
|
||||
measured_.print(" measured: ");
|
||||
model_inlier_->print(" noise model inlier: ");
|
||||
model_outlier_->print(" noise model outlier: ");
|
||||
std::cout << "(prior_inlier, prior_outlier_) = ("
|
||||
<< prior_inlier_ << ","
|
||||
<< prior_outlier_ << ")\n";
|
||||
// Base::print(s, keyFormatter);
|
||||
}
|
||||
|
||||
/** equals */
|
||||
virtual bool equals(const NonlinearFactor& f, double tol=1e-9) const {
|
||||
const This *t = dynamic_cast<const This*> (&f);
|
||||
|
||||
if(t && Base::equals(f))
|
||||
return key1_ == t->key1_ && key2_ == t->key2_ &&
|
||||
// model_inlier_->equals(t->model_inlier_ ) && // TODO: fix here
|
||||
// model_outlier_->equals(t->model_outlier_ ) &&
|
||||
prior_outlier_ == t->prior_outlier_ && prior_inlier_ == t->prior_inlier_ && measured_.equals(t->measured_);
|
||||
else
|
||||
return false;
|
||||
}
|
||||
|
||||
/** implement functions needed to derive from Factor */
|
||||
|
||||
/* ************************************************************************* */
|
||||
virtual double error(const gtsam::Values& x) const {
|
||||
return whitenedError(x).squaredNorm();
|
||||
}
|
||||
|
||||
/* ************************************************************************* */
|
||||
/**
|
||||
* Linearize a non-linearFactorN to get a gtsam::GaussianFactor,
|
||||
* \f$ Ax-b \approx h(x+\delta x)-z = h(x) + A \delta x - z \f$
|
||||
* Hence \f$ b = z - h(x) = - \mathtt{error\_vector}(x) \f$
|
||||
*/
|
||||
/* This version of linearize recalculates the noise model each time */
|
||||
virtual boost::shared_ptr<gtsam::GaussianFactor> linearize(const gtsam::Values& x) const {
|
||||
// Only linearize if the factor is active
|
||||
if (!this->active(x))
|
||||
return boost::shared_ptr<gtsam::JacobianFactor>();
|
||||
|
||||
//std::cout<<"About to linearize"<<std::endl;
|
||||
gtsam::Matrix A1, A2;
|
||||
std::vector<gtsam::Matrix> A(this->size());
|
||||
gtsam::Vector b = -whitenedError(x, A);
|
||||
A1 = A[0];
|
||||
A2 = A[1];
|
||||
|
||||
return gtsam::GaussianFactor::shared_ptr(
|
||||
new gtsam::JacobianFactor(key1_, A1, key2_, A2, b, gtsam::noiseModel::Unit::Create(b.size())));
|
||||
}
|
||||
|
||||
|
||||
/* ************************************************************************* */
|
||||
gtsam::Vector whitenedError(const gtsam::Values& x,
|
||||
boost::optional<std::vector<gtsam::Matrix>&> H = boost::none) const {
|
||||
|
||||
bool debug = true;
|
||||
|
||||
const T& p1 = x.at<T>(key1_);
|
||||
const T& p2 = x.at<T>(key2_);
|
||||
|
||||
Matrix H1, H2;
|
||||
|
||||
T hx = p1.between(p2, H1, H2); // h(x)
|
||||
// manifold equivalent of h(x)-z -> log(z,h(x))
|
||||
|
||||
Vector err = measured_.localCoordinates(hx);
|
||||
|
||||
// Calculate indicator probabilities (inlier and outlier)
|
||||
Vector p_inlier_outlier = calcIndicatorProb(x);
|
||||
double p_inlier = p_inlier_outlier[0];
|
||||
double p_outlier = p_inlier_outlier[1];
|
||||
|
||||
Vector err_wh_inlier = model_inlier_->whiten(err);
|
||||
Vector err_wh_outlier = model_outlier_->whiten(err);
|
||||
|
||||
Matrix invCov_inlier = model_inlier_->R().transpose() * model_inlier_->R();
|
||||
Matrix invCov_outlier = model_outlier_->R().transpose() * model_outlier_->R();
|
||||
|
||||
Vector err_wh_eq;
|
||||
err_wh_eq.resize(err_wh_inlier.rows()*2);
|
||||
err_wh_eq << sqrt(p_inlier) * err_wh_inlier.array() , sqrt(p_outlier) * err_wh_outlier.array();
|
||||
|
||||
if (H){
|
||||
// stack Jacobians for the two indicators for each of the key
|
||||
|
||||
Matrix H1_inlier = sqrt(p_inlier)*model_inlier_->Whiten(H1);
|
||||
Matrix H1_outlier = sqrt(p_outlier)*model_outlier_->Whiten(H1);
|
||||
Matrix H1_aug = gtsam::stack(2, &H1_inlier, &H1_outlier);
|
||||
|
||||
Matrix H2_inlier = sqrt(p_inlier)*model_inlier_->Whiten(H2);
|
||||
Matrix H2_outlier = sqrt(p_outlier)*model_outlier_->Whiten(H2);
|
||||
Matrix H2_aug = gtsam::stack(2, &H2_inlier, &H2_outlier);
|
||||
|
||||
(*H)[0].resize(H1_aug.rows(),H1_aug.cols());
|
||||
(*H)[1].resize(H2_aug.rows(),H2_aug.cols());
|
||||
|
||||
(*H)[0] = H1_aug;
|
||||
(*H)[1] = H2_aug;
|
||||
}
|
||||
|
||||
if (debug){
|
||||
// std::cout<<"unwhitened error: "<<err[0]<<" "<<err[1]<<" "<<err[2]<<std::endl;
|
||||
// std::cout<<"err_wh_inlier: "<<err_wh_inlier[0]<<" "<<err_wh_inlier[1]<<" "<<err_wh_inlier[2]<<std::endl;
|
||||
// std::cout<<"err_wh_outlier: "<<err_wh_outlier[0]<<" "<<err_wh_outlier[1]<<" "<<err_wh_outlier[2]<<std::endl;
|
||||
//
|
||||
// std::cout<<"p_inlier, p_outlier, sumP: "<<p_inlier<<" "<<p_outlier<<" " << sumP << std::endl;
|
||||
//
|
||||
// std::cout<<"prior_inlier_, prior_outlier_: "<<prior_inlier_<<" "<<prior_outlier_<< std::endl;
|
||||
//
|
||||
// double s_inl = -0.5 * err_wh_inlier.dot(err_wh_inlier);
|
||||
// double s_outl = -0.5 * err_wh_outlier.dot(err_wh_outlier);
|
||||
// std::cout<<"s_inl, s_outl: "<<s_inl<<" "<<s_outl<<std::endl;
|
||||
//
|
||||
// std::cout<<"norm of invCov_inlier, invCov_outlier: "<<invCov_inlier.norm()<<" "<<invCov_outlier.norm()<<std::endl;
|
||||
// double q_inl = invCov_inlier.norm() * exp( -0.5 * err_wh_inlier.dot(err_wh_inlier) );
|
||||
// double q_outl = invCov_outlier.norm() * exp( -0.5 * err_wh_outlier.dot(err_wh_outlier) );
|
||||
// std::cout<<"q_inl, q_outl: "<<q_inl<<" "<<q_outl<<std::endl;
|
||||
|
||||
// Matrix Cov_inlier = invCov_inlier.inverse();
|
||||
// Matrix Cov_outlier = invCov_outlier.inverse();
|
||||
// std::cout<<"Cov_inlier: "<<std::endl<<
|
||||
// Cov_inlier(0,0) << " " << Cov_inlier(0,1) << " " << Cov_inlier(0,2) <<std::endl<<
|
||||
// Cov_inlier(1,0) << " " << Cov_inlier(1,1) << " " << Cov_inlier(1,2) <<std::endl<<
|
||||
// Cov_inlier(2,0) << " " << Cov_inlier(2,1) << " " << Cov_inlier(2,2) <<std::endl;
|
||||
// std::cout<<"Cov_outlier: "<<std::endl<<
|
||||
// Cov_outlier(0,0) << " " << Cov_outlier(0,1) << " " << Cov_outlier(0,2) <<std::endl<<
|
||||
// Cov_outlier(1,0) << " " << Cov_outlier(1,1) << " " << Cov_outlier(1,2) <<std::endl<<
|
||||
// Cov_outlier(2,0) << " " << Cov_outlier(2,1) << " " << Cov_outlier(2,2) <<std::endl;
|
||||
// std::cout<<"===="<<std::endl;
|
||||
}
|
||||
|
||||
|
||||
return err_wh_eq;
|
||||
}
|
||||
|
||||
/* ************************************************************************* */
|
||||
gtsam::Vector calcIndicatorProb(const gtsam::Values& x) const {
|
||||
|
||||
Vector err = unwhitenedError(x);
|
||||
|
||||
// Calculate indicator probabilities (inlier and outlier)
|
||||
Vector err_wh_inlier = model_inlier_->whiten(err);
|
||||
Vector err_wh_outlier = model_outlier_->whiten(err);
|
||||
|
||||
Matrix invCov_inlier = model_inlier_->R().transpose() * model_inlier_->R();
|
||||
Matrix invCov_outlier = model_outlier_->R().transpose() * model_outlier_->R();
|
||||
|
||||
double p_inlier = prior_inlier_ * std::sqrt(invCov_inlier.norm()) * exp( -0.5 * err_wh_inlier.dot(err_wh_inlier) );
|
||||
double p_outlier = prior_outlier_ * std::sqrt(invCov_outlier.norm()) * exp( -0.5 * err_wh_outlier.dot(err_wh_outlier) );
|
||||
|
||||
double sumP = p_inlier + p_outlier;
|
||||
p_inlier /= sumP;
|
||||
p_outlier /= sumP;
|
||||
|
||||
// Bump up near-zero probabilities (as in linerFlow.h)
|
||||
double minP = 0.05; // == 0.1 / 2 indicator variables
|
||||
if (p_inlier < minP || p_outlier < minP){
|
||||
if (p_inlier < minP)
|
||||
p_inlier = minP;
|
||||
if (p_outlier < minP)
|
||||
p_outlier = minP;
|
||||
sumP = p_inlier + p_outlier;
|
||||
p_inlier /= sumP;
|
||||
p_outlier /= sumP;
|
||||
}
|
||||
|
||||
return Vector_(2, p_inlier, p_outlier);
|
||||
}
|
||||
|
||||
/* ************************************************************************* */
|
||||
gtsam::Vector unwhitenedError(const gtsam::Values& x) const {
|
||||
|
||||
bool debug = true;
|
||||
|
||||
const T& p1 = x.at<T>(key1_);
|
||||
const T& p2 = x.at<T>(key2_);
|
||||
|
||||
Matrix H1, H2;
|
||||
|
||||
T hx = p1.between(p2, H1, H2); // h(x)
|
||||
|
||||
return measured_.localCoordinates(hx);
|
||||
}
|
||||
|
||||
/* ************************************************************************* */
|
||||
/** return the measured */
|
||||
const VALUE& measured() const {
|
||||
return measured_;
|
||||
}
|
||||
|
||||
/** number of variables attached to this factor */
|
||||
std::size_t size() const {
|
||||
return 2;
|
||||
}
|
||||
|
||||
virtual size_t dim() const {
|
||||
return model_inlier_->R().rows() + model_inlier_->R().cols();
|
||||
}
|
||||
|
||||
private:
|
||||
|
||||
/** Serialization function */
|
||||
friend class boost::serialization::access;
|
||||
template<class ARCHIVE>
|
||||
void serialize(ARCHIVE & ar, const unsigned int version) {
|
||||
ar & boost::serialization::make_nvp("NonlinearFactor",
|
||||
boost::serialization::base_object<Base>(*this));
|
||||
ar & BOOST_SERIALIZATION_NVP(measured_);
|
||||
}
|
||||
}; // \class BetweenFactorEM
|
||||
|
||||
} /// namespace gtsam
|
||||
|
|
|
@ -1,477 +1,477 @@
|
|||
/**
|
||||
* @file testBetweenFactorEM.cpp
|
||||
* @brief Unit test for the BetweenFactorEM
|
||||
* @author Vadim Indelman
|
||||
*/
|
||||
|
||||
#include <CppUnitLite/TestHarness.h>
|
||||
|
||||
|
||||
#include <gtsam_unstable/slam/BetweenFactorEM.h>
|
||||
#include <gtsam/geometry/Pose2.h>
|
||||
#include <gtsam/nonlinear/Values.h>
|
||||
#include <gtsam/base/LieVector.h>
|
||||
#include <gtsam/base/numericalDerivative.h>
|
||||
|
||||
#include <gtsam/slam/BetweenFactor.h>
|
||||
|
||||
//#include <gtsam/nonlinear/NonlinearOptimizer.h>
|
||||
//#include <gtsam/nonlinear/NonlinearFactorGraph.h>
|
||||
//#include <gtsam/linear/GaussianSequentialSolver.h>
|
||||
|
||||
|
||||
using namespace std;
|
||||
using namespace gtsam;
|
||||
|
||||
|
||||
/* ************************************************************************* */
|
||||
LieVector predictionError(const Pose2& p1, const Pose2& p2, const gtsam::Key& key1, const gtsam::Key& key2, const BetweenFactorEM<gtsam::Pose2>& factor){
|
||||
gtsam::Values values;
|
||||
values.insert(key1, p1);
|
||||
values.insert(key2, p2);
|
||||
// LieVector err = factor.whitenedError(values);
|
||||
// return err;
|
||||
return LieVector::Expmap(factor.whitenedError(values));
|
||||
}
|
||||
|
||||
/* ************************************************************************* */
|
||||
LieVector predictionError_standard(const Pose2& p1, const Pose2& p2, const gtsam::Key& key1, const gtsam::Key& key2, const BetweenFactor<gtsam::Pose2>& factor){
|
||||
gtsam::Values values;
|
||||
values.insert(key1, p1);
|
||||
values.insert(key2, p2);
|
||||
// LieVector err = factor.whitenedError(values);
|
||||
// return err;
|
||||
return LieVector::Expmap(factor.whitenedError(values));
|
||||
}
|
||||
|
||||
/* ************************************************************************* */
|
||||
TEST( BetweenFactorEM, ConstructorAndEquals)
|
||||
{
|
||||
gtsam::Key key1(1);
|
||||
gtsam::Key key2(2);
|
||||
|
||||
gtsam::Pose2 p1(10.0, 15.0, 0.1);
|
||||
gtsam::Pose2 p2(15.0, 15.0, 0.3);
|
||||
gtsam::Pose2 noise(0.5, 0.4, 0.01);
|
||||
gtsam::Pose2 rel_pose_ideal = p1.between(p2);
|
||||
gtsam::Pose2 rel_pose_msr = rel_pose_ideal.compose(noise);
|
||||
|
||||
SharedGaussian model_inlier(noiseModel::Diagonal::Sigmas(gtsam::Vector_(3, 0.5, 0.5, 0.05)));
|
||||
SharedGaussian model_outlier(noiseModel::Diagonal::Sigmas(gtsam::Vector_(3, 5, 5, 1.0)));
|
||||
|
||||
double prior_outlier = 0.5;
|
||||
double prior_inlier = 0.5;
|
||||
|
||||
// Constructor
|
||||
BetweenFactorEM<gtsam::Pose2> f(key1, key2, rel_pose_msr, model_inlier, model_outlier,
|
||||
prior_inlier, prior_outlier);
|
||||
BetweenFactorEM<gtsam::Pose2> g(key1, key2, rel_pose_msr, model_inlier, model_outlier,
|
||||
prior_inlier, prior_outlier);
|
||||
|
||||
// Equals
|
||||
CHECK(assert_equal(f, g, 1e-5));
|
||||
}
|
||||
|
||||
/* ************************************************************************* */
|
||||
TEST( BetweenFactorEM, EvaluateError)
|
||||
{
|
||||
gtsam::Key key1(1);
|
||||
gtsam::Key key2(2);
|
||||
|
||||
// Inlier test
|
||||
gtsam::Pose2 p1(10.0, 15.0, 0.1);
|
||||
gtsam::Pose2 p2(15.0, 15.0, 0.3);
|
||||
gtsam::Pose2 noise(0.5, 0.4, 0.01);
|
||||
gtsam::Pose2 rel_pose_ideal = p1.between(p2);
|
||||
gtsam::Pose2 rel_pose_msr = rel_pose_ideal.compose(noise);
|
||||
|
||||
SharedGaussian model_inlier(noiseModel::Diagonal::Sigmas(gtsam::Vector_(3, 0.5, 0.5, 0.05)));
|
||||
SharedGaussian model_outlier(noiseModel::Diagonal::Sigmas(gtsam::Vector_(3, 50.0, 50.0, 10.0)));
|
||||
|
||||
gtsam::Values values;
|
||||
values.insert(key1, p1);
|
||||
values.insert(key2, p2);
|
||||
|
||||
double prior_outlier = 0.5;
|
||||
double prior_inlier = 0.5;
|
||||
|
||||
BetweenFactorEM<gtsam::Pose2> f(key1, key2, rel_pose_msr, model_inlier, model_outlier,
|
||||
prior_inlier, prior_outlier);
|
||||
|
||||
Vector actual_err_wh = f.whitenedError(values);
|
||||
|
||||
Vector actual_err_wh_inlier = Vector_(3, actual_err_wh[0], actual_err_wh[1], actual_err_wh[2]);
|
||||
Vector actual_err_wh_outlier = Vector_(3, actual_err_wh[3], actual_err_wh[4], actual_err_wh[5]);
|
||||
|
||||
// in case of inlier, inlier-mode whitented error should be dominant
|
||||
CHECK(actual_err_wh_inlier.norm() > 1000.0*actual_err_wh_outlier.norm());
|
||||
|
||||
cout << "Inlier test. norm of actual_err_wh_inlier, actual_err_wh_outlier: "<<actual_err_wh_inlier.norm()<<","<<actual_err_wh_outlier.norm()<<endl;
|
||||
cout<<actual_err_wh[0]<<" "<<actual_err_wh[1]<<" "<<actual_err_wh[2]<<actual_err_wh[3]<<" "<<actual_err_wh[4]<<" "<<actual_err_wh[5]<<endl;
|
||||
|
||||
|
||||
// Outlier test
|
||||
noise = gtsam::Pose2(10.5, 20.4, 2.01);
|
||||
gtsam::Pose2 rel_pose_msr_test2 = rel_pose_ideal.compose(noise);
|
||||
|
||||
BetweenFactorEM<gtsam::Pose2> g(key1, key2, rel_pose_msr_test2, model_inlier, model_outlier,
|
||||
prior_inlier, prior_outlier);
|
||||
|
||||
actual_err_wh = g.whitenedError(values);
|
||||
|
||||
actual_err_wh_inlier = Vector_(3, actual_err_wh[0], actual_err_wh[1], actual_err_wh[2]);
|
||||
actual_err_wh_outlier = Vector_(3, actual_err_wh[3], actual_err_wh[4], actual_err_wh[5]);
|
||||
|
||||
// in case of outlier, outlier-mode whitented error should be dominant
|
||||
CHECK(actual_err_wh_inlier.norm() < 1000.0*actual_err_wh_outlier.norm());
|
||||
|
||||
cout << "Outlier test. norm of actual_err_wh_inlier, actual_err_wh_outlier: "<<actual_err_wh_inlier.norm()<<","<<actual_err_wh_outlier<<endl;
|
||||
cout<<actual_err_wh[0]<<" "<<actual_err_wh[1]<<" "<<actual_err_wh[2]<<actual_err_wh[3]<<" "<<actual_err_wh[4]<<" "<<actual_err_wh[5]<<endl;
|
||||
|
||||
// Compare with standard between factor for the inlier case
|
||||
prior_outlier = 0.0;
|
||||
prior_inlier = 1.0;
|
||||
BetweenFactorEM<gtsam::Pose2> h_EM(key1, key2, rel_pose_msr, model_inlier, model_outlier,
|
||||
prior_inlier, prior_outlier);
|
||||
actual_err_wh = h_EM.whitenedError(values);
|
||||
actual_err_wh_inlier = Vector_(3, actual_err_wh[0], actual_err_wh[1], actual_err_wh[2]);
|
||||
|
||||
BetweenFactor<gtsam::Pose2> h(key1, key2, rel_pose_msr, model_inlier );
|
||||
Vector actual_err_wh_stnd = h.whitenedError(values);
|
||||
|
||||
cout<<"actual_err_wh: "<<actual_err_wh_inlier[0]<<", "<<actual_err_wh_inlier[1]<<", "<<actual_err_wh_inlier[2]<<endl;
|
||||
cout<<"actual_err_wh_stnd: "<<actual_err_wh_stnd[0]<<", "<<actual_err_wh_stnd[1]<<", "<<actual_err_wh_stnd[2]<<endl;
|
||||
|
||||
CHECK( assert_equal(actual_err_wh_inlier, actual_err_wh_stnd, 1e-8));
|
||||
}
|
||||
|
||||
///* ************************************************************************** */
|
||||
TEST (BetweenFactorEM, jacobian ) {
|
||||
|
||||
gtsam::Key key1(1);
|
||||
gtsam::Key key2(2);
|
||||
|
||||
// Inlier test
|
||||
gtsam::Pose2 p1(10.0, 15.0, 0.1);
|
||||
gtsam::Pose2 p2(15.0, 15.0, 0.3);
|
||||
gtsam::Pose2 noise(0.5, 0.4, 0.01);
|
||||
gtsam::Pose2 rel_pose_ideal = p1.between(p2);
|
||||
gtsam::Pose2 rel_pose_msr = rel_pose_ideal.compose(noise);
|
||||
|
||||
SharedGaussian model_inlier(noiseModel::Diagonal::Sigmas(gtsam::Vector_(3, 0.5, 0.5, 0.05)));
|
||||
SharedGaussian model_outlier(noiseModel::Diagonal::Sigmas(gtsam::Vector_(3, 50.0, 50.0, 10.0)));
|
||||
|
||||
gtsam::Values values;
|
||||
values.insert(key1, p1);
|
||||
values.insert(key2, p2);
|
||||
|
||||
double prior_outlier = 0.0;
|
||||
double prior_inlier = 1.0;
|
||||
|
||||
BetweenFactorEM<gtsam::Pose2> f(key1, key2, rel_pose_msr, model_inlier, model_outlier,
|
||||
prior_inlier, prior_outlier);
|
||||
|
||||
std::vector<gtsam::Matrix> H_actual(2);
|
||||
Vector actual_err_wh = f.whitenedError(values, H_actual);
|
||||
|
||||
Matrix H1_actual = H_actual[0];
|
||||
Matrix H2_actual = H_actual[1];
|
||||
|
||||
// compare to standard between factor
|
||||
BetweenFactor<gtsam::Pose2> h(key1, key2, rel_pose_msr, model_inlier );
|
||||
Vector actual_err_wh_stnd = h.whitenedError(values);
|
||||
Vector actual_err_wh_inlier = Vector_(3, actual_err_wh[0], actual_err_wh[1], actual_err_wh[2]);
|
||||
CHECK( assert_equal(actual_err_wh_stnd, actual_err_wh_inlier, 1e-8));
|
||||
std::vector<gtsam::Matrix> H_actual_stnd_unwh(2);
|
||||
(void)h.unwhitenedError(values, H_actual_stnd_unwh);
|
||||
Matrix H1_actual_stnd_unwh = H_actual_stnd_unwh[0];
|
||||
Matrix H2_actual_stnd_unwh = H_actual_stnd_unwh[1];
|
||||
Matrix H1_actual_stnd = model_inlier->Whiten(H1_actual_stnd_unwh);
|
||||
Matrix H2_actual_stnd = model_inlier->Whiten(H2_actual_stnd_unwh);
|
||||
// CHECK( assert_equal(H1_actual_stnd, H1_actual, 1e-8));
|
||||
// CHECK( assert_equal(H2_actual_stnd, H2_actual, 1e-8));
|
||||
|
||||
double stepsize = 1.0e-9;
|
||||
Matrix H1_expected = gtsam::numericalDerivative11<LieVector, Pose2>(boost::bind(&predictionError, _1, p2, key1, key2, f), p1, stepsize);
|
||||
Matrix H2_expected = gtsam::numericalDerivative11<LieVector, Pose2>(boost::bind(&predictionError, p1, _1, key1, key2, f), p2, stepsize);
|
||||
|
||||
|
||||
// try to check numerical derivatives of a standard between factor
|
||||
Matrix H1_expected_stnd = gtsam::numericalDerivative11<LieVector, Pose2>(boost::bind(&predictionError_standard, _1, p2, key1, key2, h), p1, stepsize);
|
||||
CHECK( assert_equal(H1_expected_stnd, H1_actual_stnd, 1e-5));
|
||||
|
||||
|
||||
CHECK( assert_equal(H1_expected, H1_actual, 1e-8));
|
||||
CHECK( assert_equal(H2_expected, H2_actual, 1e-8));
|
||||
|
||||
}
|
||||
|
||||
/* ************************************************************************* */
|
||||
TEST( InertialNavFactor, Equals)
|
||||
{
|
||||
// gtsam::Key Pose1(11);
|
||||
// gtsam::Key Pose2(12);
|
||||
// gtsam::Key Vel1(21);
|
||||
// gtsam::Key Vel2(22);
|
||||
// gtsam::Key Bias1(31);
|
||||
//
|
||||
// Vector measurement_acc(Vector_(3,0.1,0.2,0.4));
|
||||
// Vector measurement_gyro(Vector_(3, -0.2, 0.5, 0.03));
|
||||
//
|
||||
// double measurement_dt(0.1);
|
||||
// Vector world_g(Vector_(3, 0.0, 0.0, 9.81));
|
||||
// Vector world_rho(Vector_(3, 0.0, -1.5724e-05, 0.0)); // NED system
|
||||
// gtsam::Vector ECEF_omega_earth(Vector_(3, 0.0, 0.0, 7.292115e-5));
|
||||
// gtsam::Vector world_omega_earth(world_R_ECEF.matrix() * ECEF_omega_earth);
|
||||
//
|
||||
// SharedGaussian model(noiseModel::Isotropic::Sigma(9, 0.1));
|
||||
//
|
||||
// InertialNavFactor<Pose3, LieVector, imuBias::ConstantBias> f(Pose1, Vel1, Bias1, Pose2, Vel2, measurement_acc, measurement_gyro, measurement_dt, world_g, world_rho, world_omega_earth, model);
|
||||
// InertialNavFactor<Pose3, LieVector, imuBias::ConstantBias> g(Pose1, Vel1, Bias1, Pose2, Vel2, measurement_acc, measurement_gyro, measurement_dt, world_g, world_rho, world_omega_earth, model);
|
||||
// CHECK(assert_equal(f, g, 1e-5));
|
||||
}
|
||||
|
||||
/* ************************************************************************* */
|
||||
TEST( InertialNavFactor, Predict)
|
||||
{
|
||||
// gtsam::Key PoseKey1(11);
|
||||
// gtsam::Key PoseKey2(12);
|
||||
// gtsam::Key VelKey1(21);
|
||||
// gtsam::Key VelKey2(22);
|
||||
// gtsam::Key BiasKey1(31);
|
||||
//
|
||||
// double measurement_dt(0.1);
|
||||
// Vector world_g(Vector_(3, 0.0, 0.0, 9.81));
|
||||
// Vector world_rho(Vector_(3, 0.0, -1.5724e-05, 0.0)); // NED system
|
||||
// gtsam::Vector ECEF_omega_earth(Vector_(3, 0.0, 0.0, 7.292115e-5));
|
||||
// gtsam::Vector world_omega_earth(world_R_ECEF.matrix() * ECEF_omega_earth);
|
||||
//
|
||||
// SharedGaussian model(noiseModel::Isotropic::Sigma(9, 0.1));
|
||||
//
|
||||
//
|
||||
// // First test: zero angular motion, some acceleration
|
||||
// Vector measurement_acc(Vector_(3,0.1,0.2,0.3-9.81));
|
||||
// Vector measurement_gyro(Vector_(3, 0.0, 0.0, 0.0));
|
||||
//
|
||||
// InertialNavFactor<Pose3, LieVector, imuBias::ConstantBias> f(PoseKey1, VelKey1, BiasKey1, PoseKey2, VelKey2, measurement_acc, measurement_gyro, measurement_dt, world_g, world_rho, world_omega_earth, model);
|
||||
//
|
||||
// Pose3 Pose1(Rot3(), Point3(2.00, 1.00, 3.00));
|
||||
// LieVector Vel1(3, 0.50, -0.50, 0.40);
|
||||
// imuBias::ConstantBias Bias1;
|
||||
// Pose3 expectedPose2(Rot3(), Point3(2.05, 0.95, 3.04));
|
||||
// LieVector expectedVel2(3, 0.51, -0.48, 0.43);
|
||||
// Pose3 actualPose2;
|
||||
// LieVector actualVel2;
|
||||
// f.predict(Pose1, Vel1, Bias1, actualPose2, actualVel2);
|
||||
//
|
||||
// CHECK(assert_equal(expectedPose2, actualPose2, 1e-5));
|
||||
// CHECK(assert_equal(expectedVel2, actualVel2, 1e-5));
|
||||
}
|
||||
|
||||
/* ************************************************************************* */
|
||||
TEST( InertialNavFactor, ErrorPosVel)
|
||||
{
|
||||
// gtsam::Key PoseKey1(11);
|
||||
// gtsam::Key PoseKey2(12);
|
||||
// gtsam::Key VelKey1(21);
|
||||
// gtsam::Key VelKey2(22);
|
||||
// gtsam::Key BiasKey1(31);
|
||||
//
|
||||
// double measurement_dt(0.1);
|
||||
// Vector world_g(Vector_(3, 0.0, 0.0, 9.81));
|
||||
// Vector world_rho(Vector_(3, 0.0, -1.5724e-05, 0.0)); // NED system
|
||||
// gtsam::Vector ECEF_omega_earth(Vector_(3, 0.0, 0.0, 7.292115e-5));
|
||||
// gtsam::Vector world_omega_earth(world_R_ECEF.matrix() * ECEF_omega_earth);
|
||||
//
|
||||
// SharedGaussian model(noiseModel::Isotropic::Sigma(9, 0.1));
|
||||
//
|
||||
//
|
||||
// // First test: zero angular motion, some acceleration
|
||||
// Vector measurement_acc(Vector_(3,0.1,0.2,0.3-9.81));
|
||||
// Vector measurement_gyro(Vector_(3, 0.0, 0.0, 0.0));
|
||||
//
|
||||
// InertialNavFactor<Pose3, LieVector, imuBias::ConstantBias> f(PoseKey1, VelKey1, BiasKey1, PoseKey2, VelKey2, measurement_acc, measurement_gyro, measurement_dt, world_g, world_rho, world_omega_earth, model);
|
||||
//
|
||||
// Pose3 Pose1(Rot3(), Point3(2.00, 1.00, 3.00));
|
||||
// Pose3 Pose2(Rot3(), Point3(2.05, 0.95, 3.04));
|
||||
// LieVector Vel1(3, 0.50, -0.50, 0.40);
|
||||
// LieVector Vel2(3, 0.51, -0.48, 0.43);
|
||||
// imuBias::ConstantBias Bias1;
|
||||
//
|
||||
// Vector ActualErr(f.evaluateError(Pose1, Vel1, Bias1, Pose2, Vel2));
|
||||
// Vector ExpectedErr(zero(9));
|
||||
//
|
||||
// CHECK(assert_equal(ExpectedErr, ActualErr, 1e-5));
|
||||
}
|
||||
|
||||
/* ************************************************************************* */
|
||||
TEST( InertialNavFactor, ErrorRot)
|
||||
{
|
||||
// gtsam::Key PoseKey1(11);
|
||||
// gtsam::Key PoseKey2(12);
|
||||
// gtsam::Key VelKey1(21);
|
||||
// gtsam::Key VelKey2(22);
|
||||
// gtsam::Key BiasKey1(31);
|
||||
//
|
||||
// double measurement_dt(0.1);
|
||||
// Vector world_g(Vector_(3, 0.0, 0.0, 9.81));
|
||||
// Vector world_rho(Vector_(3, 0.0, -1.5724e-05, 0.0)); // NED system
|
||||
// gtsam::Vector ECEF_omega_earth(Vector_(3, 0.0, 0.0, 7.292115e-5));
|
||||
// gtsam::Vector world_omega_earth(world_R_ECEF.matrix() * ECEF_omega_earth);
|
||||
//
|
||||
// SharedGaussian model(noiseModel::Isotropic::Sigma(9, 0.1));
|
||||
//
|
||||
// // Second test: zero angular motion, some acceleration
|
||||
// Vector measurement_acc(Vector_(3,0.0,0.0,0.0-9.81));
|
||||
// Vector measurement_gyro(Vector_(3, 0.1, 0.2, 0.3));
|
||||
//
|
||||
// InertialNavFactor<Pose3, LieVector, imuBias::ConstantBias> f(PoseKey1, VelKey1, BiasKey1, PoseKey2, VelKey2, measurement_acc, measurement_gyro, measurement_dt, world_g, world_rho, world_omega_earth, model);
|
||||
//
|
||||
// Pose3 Pose1(Rot3(), Point3(2.0,1.0,3.0));
|
||||
// Pose3 Pose2(Rot3::Expmap(measurement_gyro*measurement_dt), Point3(2.0,1.0,3.0));
|
||||
// LieVector Vel1(3,0.0,0.0,0.0);
|
||||
// LieVector Vel2(3,0.0,0.0,0.0);
|
||||
// imuBias::ConstantBias Bias1;
|
||||
//
|
||||
// Vector ActualErr(f.evaluateError(Pose1, Vel1, Bias1, Pose2, Vel2));
|
||||
// Vector ExpectedErr(zero(9));
|
||||
//
|
||||
// CHECK(assert_equal(ExpectedErr, ActualErr, 1e-5));
|
||||
}
|
||||
|
||||
/* ************************************************************************* */
|
||||
TEST( InertialNavFactor, ErrorRotPosVel)
|
||||
{
|
||||
// gtsam::Key PoseKey1(11);
|
||||
// gtsam::Key PoseKey2(12);
|
||||
// gtsam::Key VelKey1(21);
|
||||
// gtsam::Key VelKey2(22);
|
||||
// gtsam::Key BiasKey1(31);
|
||||
//
|
||||
// double measurement_dt(0.1);
|
||||
// Vector world_g(Vector_(3, 0.0, 0.0, 9.81));
|
||||
// Vector world_rho(Vector_(3, 0.0, -1.5724e-05, 0.0)); // NED system
|
||||
// gtsam::Vector ECEF_omega_earth(Vector_(3, 0.0, 0.0, 7.292115e-5));
|
||||
// gtsam::Vector world_omega_earth(world_R_ECEF.matrix() * ECEF_omega_earth);
|
||||
//
|
||||
// SharedGaussian model(noiseModel::Isotropic::Sigma(9, 0.1));
|
||||
//
|
||||
// // Second test: zero angular motion, some acceleration - generated in matlab
|
||||
// Vector measurement_acc(Vector_(3, 6.501390843381716, -6.763926150509185, -2.300389940090343));
|
||||
// Vector measurement_gyro(Vector_(3, 0.1, 0.2, 0.3));
|
||||
//
|
||||
// InertialNavFactor<Pose3, LieVector, imuBias::ConstantBias> f(PoseKey1, VelKey1, BiasKey1, PoseKey2, VelKey2, measurement_acc, measurement_gyro, measurement_dt, world_g, world_rho, world_omega_earth, model);
|
||||
//
|
||||
// Rot3 R1(0.487316618, 0.125253866, 0.86419557,
|
||||
// 0.580273724, 0.693095498, -0.427669306,
|
||||
// -0.652537293, 0.709880342, 0.265075427);
|
||||
// Point3 t1(2.0,1.0,3.0);
|
||||
// Pose3 Pose1(R1, t1);
|
||||
// LieVector Vel1(3,0.5,-0.5,0.4);
|
||||
// Rot3 R2(0.473618898, 0.119523052, 0.872582019,
|
||||
// 0.609241153, 0.67099888, -0.422594037,
|
||||
// -0.636011287, 0.731761397, 0.244979388);
|
||||
// Point3 t2(2.052670960415706, 0.977252139079380, 2.942482135362800);
|
||||
// Pose3 Pose2(R2, t2);
|
||||
// LieVector Vel2(3,0.510000000000000, -0.480000000000000, 0.430000000000000);
|
||||
// imuBias::ConstantBias Bias1;
|
||||
//
|
||||
// Vector ActualErr(f.evaluateError(Pose1, Vel1, Bias1, Pose2, Vel2));
|
||||
// Vector ExpectedErr(zero(9));
|
||||
//
|
||||
// CHECK(assert_equal(ExpectedErr, ActualErr, 1e-5));
|
||||
}
|
||||
|
||||
|
||||
/* ************************************************************************* */
|
||||
TEST (InertialNavFactor, Jacobian ) {
|
||||
|
||||
// gtsam::Key PoseKey1(11);
|
||||
// gtsam::Key PoseKey2(12);
|
||||
// gtsam::Key VelKey1(21);
|
||||
// gtsam::Key VelKey2(22);
|
||||
// gtsam::Key BiasKey1(31);
|
||||
//
|
||||
// double measurement_dt(0.01);
|
||||
// Vector world_g(Vector_(3, 0.0, 0.0, 9.81));
|
||||
// Vector world_rho(Vector_(3, 0.0, -1.5724e-05, 0.0)); // NED system
|
||||
// gtsam::Vector ECEF_omega_earth(Vector_(3, 0.0, 0.0, 7.292115e-5));
|
||||
// gtsam::Vector world_omega_earth(world_R_ECEF.matrix() * ECEF_omega_earth);
|
||||
//
|
||||
// SharedGaussian model(noiseModel::Isotropic::Sigma(9, 0.1));
|
||||
//
|
||||
// Vector measurement_acc(Vector_(3, 6.501390843381716, -6.763926150509185, -2.300389940090343));
|
||||
// Vector measurement_gyro(Vector_(3, 3.14, 3.14/2, -3.14));
|
||||
//
|
||||
// InertialNavFactor<Pose3, LieVector, imuBias::ConstantBias> factor(PoseKey1, VelKey1, BiasKey1, PoseKey2, VelKey2, measurement_acc, measurement_gyro, measurement_dt, world_g, world_rho, world_omega_earth, model);
|
||||
//
|
||||
// Rot3 R1(0.487316618, 0.125253866, 0.86419557,
|
||||
// 0.580273724, 0.693095498, -0.427669306,
|
||||
// -0.652537293, 0.709880342, 0.265075427);
|
||||
// Point3 t1(2.0,1.0,3.0);
|
||||
// Pose3 Pose1(R1, t1);
|
||||
// LieVector Vel1(3,0.5,-0.5,0.4);
|
||||
// Rot3 R2(0.473618898, 0.119523052, 0.872582019,
|
||||
// 0.609241153, 0.67099888, -0.422594037,
|
||||
// -0.636011287, 0.731761397, 0.244979388);
|
||||
// Point3 t2(2.052670960415706, 0.977252139079380, 2.942482135362800);
|
||||
// Pose3 Pose2(R2, t2);
|
||||
// LieVector Vel2(3,0.510000000000000, -0.480000000000000, 0.430000000000000);
|
||||
// imuBias::ConstantBias Bias1;
|
||||
//
|
||||
// Matrix H1_actual, H2_actual, H3_actual, H4_actual, H5_actual;
|
||||
//
|
||||
// Vector ActualErr(factor.evaluateError(Pose1, Vel1, Bias1, Pose2, Vel2, H1_actual, H2_actual, H3_actual, H4_actual, H5_actual));
|
||||
//
|
||||
// // Checking for Pose part in the jacobians
|
||||
// // ******
|
||||
// Matrix H1_actualPose(H1_actual.block(0,0,6,H1_actual.cols()));
|
||||
// Matrix H2_actualPose(H2_actual.block(0,0,6,H2_actual.cols()));
|
||||
// Matrix H3_actualPose(H3_actual.block(0,0,6,H3_actual.cols()));
|
||||
// Matrix H4_actualPose(H4_actual.block(0,0,6,H4_actual.cols()));
|
||||
// Matrix H5_actualPose(H5_actual.block(0,0,6,H5_actual.cols()));
|
||||
//
|
||||
// // Calculate the Jacobian matrices H1 until H5 using the numerical derivative function
|
||||
// gtsam::Matrix H1_expectedPose, H2_expectedPose, H3_expectedPose, H4_expectedPose, H5_expectedPose;
|
||||
// H1_expectedPose = gtsam::numericalDerivative11<Pose3, Pose3>(boost::bind(&predictionErrorPose, _1, Vel1, Bias1, Pose2, Vel2, factor), Pose1);
|
||||
// H2_expectedPose = gtsam::numericalDerivative11<Pose3, LieVector>(boost::bind(&predictionErrorPose, Pose1, _1, Bias1, Pose2, Vel2, factor), Vel1);
|
||||
// H3_expectedPose = gtsam::numericalDerivative11<Pose3, imuBias::ConstantBias>(boost::bind(&predictionErrorPose, Pose1, Vel1, _1, Pose2, Vel2, factor), Bias1);
|
||||
// H4_expectedPose = gtsam::numericalDerivative11<Pose3, Pose3>(boost::bind(&predictionErrorPose, Pose1, Vel1, Bias1, _1, Vel2, factor), Pose2);
|
||||
// H5_expectedPose = gtsam::numericalDerivative11<Pose3, LieVector>(boost::bind(&predictionErrorPose, Pose1, Vel1, Bias1, Pose2, _1, factor), Vel2);
|
||||
//
|
||||
// // Verify they are equal for this choice of state
|
||||
// CHECK( gtsam::assert_equal(H1_expectedPose, H1_actualPose, 1e-6));
|
||||
// CHECK( gtsam::assert_equal(H2_expectedPose, H2_actualPose, 1e-6));
|
||||
// CHECK( gtsam::assert_equal(H3_expectedPose, H3_actualPose, 1e-6));
|
||||
// CHECK( gtsam::assert_equal(H4_expectedPose, H4_actualPose, 1e-6));
|
||||
// CHECK( gtsam::assert_equal(H5_expectedPose, H5_actualPose, 1e-6));
|
||||
//
|
||||
// // Checking for Vel part in the jacobians
|
||||
// // ******
|
||||
// Matrix H1_actualVel(H1_actual.block(6,0,3,H1_actual.cols()));
|
||||
// Matrix H2_actualVel(H2_actual.block(6,0,3,H2_actual.cols()));
|
||||
// Matrix H3_actualVel(H3_actual.block(6,0,3,H3_actual.cols()));
|
||||
// Matrix H4_actualVel(H4_actual.block(6,0,3,H4_actual.cols()));
|
||||
// Matrix H5_actualVel(H5_actual.block(6,0,3,H5_actual.cols()));
|
||||
//
|
||||
// // Calculate the Jacobian matrices H1 until H5 using the numerical derivative function
|
||||
// gtsam::Matrix H1_expectedVel, H2_expectedVel, H3_expectedVel, H4_expectedVel, H5_expectedVel;
|
||||
// H1_expectedVel = gtsam::numericalDerivative11<LieVector, Pose3>(boost::bind(&predictionErrorVel, _1, Vel1, Bias1, Pose2, Vel2, factor), Pose1);
|
||||
// H2_expectedVel = gtsam::numericalDerivative11<LieVector, LieVector>(boost::bind(&predictionErrorVel, Pose1, _1, Bias1, Pose2, Vel2, factor), Vel1);
|
||||
// H3_expectedVel = gtsam::numericalDerivative11<LieVector, imuBias::ConstantBias>(boost::bind(&predictionErrorVel, Pose1, Vel1, _1, Pose2, Vel2, factor), Bias1);
|
||||
// H4_expectedVel = gtsam::numericalDerivative11<LieVector, Pose3>(boost::bind(&predictionErrorVel, Pose1, Vel1, Bias1, _1, Vel2, factor), Pose2);
|
||||
// H5_expectedVel = gtsam::numericalDerivative11<LieVector, LieVector>(boost::bind(&predictionErrorVel, Pose1, Vel1, Bias1, Pose2, _1, factor), Vel2);
|
||||
//
|
||||
// // Verify they are equal for this choice of state
|
||||
// CHECK( gtsam::assert_equal(H1_expectedVel, H1_actualVel, 1e-6));
|
||||
// CHECK( gtsam::assert_equal(H2_expectedVel, H2_actualVel, 1e-6));
|
||||
// CHECK( gtsam::assert_equal(H3_expectedVel, H3_actualVel, 1e-6));
|
||||
// CHECK( gtsam::assert_equal(H4_expectedVel, H4_actualVel, 1e-6));
|
||||
// CHECK( gtsam::assert_equal(H5_expectedVel, H5_actualVel, 1e-6));
|
||||
}
|
||||
|
||||
|
||||
|
||||
/* ************************************************************************* */
|
||||
int main() { TestResult tr; return TestRegistry::runAllTests(tr);}
|
||||
/* ************************************************************************* */
|
||||
/**
|
||||
* @file testBetweenFactorEM.cpp
|
||||
* @brief Unit test for the BetweenFactorEM
|
||||
* @author Vadim Indelman
|
||||
*/
|
||||
|
||||
#include <CppUnitLite/TestHarness.h>
|
||||
|
||||
|
||||
#include <gtsam_unstable/slam/BetweenFactorEM.h>
|
||||
#include <gtsam/geometry/Pose2.h>
|
||||
#include <gtsam/nonlinear/Values.h>
|
||||
#include <gtsam/base/LieVector.h>
|
||||
#include <gtsam/base/numericalDerivative.h>
|
||||
|
||||
#include <gtsam/slam/BetweenFactor.h>
|
||||
|
||||
//#include <gtsam/nonlinear/NonlinearOptimizer.h>
|
||||
//#include <gtsam/nonlinear/NonlinearFactorGraph.h>
|
||||
//#include <gtsam/linear/GaussianSequentialSolver.h>
|
||||
|
||||
|
||||
using namespace std;
|
||||
using namespace gtsam;
|
||||
|
||||
|
||||
/* ************************************************************************* */
|
||||
LieVector predictionError(const Pose2& p1, const Pose2& p2, const gtsam::Key& key1, const gtsam::Key& key2, const BetweenFactorEM<gtsam::Pose2>& factor){
|
||||
gtsam::Values values;
|
||||
values.insert(key1, p1);
|
||||
values.insert(key2, p2);
|
||||
// LieVector err = factor.whitenedError(values);
|
||||
// return err;
|
||||
return LieVector::Expmap(factor.whitenedError(values));
|
||||
}
|
||||
|
||||
/* ************************************************************************* */
|
||||
LieVector predictionError_standard(const Pose2& p1, const Pose2& p2, const gtsam::Key& key1, const gtsam::Key& key2, const BetweenFactor<gtsam::Pose2>& factor){
|
||||
gtsam::Values values;
|
||||
values.insert(key1, p1);
|
||||
values.insert(key2, p2);
|
||||
// LieVector err = factor.whitenedError(values);
|
||||
// return err;
|
||||
return LieVector::Expmap(factor.whitenedError(values));
|
||||
}
|
||||
|
||||
/* ************************************************************************* */
|
||||
TEST( BetweenFactorEM, ConstructorAndEquals)
|
||||
{
|
||||
gtsam::Key key1(1);
|
||||
gtsam::Key key2(2);
|
||||
|
||||
gtsam::Pose2 p1(10.0, 15.0, 0.1);
|
||||
gtsam::Pose2 p2(15.0, 15.0, 0.3);
|
||||
gtsam::Pose2 noise(0.5, 0.4, 0.01);
|
||||
gtsam::Pose2 rel_pose_ideal = p1.between(p2);
|
||||
gtsam::Pose2 rel_pose_msr = rel_pose_ideal.compose(noise);
|
||||
|
||||
SharedGaussian model_inlier(noiseModel::Diagonal::Sigmas(gtsam::Vector_(3, 0.5, 0.5, 0.05)));
|
||||
SharedGaussian model_outlier(noiseModel::Diagonal::Sigmas(gtsam::Vector_(3, 5, 5, 1.0)));
|
||||
|
||||
double prior_outlier = 0.5;
|
||||
double prior_inlier = 0.5;
|
||||
|
||||
// Constructor
|
||||
BetweenFactorEM<gtsam::Pose2> f(key1, key2, rel_pose_msr, model_inlier, model_outlier,
|
||||
prior_inlier, prior_outlier);
|
||||
BetweenFactorEM<gtsam::Pose2> g(key1, key2, rel_pose_msr, model_inlier, model_outlier,
|
||||
prior_inlier, prior_outlier);
|
||||
|
||||
// Equals
|
||||
CHECK(assert_equal(f, g, 1e-5));
|
||||
}
|
||||
|
||||
/* ************************************************************************* */
|
||||
TEST( BetweenFactorEM, EvaluateError)
|
||||
{
|
||||
gtsam::Key key1(1);
|
||||
gtsam::Key key2(2);
|
||||
|
||||
// Inlier test
|
||||
gtsam::Pose2 p1(10.0, 15.0, 0.1);
|
||||
gtsam::Pose2 p2(15.0, 15.0, 0.3);
|
||||
gtsam::Pose2 noise(0.5, 0.4, 0.01);
|
||||
gtsam::Pose2 rel_pose_ideal = p1.between(p2);
|
||||
gtsam::Pose2 rel_pose_msr = rel_pose_ideal.compose(noise);
|
||||
|
||||
SharedGaussian model_inlier(noiseModel::Diagonal::Sigmas(gtsam::Vector_(3, 0.5, 0.5, 0.05)));
|
||||
SharedGaussian model_outlier(noiseModel::Diagonal::Sigmas(gtsam::Vector_(3, 50.0, 50.0, 10.0)));
|
||||
|
||||
gtsam::Values values;
|
||||
values.insert(key1, p1);
|
||||
values.insert(key2, p2);
|
||||
|
||||
double prior_outlier = 0.5;
|
||||
double prior_inlier = 0.5;
|
||||
|
||||
BetweenFactorEM<gtsam::Pose2> f(key1, key2, rel_pose_msr, model_inlier, model_outlier,
|
||||
prior_inlier, prior_outlier);
|
||||
|
||||
Vector actual_err_wh = f.whitenedError(values);
|
||||
|
||||
Vector actual_err_wh_inlier = Vector_(3, actual_err_wh[0], actual_err_wh[1], actual_err_wh[2]);
|
||||
Vector actual_err_wh_outlier = Vector_(3, actual_err_wh[3], actual_err_wh[4], actual_err_wh[5]);
|
||||
|
||||
// in case of inlier, inlier-mode whitented error should be dominant
|
||||
CHECK(actual_err_wh_inlier.norm() > 1000.0*actual_err_wh_outlier.norm());
|
||||
|
||||
cout << "Inlier test. norm of actual_err_wh_inlier, actual_err_wh_outlier: "<<actual_err_wh_inlier.norm()<<","<<actual_err_wh_outlier.norm()<<endl;
|
||||
cout<<actual_err_wh[0]<<" "<<actual_err_wh[1]<<" "<<actual_err_wh[2]<<actual_err_wh[3]<<" "<<actual_err_wh[4]<<" "<<actual_err_wh[5]<<endl;
|
||||
|
||||
|
||||
// Outlier test
|
||||
noise = gtsam::Pose2(10.5, 20.4, 2.01);
|
||||
gtsam::Pose2 rel_pose_msr_test2 = rel_pose_ideal.compose(noise);
|
||||
|
||||
BetweenFactorEM<gtsam::Pose2> g(key1, key2, rel_pose_msr_test2, model_inlier, model_outlier,
|
||||
prior_inlier, prior_outlier);
|
||||
|
||||
actual_err_wh = g.whitenedError(values);
|
||||
|
||||
actual_err_wh_inlier = Vector_(3, actual_err_wh[0], actual_err_wh[1], actual_err_wh[2]);
|
||||
actual_err_wh_outlier = Vector_(3, actual_err_wh[3], actual_err_wh[4], actual_err_wh[5]);
|
||||
|
||||
// in case of outlier, outlier-mode whitented error should be dominant
|
||||
CHECK(actual_err_wh_inlier.norm() < 1000.0*actual_err_wh_outlier.norm());
|
||||
|
||||
cout << "Outlier test. norm of actual_err_wh_inlier, actual_err_wh_outlier: "<<actual_err_wh_inlier.norm()<<","<<actual_err_wh_outlier<<endl;
|
||||
cout<<actual_err_wh[0]<<" "<<actual_err_wh[1]<<" "<<actual_err_wh[2]<<actual_err_wh[3]<<" "<<actual_err_wh[4]<<" "<<actual_err_wh[5]<<endl;
|
||||
|
||||
// Compare with standard between factor for the inlier case
|
||||
prior_outlier = 0.0;
|
||||
prior_inlier = 1.0;
|
||||
BetweenFactorEM<gtsam::Pose2> h_EM(key1, key2, rel_pose_msr, model_inlier, model_outlier,
|
||||
prior_inlier, prior_outlier);
|
||||
actual_err_wh = h_EM.whitenedError(values);
|
||||
actual_err_wh_inlier = Vector_(3, actual_err_wh[0], actual_err_wh[1], actual_err_wh[2]);
|
||||
|
||||
BetweenFactor<gtsam::Pose2> h(key1, key2, rel_pose_msr, model_inlier );
|
||||
Vector actual_err_wh_stnd = h.whitenedError(values);
|
||||
|
||||
cout<<"actual_err_wh: "<<actual_err_wh_inlier[0]<<", "<<actual_err_wh_inlier[1]<<", "<<actual_err_wh_inlier[2]<<endl;
|
||||
cout<<"actual_err_wh_stnd: "<<actual_err_wh_stnd[0]<<", "<<actual_err_wh_stnd[1]<<", "<<actual_err_wh_stnd[2]<<endl;
|
||||
|
||||
CHECK( assert_equal(actual_err_wh_inlier, actual_err_wh_stnd, 1e-8));
|
||||
}
|
||||
|
||||
///* ************************************************************************** */
|
||||
TEST (BetweenFactorEM, jacobian ) {
|
||||
|
||||
gtsam::Key key1(1);
|
||||
gtsam::Key key2(2);
|
||||
|
||||
// Inlier test
|
||||
gtsam::Pose2 p1(10.0, 15.0, 0.1);
|
||||
gtsam::Pose2 p2(15.0, 15.0, 0.3);
|
||||
gtsam::Pose2 noise(0.5, 0.4, 0.01);
|
||||
gtsam::Pose2 rel_pose_ideal = p1.between(p2);
|
||||
gtsam::Pose2 rel_pose_msr = rel_pose_ideal.compose(noise);
|
||||
|
||||
SharedGaussian model_inlier(noiseModel::Diagonal::Sigmas(gtsam::Vector_(3, 0.5, 0.5, 0.05)));
|
||||
SharedGaussian model_outlier(noiseModel::Diagonal::Sigmas(gtsam::Vector_(3, 50.0, 50.0, 10.0)));
|
||||
|
||||
gtsam::Values values;
|
||||
values.insert(key1, p1);
|
||||
values.insert(key2, p2);
|
||||
|
||||
double prior_outlier = 0.0;
|
||||
double prior_inlier = 1.0;
|
||||
|
||||
BetweenFactorEM<gtsam::Pose2> f(key1, key2, rel_pose_msr, model_inlier, model_outlier,
|
||||
prior_inlier, prior_outlier);
|
||||
|
||||
std::vector<gtsam::Matrix> H_actual(2);
|
||||
Vector actual_err_wh = f.whitenedError(values, H_actual);
|
||||
|
||||
Matrix H1_actual = H_actual[0];
|
||||
Matrix H2_actual = H_actual[1];
|
||||
|
||||
// compare to standard between factor
|
||||
BetweenFactor<gtsam::Pose2> h(key1, key2, rel_pose_msr, model_inlier );
|
||||
Vector actual_err_wh_stnd = h.whitenedError(values);
|
||||
Vector actual_err_wh_inlier = Vector_(3, actual_err_wh[0], actual_err_wh[1], actual_err_wh[2]);
|
||||
CHECK( assert_equal(actual_err_wh_stnd, actual_err_wh_inlier, 1e-8));
|
||||
std::vector<gtsam::Matrix> H_actual_stnd_unwh(2);
|
||||
(void)h.unwhitenedError(values, H_actual_stnd_unwh);
|
||||
Matrix H1_actual_stnd_unwh = H_actual_stnd_unwh[0];
|
||||
Matrix H2_actual_stnd_unwh = H_actual_stnd_unwh[1];
|
||||
Matrix H1_actual_stnd = model_inlier->Whiten(H1_actual_stnd_unwh);
|
||||
Matrix H2_actual_stnd = model_inlier->Whiten(H2_actual_stnd_unwh);
|
||||
// CHECK( assert_equal(H1_actual_stnd, H1_actual, 1e-8));
|
||||
// CHECK( assert_equal(H2_actual_stnd, H2_actual, 1e-8));
|
||||
|
||||
double stepsize = 1.0e-9;
|
||||
Matrix H1_expected = gtsam::numericalDerivative11<LieVector, Pose2>(boost::bind(&predictionError, _1, p2, key1, key2, f), p1, stepsize);
|
||||
Matrix H2_expected = gtsam::numericalDerivative11<LieVector, Pose2>(boost::bind(&predictionError, p1, _1, key1, key2, f), p2, stepsize);
|
||||
|
||||
|
||||
// try to check numerical derivatives of a standard between factor
|
||||
Matrix H1_expected_stnd = gtsam::numericalDerivative11<LieVector, Pose2>(boost::bind(&predictionError_standard, _1, p2, key1, key2, h), p1, stepsize);
|
||||
CHECK( assert_equal(H1_expected_stnd, H1_actual_stnd, 1e-5));
|
||||
|
||||
|
||||
CHECK( assert_equal(H1_expected, H1_actual, 1e-8));
|
||||
CHECK( assert_equal(H2_expected, H2_actual, 1e-8));
|
||||
|
||||
}
|
||||
|
||||
/* ************************************************************************* */
|
||||
TEST( InertialNavFactor, Equals)
|
||||
{
|
||||
// gtsam::Key Pose1(11);
|
||||
// gtsam::Key Pose2(12);
|
||||
// gtsam::Key Vel1(21);
|
||||
// gtsam::Key Vel2(22);
|
||||
// gtsam::Key Bias1(31);
|
||||
//
|
||||
// Vector measurement_acc(Vector_(3,0.1,0.2,0.4));
|
||||
// Vector measurement_gyro(Vector_(3, -0.2, 0.5, 0.03));
|
||||
//
|
||||
// double measurement_dt(0.1);
|
||||
// Vector world_g(Vector_(3, 0.0, 0.0, 9.81));
|
||||
// Vector world_rho(Vector_(3, 0.0, -1.5724e-05, 0.0)); // NED system
|
||||
// gtsam::Vector ECEF_omega_earth(Vector_(3, 0.0, 0.0, 7.292115e-5));
|
||||
// gtsam::Vector world_omega_earth(world_R_ECEF.matrix() * ECEF_omega_earth);
|
||||
//
|
||||
// SharedGaussian model(noiseModel::Isotropic::Sigma(9, 0.1));
|
||||
//
|
||||
// InertialNavFactor<Pose3, LieVector, imuBias::ConstantBias> f(Pose1, Vel1, Bias1, Pose2, Vel2, measurement_acc, measurement_gyro, measurement_dt, world_g, world_rho, world_omega_earth, model);
|
||||
// InertialNavFactor<Pose3, LieVector, imuBias::ConstantBias> g(Pose1, Vel1, Bias1, Pose2, Vel2, measurement_acc, measurement_gyro, measurement_dt, world_g, world_rho, world_omega_earth, model);
|
||||
// CHECK(assert_equal(f, g, 1e-5));
|
||||
}
|
||||
|
||||
/* ************************************************************************* */
|
||||
TEST( InertialNavFactor, Predict)
|
||||
{
|
||||
// gtsam::Key PoseKey1(11);
|
||||
// gtsam::Key PoseKey2(12);
|
||||
// gtsam::Key VelKey1(21);
|
||||
// gtsam::Key VelKey2(22);
|
||||
// gtsam::Key BiasKey1(31);
|
||||
//
|
||||
// double measurement_dt(0.1);
|
||||
// Vector world_g(Vector_(3, 0.0, 0.0, 9.81));
|
||||
// Vector world_rho(Vector_(3, 0.0, -1.5724e-05, 0.0)); // NED system
|
||||
// gtsam::Vector ECEF_omega_earth(Vector_(3, 0.0, 0.0, 7.292115e-5));
|
||||
// gtsam::Vector world_omega_earth(world_R_ECEF.matrix() * ECEF_omega_earth);
|
||||
//
|
||||
// SharedGaussian model(noiseModel::Isotropic::Sigma(9, 0.1));
|
||||
//
|
||||
//
|
||||
// // First test: zero angular motion, some acceleration
|
||||
// Vector measurement_acc(Vector_(3,0.1,0.2,0.3-9.81));
|
||||
// Vector measurement_gyro(Vector_(3, 0.0, 0.0, 0.0));
|
||||
//
|
||||
// InertialNavFactor<Pose3, LieVector, imuBias::ConstantBias> f(PoseKey1, VelKey1, BiasKey1, PoseKey2, VelKey2, measurement_acc, measurement_gyro, measurement_dt, world_g, world_rho, world_omega_earth, model);
|
||||
//
|
||||
// Pose3 Pose1(Rot3(), Point3(2.00, 1.00, 3.00));
|
||||
// LieVector Vel1(3, 0.50, -0.50, 0.40);
|
||||
// imuBias::ConstantBias Bias1;
|
||||
// Pose3 expectedPose2(Rot3(), Point3(2.05, 0.95, 3.04));
|
||||
// LieVector expectedVel2(3, 0.51, -0.48, 0.43);
|
||||
// Pose3 actualPose2;
|
||||
// LieVector actualVel2;
|
||||
// f.predict(Pose1, Vel1, Bias1, actualPose2, actualVel2);
|
||||
//
|
||||
// CHECK(assert_equal(expectedPose2, actualPose2, 1e-5));
|
||||
// CHECK(assert_equal(expectedVel2, actualVel2, 1e-5));
|
||||
}
|
||||
|
||||
/* ************************************************************************* */
|
||||
TEST( InertialNavFactor, ErrorPosVel)
|
||||
{
|
||||
// gtsam::Key PoseKey1(11);
|
||||
// gtsam::Key PoseKey2(12);
|
||||
// gtsam::Key VelKey1(21);
|
||||
// gtsam::Key VelKey2(22);
|
||||
// gtsam::Key BiasKey1(31);
|
||||
//
|
||||
// double measurement_dt(0.1);
|
||||
// Vector world_g(Vector_(3, 0.0, 0.0, 9.81));
|
||||
// Vector world_rho(Vector_(3, 0.0, -1.5724e-05, 0.0)); // NED system
|
||||
// gtsam::Vector ECEF_omega_earth(Vector_(3, 0.0, 0.0, 7.292115e-5));
|
||||
// gtsam::Vector world_omega_earth(world_R_ECEF.matrix() * ECEF_omega_earth);
|
||||
//
|
||||
// SharedGaussian model(noiseModel::Isotropic::Sigma(9, 0.1));
|
||||
//
|
||||
//
|
||||
// // First test: zero angular motion, some acceleration
|
||||
// Vector measurement_acc(Vector_(3,0.1,0.2,0.3-9.81));
|
||||
// Vector measurement_gyro(Vector_(3, 0.0, 0.0, 0.0));
|
||||
//
|
||||
// InertialNavFactor<Pose3, LieVector, imuBias::ConstantBias> f(PoseKey1, VelKey1, BiasKey1, PoseKey2, VelKey2, measurement_acc, measurement_gyro, measurement_dt, world_g, world_rho, world_omega_earth, model);
|
||||
//
|
||||
// Pose3 Pose1(Rot3(), Point3(2.00, 1.00, 3.00));
|
||||
// Pose3 Pose2(Rot3(), Point3(2.05, 0.95, 3.04));
|
||||
// LieVector Vel1(3, 0.50, -0.50, 0.40);
|
||||
// LieVector Vel2(3, 0.51, -0.48, 0.43);
|
||||
// imuBias::ConstantBias Bias1;
|
||||
//
|
||||
// Vector ActualErr(f.evaluateError(Pose1, Vel1, Bias1, Pose2, Vel2));
|
||||
// Vector ExpectedErr(zero(9));
|
||||
//
|
||||
// CHECK(assert_equal(ExpectedErr, ActualErr, 1e-5));
|
||||
}
|
||||
|
||||
/* ************************************************************************* */
|
||||
TEST( InertialNavFactor, ErrorRot)
|
||||
{
|
||||
// gtsam::Key PoseKey1(11);
|
||||
// gtsam::Key PoseKey2(12);
|
||||
// gtsam::Key VelKey1(21);
|
||||
// gtsam::Key VelKey2(22);
|
||||
// gtsam::Key BiasKey1(31);
|
||||
//
|
||||
// double measurement_dt(0.1);
|
||||
// Vector world_g(Vector_(3, 0.0, 0.0, 9.81));
|
||||
// Vector world_rho(Vector_(3, 0.0, -1.5724e-05, 0.0)); // NED system
|
||||
// gtsam::Vector ECEF_omega_earth(Vector_(3, 0.0, 0.0, 7.292115e-5));
|
||||
// gtsam::Vector world_omega_earth(world_R_ECEF.matrix() * ECEF_omega_earth);
|
||||
//
|
||||
// SharedGaussian model(noiseModel::Isotropic::Sigma(9, 0.1));
|
||||
//
|
||||
// // Second test: zero angular motion, some acceleration
|
||||
// Vector measurement_acc(Vector_(3,0.0,0.0,0.0-9.81));
|
||||
// Vector measurement_gyro(Vector_(3, 0.1, 0.2, 0.3));
|
||||
//
|
||||
// InertialNavFactor<Pose3, LieVector, imuBias::ConstantBias> f(PoseKey1, VelKey1, BiasKey1, PoseKey2, VelKey2, measurement_acc, measurement_gyro, measurement_dt, world_g, world_rho, world_omega_earth, model);
|
||||
//
|
||||
// Pose3 Pose1(Rot3(), Point3(2.0,1.0,3.0));
|
||||
// Pose3 Pose2(Rot3::Expmap(measurement_gyro*measurement_dt), Point3(2.0,1.0,3.0));
|
||||
// LieVector Vel1(3,0.0,0.0,0.0);
|
||||
// LieVector Vel2(3,0.0,0.0,0.0);
|
||||
// imuBias::ConstantBias Bias1;
|
||||
//
|
||||
// Vector ActualErr(f.evaluateError(Pose1, Vel1, Bias1, Pose2, Vel2));
|
||||
// Vector ExpectedErr(zero(9));
|
||||
//
|
||||
// CHECK(assert_equal(ExpectedErr, ActualErr, 1e-5));
|
||||
}
|
||||
|
||||
/* ************************************************************************* */
|
||||
TEST( InertialNavFactor, ErrorRotPosVel)
|
||||
{
|
||||
// gtsam::Key PoseKey1(11);
|
||||
// gtsam::Key PoseKey2(12);
|
||||
// gtsam::Key VelKey1(21);
|
||||
// gtsam::Key VelKey2(22);
|
||||
// gtsam::Key BiasKey1(31);
|
||||
//
|
||||
// double measurement_dt(0.1);
|
||||
// Vector world_g(Vector_(3, 0.0, 0.0, 9.81));
|
||||
// Vector world_rho(Vector_(3, 0.0, -1.5724e-05, 0.0)); // NED system
|
||||
// gtsam::Vector ECEF_omega_earth(Vector_(3, 0.0, 0.0, 7.292115e-5));
|
||||
// gtsam::Vector world_omega_earth(world_R_ECEF.matrix() * ECEF_omega_earth);
|
||||
//
|
||||
// SharedGaussian model(noiseModel::Isotropic::Sigma(9, 0.1));
|
||||
//
|
||||
// // Second test: zero angular motion, some acceleration - generated in matlab
|
||||
// Vector measurement_acc(Vector_(3, 6.501390843381716, -6.763926150509185, -2.300389940090343));
|
||||
// Vector measurement_gyro(Vector_(3, 0.1, 0.2, 0.3));
|
||||
//
|
||||
// InertialNavFactor<Pose3, LieVector, imuBias::ConstantBias> f(PoseKey1, VelKey1, BiasKey1, PoseKey2, VelKey2, measurement_acc, measurement_gyro, measurement_dt, world_g, world_rho, world_omega_earth, model);
|
||||
//
|
||||
// Rot3 R1(0.487316618, 0.125253866, 0.86419557,
|
||||
// 0.580273724, 0.693095498, -0.427669306,
|
||||
// -0.652537293, 0.709880342, 0.265075427);
|
||||
// Point3 t1(2.0,1.0,3.0);
|
||||
// Pose3 Pose1(R1, t1);
|
||||
// LieVector Vel1(3,0.5,-0.5,0.4);
|
||||
// Rot3 R2(0.473618898, 0.119523052, 0.872582019,
|
||||
// 0.609241153, 0.67099888, -0.422594037,
|
||||
// -0.636011287, 0.731761397, 0.244979388);
|
||||
// Point3 t2(2.052670960415706, 0.977252139079380, 2.942482135362800);
|
||||
// Pose3 Pose2(R2, t2);
|
||||
// LieVector Vel2(3,0.510000000000000, -0.480000000000000, 0.430000000000000);
|
||||
// imuBias::ConstantBias Bias1;
|
||||
//
|
||||
// Vector ActualErr(f.evaluateError(Pose1, Vel1, Bias1, Pose2, Vel2));
|
||||
// Vector ExpectedErr(zero(9));
|
||||
//
|
||||
// CHECK(assert_equal(ExpectedErr, ActualErr, 1e-5));
|
||||
}
|
||||
|
||||
|
||||
/* ************************************************************************* */
|
||||
TEST (InertialNavFactor, Jacobian ) {
|
||||
|
||||
// gtsam::Key PoseKey1(11);
|
||||
// gtsam::Key PoseKey2(12);
|
||||
// gtsam::Key VelKey1(21);
|
||||
// gtsam::Key VelKey2(22);
|
||||
// gtsam::Key BiasKey1(31);
|
||||
//
|
||||
// double measurement_dt(0.01);
|
||||
// Vector world_g(Vector_(3, 0.0, 0.0, 9.81));
|
||||
// Vector world_rho(Vector_(3, 0.0, -1.5724e-05, 0.0)); // NED system
|
||||
// gtsam::Vector ECEF_omega_earth(Vector_(3, 0.0, 0.0, 7.292115e-5));
|
||||
// gtsam::Vector world_omega_earth(world_R_ECEF.matrix() * ECEF_omega_earth);
|
||||
//
|
||||
// SharedGaussian model(noiseModel::Isotropic::Sigma(9, 0.1));
|
||||
//
|
||||
// Vector measurement_acc(Vector_(3, 6.501390843381716, -6.763926150509185, -2.300389940090343));
|
||||
// Vector measurement_gyro(Vector_(3, 3.14, 3.14/2, -3.14));
|
||||
//
|
||||
// InertialNavFactor<Pose3, LieVector, imuBias::ConstantBias> factor(PoseKey1, VelKey1, BiasKey1, PoseKey2, VelKey2, measurement_acc, measurement_gyro, measurement_dt, world_g, world_rho, world_omega_earth, model);
|
||||
//
|
||||
// Rot3 R1(0.487316618, 0.125253866, 0.86419557,
|
||||
// 0.580273724, 0.693095498, -0.427669306,
|
||||
// -0.652537293, 0.709880342, 0.265075427);
|
||||
// Point3 t1(2.0,1.0,3.0);
|
||||
// Pose3 Pose1(R1, t1);
|
||||
// LieVector Vel1(3,0.5,-0.5,0.4);
|
||||
// Rot3 R2(0.473618898, 0.119523052, 0.872582019,
|
||||
// 0.609241153, 0.67099888, -0.422594037,
|
||||
// -0.636011287, 0.731761397, 0.244979388);
|
||||
// Point3 t2(2.052670960415706, 0.977252139079380, 2.942482135362800);
|
||||
// Pose3 Pose2(R2, t2);
|
||||
// LieVector Vel2(3,0.510000000000000, -0.480000000000000, 0.430000000000000);
|
||||
// imuBias::ConstantBias Bias1;
|
||||
//
|
||||
// Matrix H1_actual, H2_actual, H3_actual, H4_actual, H5_actual;
|
||||
//
|
||||
// Vector ActualErr(factor.evaluateError(Pose1, Vel1, Bias1, Pose2, Vel2, H1_actual, H2_actual, H3_actual, H4_actual, H5_actual));
|
||||
//
|
||||
// // Checking for Pose part in the jacobians
|
||||
// // ******
|
||||
// Matrix H1_actualPose(H1_actual.block(0,0,6,H1_actual.cols()));
|
||||
// Matrix H2_actualPose(H2_actual.block(0,0,6,H2_actual.cols()));
|
||||
// Matrix H3_actualPose(H3_actual.block(0,0,6,H3_actual.cols()));
|
||||
// Matrix H4_actualPose(H4_actual.block(0,0,6,H4_actual.cols()));
|
||||
// Matrix H5_actualPose(H5_actual.block(0,0,6,H5_actual.cols()));
|
||||
//
|
||||
// // Calculate the Jacobian matrices H1 until H5 using the numerical derivative function
|
||||
// gtsam::Matrix H1_expectedPose, H2_expectedPose, H3_expectedPose, H4_expectedPose, H5_expectedPose;
|
||||
// H1_expectedPose = gtsam::numericalDerivative11<Pose3, Pose3>(boost::bind(&predictionErrorPose, _1, Vel1, Bias1, Pose2, Vel2, factor), Pose1);
|
||||
// H2_expectedPose = gtsam::numericalDerivative11<Pose3, LieVector>(boost::bind(&predictionErrorPose, Pose1, _1, Bias1, Pose2, Vel2, factor), Vel1);
|
||||
// H3_expectedPose = gtsam::numericalDerivative11<Pose3, imuBias::ConstantBias>(boost::bind(&predictionErrorPose, Pose1, Vel1, _1, Pose2, Vel2, factor), Bias1);
|
||||
// H4_expectedPose = gtsam::numericalDerivative11<Pose3, Pose3>(boost::bind(&predictionErrorPose, Pose1, Vel1, Bias1, _1, Vel2, factor), Pose2);
|
||||
// H5_expectedPose = gtsam::numericalDerivative11<Pose3, LieVector>(boost::bind(&predictionErrorPose, Pose1, Vel1, Bias1, Pose2, _1, factor), Vel2);
|
||||
//
|
||||
// // Verify they are equal for this choice of state
|
||||
// CHECK( gtsam::assert_equal(H1_expectedPose, H1_actualPose, 1e-6));
|
||||
// CHECK( gtsam::assert_equal(H2_expectedPose, H2_actualPose, 1e-6));
|
||||
// CHECK( gtsam::assert_equal(H3_expectedPose, H3_actualPose, 1e-6));
|
||||
// CHECK( gtsam::assert_equal(H4_expectedPose, H4_actualPose, 1e-6));
|
||||
// CHECK( gtsam::assert_equal(H5_expectedPose, H5_actualPose, 1e-6));
|
||||
//
|
||||
// // Checking for Vel part in the jacobians
|
||||
// // ******
|
||||
// Matrix H1_actualVel(H1_actual.block(6,0,3,H1_actual.cols()));
|
||||
// Matrix H2_actualVel(H2_actual.block(6,0,3,H2_actual.cols()));
|
||||
// Matrix H3_actualVel(H3_actual.block(6,0,3,H3_actual.cols()));
|
||||
// Matrix H4_actualVel(H4_actual.block(6,0,3,H4_actual.cols()));
|
||||
// Matrix H5_actualVel(H5_actual.block(6,0,3,H5_actual.cols()));
|
||||
//
|
||||
// // Calculate the Jacobian matrices H1 until H5 using the numerical derivative function
|
||||
// gtsam::Matrix H1_expectedVel, H2_expectedVel, H3_expectedVel, H4_expectedVel, H5_expectedVel;
|
||||
// H1_expectedVel = gtsam::numericalDerivative11<LieVector, Pose3>(boost::bind(&predictionErrorVel, _1, Vel1, Bias1, Pose2, Vel2, factor), Pose1);
|
||||
// H2_expectedVel = gtsam::numericalDerivative11<LieVector, LieVector>(boost::bind(&predictionErrorVel, Pose1, _1, Bias1, Pose2, Vel2, factor), Vel1);
|
||||
// H3_expectedVel = gtsam::numericalDerivative11<LieVector, imuBias::ConstantBias>(boost::bind(&predictionErrorVel, Pose1, Vel1, _1, Pose2, Vel2, factor), Bias1);
|
||||
// H4_expectedVel = gtsam::numericalDerivative11<LieVector, Pose3>(boost::bind(&predictionErrorVel, Pose1, Vel1, Bias1, _1, Vel2, factor), Pose2);
|
||||
// H5_expectedVel = gtsam::numericalDerivative11<LieVector, LieVector>(boost::bind(&predictionErrorVel, Pose1, Vel1, Bias1, Pose2, _1, factor), Vel2);
|
||||
//
|
||||
// // Verify they are equal for this choice of state
|
||||
// CHECK( gtsam::assert_equal(H1_expectedVel, H1_actualVel, 1e-6));
|
||||
// CHECK( gtsam::assert_equal(H2_expectedVel, H2_actualVel, 1e-6));
|
||||
// CHECK( gtsam::assert_equal(H3_expectedVel, H3_actualVel, 1e-6));
|
||||
// CHECK( gtsam::assert_equal(H4_expectedVel, H4_actualVel, 1e-6));
|
||||
// CHECK( gtsam::assert_equal(H5_expectedVel, H5_actualVel, 1e-6));
|
||||
}
|
||||
|
||||
|
||||
|
||||
/* ************************************************************************* */
|
||||
int main() { TestResult tr; return TestRegistry::runAllTests(tr);}
|
||||
/* ************************************************************************* */
|
||||
|
|
|
@ -173,8 +173,8 @@ TEST( SmartProjectionFactor, noisy ){
|
|||
|
||||
|
||||
/* ************************************************************************* */
|
||||
TEST( SmartProjectionFactor, 3poses ){
|
||||
cout << " ************************ MultiProjectionFactor: 3 cams + 3 landmarks **********************" << endl;
|
||||
TEST( SmartProjectionFactor, 3poses_smart_projection_factor ){
|
||||
cout << " ************************ SmartProjectionFactor: 3 cams + 3 landmarks **********************" << endl;
|
||||
|
||||
Symbol x1('X', 1);
|
||||
Symbol x2('X', 2);
|
||||
|
@ -239,17 +239,19 @@ TEST( SmartProjectionFactor, 3poses ){
|
|||
graph.push_back(PriorFactor<Pose3>(x1, pose1, noisePrior));
|
||||
graph.push_back(PriorFactor<Pose3>(x2, pose2, noisePrior));
|
||||
|
||||
Pose3 noise_pose = Pose3(Rot3::ypr(-M_PI/100, 0., -M_PI/100), gtsam::Point3(0.1,0.1,0.1));
|
||||
// Pose3 noise_pose = Pose3(Rot3::ypr(-M_PI/10, 0., -M_PI/10), gtsam::Point3(0.5,0.1,0.3)); // noise from regular projection factor test below
|
||||
Pose3 noise_pose = Pose3(Rot3::ypr(-M_PI/100, 0., -M_PI/100), gtsam::Point3(0.1,0.1,0.1)); // smaller noise
|
||||
Values values;
|
||||
values.insert(x1, pose1);
|
||||
values.insert(x2, pose2*noise_pose);
|
||||
values.insert(x3, pose3);
|
||||
values.insert(x2, pose2);
|
||||
// initialize third pose with some noise, we expect it to move back to original pose3
|
||||
values.insert(x3, pose3*noise_pose);
|
||||
values.at<Pose3>(x3).print("Smart: Pose3 before optimization: ");
|
||||
|
||||
LevenbergMarquardtParams params;
|
||||
params.verbosityLM = LevenbergMarquardtParams::TRYLAMBDA;
|
||||
params.verbosity = NonlinearOptimizerParams::ERROR;
|
||||
|
||||
|
||||
Values result;
|
||||
gttic_(SmartProjectionFactor);
|
||||
LevenbergMarquardtOptimizer optimizer(graph, values, params);
|
||||
|
@ -257,7 +259,9 @@ TEST( SmartProjectionFactor, 3poses ){
|
|||
gttoc_(SmartProjectionFactor);
|
||||
tictoc_finishedIteration_();
|
||||
|
||||
result.print("results of 3 camera, 3 landmark optimization \n");
|
||||
// result.print("results of 3 camera, 3 landmark optimization \n");
|
||||
result.at<Pose3>(x3).print("Smart: Pose3 after optimization: ");
|
||||
EXPECT(assert_equal(pose3,result.at<Pose3>(x3)));
|
||||
tictoc_print_();
|
||||
|
||||
}
|
||||
|
@ -265,7 +269,7 @@ TEST( SmartProjectionFactor, 3poses ){
|
|||
|
||||
/* ************************************************************************* */
|
||||
TEST( SmartProjectionFactor, 3poses_projection_factor ){
|
||||
cout << " ************************ Normal ProjectionFactor: 3 cams + 3 landmarks **********************" << endl;
|
||||
// cout << " ************************ Normal ProjectionFactor: 3 cams + 3 landmarks **********************" << endl;
|
||||
|
||||
Symbol x1('X', 1);
|
||||
Symbol x2('X', 2);
|
||||
|
@ -287,7 +291,6 @@ TEST( SmartProjectionFactor, 3poses_projection_factor ){
|
|||
|
||||
// create third camera 1 meter above the first camera
|
||||
Pose3 pose3 = pose1 * Pose3(Rot3(), Point3(0,-1,0));
|
||||
pose3.print("Pose3: ");
|
||||
SimpleCamera cam3(pose3, *K);
|
||||
|
||||
// three landmarks ~5 meters infront of camera
|
||||
|
@ -324,6 +327,7 @@ TEST( SmartProjectionFactor, 3poses_projection_factor ){
|
|||
values.insert(L(1), landmark1);
|
||||
values.insert(L(2), landmark2);
|
||||
values.insert(L(3), landmark3);
|
||||
// values.at<Pose3>(x3).print("Pose3 before optimization: ");
|
||||
|
||||
LevenbergMarquardtParams params;
|
||||
// params.verbosityLM = LevenbergMarquardtParams::TRYLAMBDA;
|
||||
|
@ -331,14 +335,15 @@ TEST( SmartProjectionFactor, 3poses_projection_factor ){
|
|||
LevenbergMarquardtOptimizer optimizer(graph, values, params);
|
||||
Values result = optimizer.optimize();
|
||||
|
||||
result.print("Regular Projection Factor: results of 3 camera, 3 landmark optimization \n");
|
||||
// result.at<Pose3>(x3).print("Pose3 after optimization: ");
|
||||
EXPECT(assert_equal(pose3,result.at<Pose3>(x3)));
|
||||
|
||||
}
|
||||
|
||||
|
||||
/* ************************************************************************* */
|
||||
TEST( SmartProjectionFactor, Hessian ){
|
||||
cout << " ************************ Normal ProjectionFactor: Hessian **********************" << endl;
|
||||
cout << " ************************ SmartProjectionFactor: Hessian **********************" << endl;
|
||||
|
||||
Symbol x1('X', 1);
|
||||
Symbol x2('X', 2);
|
||||
|
|
|
@ -1,226 +0,0 @@
|
|||
%close all
|
||||
%clc
|
||||
|
||||
import gtsam.*;
|
||||
|
||||
%% Read metadata and compute relative sensor pose transforms
|
||||
IMU_metadata = importdata('KittiEquivBiasedImu_metadata.txt');
|
||||
IMU_metadata = cell2struct(num2cell(IMU_metadata.data), IMU_metadata.colheaders, 2);
|
||||
IMUinBody = Pose3.Expmap([
|
||||
IMU_metadata.BodyPtx; IMU_metadata.BodyPty; IMU_metadata.BodyPtz;
|
||||
IMU_metadata.BodyPrx; IMU_metadata.BodyPry; IMU_metadata.BodyPrz; ]);
|
||||
if ~IMUinBody.equals(Pose3, 1e-5)
|
||||
error 'Currently only support IMUinBody is identity, i.e. IMU and body frame are the same';
|
||||
end
|
||||
|
||||
VO_metadata = importdata('KittiRelativePose_metadata.txt');
|
||||
VO_metadata = cell2struct(num2cell(VO_metadata.data), VO_metadata.colheaders, 2);
|
||||
VOinBody = Pose3.Expmap([
|
||||
VO_metadata.BodyPtx; VO_metadata.BodyPty; VO_metadata.BodyPtz;
|
||||
VO_metadata.BodyPrx; VO_metadata.BodyPry; VO_metadata.BodyPrz; ]);
|
||||
|
||||
GPS_metadata = importdata('KittiGps_metadata.txt');
|
||||
GPS_metadata = cell2struct(num2cell(GPS_metadata.data), GPS_metadata.colheaders, 2);
|
||||
GPSinBody = Pose3.Expmap([
|
||||
GPS_metadata.BodyPtx; GPS_metadata.BodyPty; GPS_metadata.BodyPtz;
|
||||
GPS_metadata.BodyPrx; GPS_metadata.BodyPry; GPS_metadata.BodyPrz; ]);
|
||||
|
||||
VOinIMU = IMUinBody.inverse().compose(VOinBody);
|
||||
GPSinIMU = IMUinBody.inverse().compose(GPSinBody);
|
||||
|
||||
%% Read data and change coordinate frame of GPS and VO measurements to IMU frame
|
||||
IMU_data = importdata('KittiEquivBiasedImu.txt');
|
||||
IMU_data = cell2struct(num2cell(IMU_data.data), IMU_data.colheaders, 2);
|
||||
imum = cellfun(@(x) x', num2cell([ [IMU_data.accelX]' [IMU_data.accelY]' [IMU_data.accelZ]' [IMU_data.omegaX]' [IMU_data.omegaY]' [IMU_data.omegaZ]' ], 2), 'UniformOutput', false);
|
||||
[IMU_data.acc_omega] = deal(imum{:});
|
||||
IMU_data = rmfield(IMU_data, { 'accelX' 'accelY' 'accelZ' 'omegaX' 'omegaY' 'omegaZ' });
|
||||
clear imum
|
||||
|
||||
VO_data = importdata('KittiRelativePose.txt');
|
||||
VO_data = cell2struct(num2cell(VO_data.data), VO_data.colheaders, 2);
|
||||
% Merge relative pose fields and convert to Pose3
|
||||
logposes = [ [VO_data.dtx]' [VO_data.dty]' [VO_data.dtz]' [VO_data.drx]' [VO_data.dry]' [VO_data.drz]' ];
|
||||
logposes = num2cell(logposes, 2);
|
||||
relposes = arrayfun(@(x) {gtsam.Pose3.Expmap(x{:}')}, logposes);
|
||||
relposes = arrayfun(@(x) {VOinIMU.compose(x{:}).compose(VOinIMU.inverse())}, relposes);
|
||||
[VO_data.RelativePose] = deal(relposes{:});
|
||||
VO_data = rmfield(VO_data, { 'dtx' 'dty' 'dtz' 'drx' 'dry' 'drz' });
|
||||
clear logposes relposes
|
||||
|
||||
GPS_data = importdata('KittiGps.txt');
|
||||
GPS_data = cell2struct(num2cell(GPS_data.data), GPS_data.colheaders, 2);
|
||||
|
||||
%% Set initial conditions for the estimated trajectory
|
||||
disp('TODO: we have GPS so this initialization is not right')
|
||||
currentPoseGlobal = Pose3; % initial pose is the reference frame (navigation frame)
|
||||
currentVelocityGlobal = [0;0;0]; % the vehicle is stationary at the beginning
|
||||
bias_acc = [0;0;0]; % we initialize accelerometer biases to zero
|
||||
bias_omega = [0;0;0]; % we initialize gyro biases to zero
|
||||
|
||||
%% Solver object
|
||||
isamParams = ISAM2Params;
|
||||
isamParams.setRelinearizeSkip(1);
|
||||
isam = gtsam.ISAM2(isamParams);
|
||||
|
||||
%% create nonlinear factor graph
|
||||
factors = NonlinearFactorGraph;
|
||||
values = Values;
|
||||
|
||||
%% Create prior on initial pose, velocity, and biases
|
||||
sigma_init_x = 1.0;
|
||||
sigma_init_v = 1.0;
|
||||
sigma_init_b = 1.0;
|
||||
|
||||
values.insert(symbol('x',0), currentPoseGlobal);
|
||||
values.insert(symbol('v',0), LieVector(currentVelocityGlobal) );
|
||||
values.insert(symbol('b',0), imuBias.ConstantBias(bias_acc,bias_omega) );
|
||||
|
||||
disp('TODO: we have GPS so this initialization is not right')
|
||||
% Prior on initial pose
|
||||
factors.add(PriorFactorPose3(symbol('x',0), ...
|
||||
currentPoseGlobal, noiseModel.Isotropic.Sigma(6, sigma_init_x)));
|
||||
% Prior on initial velocity
|
||||
factors.add(PriorFactorLieVector(symbol('v',0), ...
|
||||
LieVector(currentVelocityGlobal), noiseModel.Isotropic.Sigma(3, sigma_init_v)));
|
||||
% Prior on initial bias
|
||||
factors.add(PriorFactorConstantBias(symbol('b',0), ...
|
||||
imuBias.ConstantBias(bias_acc,bias_omega), noiseModel.Isotropic.Sigma(6, sigma_init_b)));
|
||||
|
||||
%% Main loop:
|
||||
% (1) we read the measurements
|
||||
% (2) we create the corresponding factors in the graph
|
||||
% (3) we solve the graph to obtain and optimal estimate of robot trajectory
|
||||
|
||||
% lastTime = 0; TODO: delete?
|
||||
% lastIndex = 0; TODO: delete?
|
||||
currentSummarizedMeasurement = [];
|
||||
|
||||
% Measurement types:
|
||||
% 1: VO
|
||||
% 2: GPS
|
||||
% 3: IMU
|
||||
times = sortrows( [ ...
|
||||
[VO_data.Time]' 1*ones(length([VO_data.Time]), 1); ...
|
||||
%[GPS_data.Time]' 2*ones(length([GPS_data.Time]), 1); ...
|
||||
[IMU_data.Time]' 3*ones(length([IMU_data.Time]), 1); ...
|
||||
], 1); % this are the time-stamps at which we want to initialize a new node in the graph
|
||||
|
||||
t_previous = 0;
|
||||
poseIndex = 0;
|
||||
for measurementIndex = 1:size(times,1)
|
||||
% At each non=IMU measurement we initialize a new node in the graph
|
||||
currentPoseKey = symbol('x',poseIndex);
|
||||
currentVelKey = symbol('v',poseIndex);
|
||||
currentBiasKey = symbol('b',poseIndex);
|
||||
|
||||
t = times(measurementIndex, 1);
|
||||
type = times(measurementIndex, 2);
|
||||
|
||||
if type == 3
|
||||
% Integrate IMU
|
||||
|
||||
if isempty(currentSummarizedMeasurement)
|
||||
% Create initial empty summarized measurement
|
||||
% we assume that each row of the IMU.txt file has the following structure:
|
||||
% timestamp delta_t acc_x acc_y acc_z omega_x omega_y omega_z
|
||||
currentBias = isam.calculateEstimate(currentBiasKey - 1);
|
||||
currentSummarizedMeasurement = gtsam.ImuFactorPreintegratedMeasurements( ...
|
||||
currentBias, IMU_metadata.AccelerometerSigma.^2 * eye(3), ...
|
||||
IMU_metadata.GyroscopeSigma.^2 * eye(3), IMU_metadata.IntegrationSigma.^2 * eye(3));
|
||||
end
|
||||
|
||||
% Accumulate preintegrated measurement
|
||||
deltaT = IMU_data(index).dt;
|
||||
accMeas = IMU_data(index).acc_omega(1:3);
|
||||
omegaMeas = IMU_data(index).acc_omega(4:6);
|
||||
currentSummarizedMeasurement.integrateMeasurement(accMeas, omegaMeas, deltaT);
|
||||
|
||||
else
|
||||
% Create IMU factor
|
||||
factors.add(ImuFactor( ...
|
||||
currentPoseKey-1, currentVelKey-1, ...
|
||||
currentPoseKey, currentVelKey, ...
|
||||
currentBiasKey-1, currentSummarizedMeasurement, g, cor_v, ...
|
||||
currentSummarizedMeasurement.PreintMeasCov));
|
||||
|
||||
% Reset summarized measurement
|
||||
currentSummarizedMeasurement = [];
|
||||
|
||||
if type == 1
|
||||
% Create VO factor
|
||||
elseif type == 2
|
||||
% Create GPS factor
|
||||
end
|
||||
|
||||
poseIndex = poseIndex + 1;
|
||||
end
|
||||
|
||||
|
||||
% =======================================================================
|
||||
|
||||
|
||||
%% add factor corresponding to GPS measurements (if available at the current time)
|
||||
% % =======================================================================
|
||||
% if isempty( find(GPS_data(:,1) == t ) ) == 0 % it is a GPS measurement
|
||||
% if length( find(GPS_data(:,1)) ) > 1
|
||||
% error('more GPS measurements at the same time stamp: it should be an error')
|
||||
% end
|
||||
%
|
||||
% index = find(GPS_data(:,1) == t ); % the row of the IMU_data matrix that we have to integrate
|
||||
% GPSmeas = GPS_data(index,2:4);
|
||||
%
|
||||
% noiseModelGPS = ???; % noiseModelGPS.Isotropic.Sigma(6, sigma_init_x))
|
||||
%
|
||||
% % add factor
|
||||
% disp('TODO: is the GPS noise right?')
|
||||
% factors.add(PriorFactor???(currentPoseKey, GPSmeas, noiseModelGPS) );
|
||||
% end
|
||||
% =======================================================================
|
||||
|
||||
|
||||
%% add factor corresponding to VO measurements (if available at the current time)
|
||||
% =======================================================================
|
||||
if isempty( find([VO_data.Time] == t, 1) )== 0 % it is a GPS measurement
|
||||
if length( find([VO_data.Time] == t) ) > 1
|
||||
error('more VO measurements at the same time stamp: it should be an error')
|
||||
end
|
||||
|
||||
index = find([VO_data.Time] == t, 1); % the row of the IMU_data matrix that we have to integrate
|
||||
|
||||
VOpose = VO_data(index).RelativePose;
|
||||
noiseModelVO = noiseModel.Diagonal.Sigmas([ IMU_metadata.RotationSigma * [1;1;1]; IMU_metadata.TranslationSigma * [1;1;1] ]);
|
||||
|
||||
% add factor
|
||||
disp('TODO: is the VO noise right?')
|
||||
factors.add(BetweenFactorPose3(lastVOPoseKey, currentPoseKey, VOpose, noiseModelVO));
|
||||
|
||||
lastVOPoseKey = currentPoseKey;
|
||||
end
|
||||
% =======================================================================
|
||||
|
||||
disp('TODO: add values')
|
||||
% values.insert(, initialPose);
|
||||
% values.insert(symbol('v',lastIndex+1), initialVel);
|
||||
|
||||
%% Update solver
|
||||
% =======================================================================
|
||||
isam.update(factors, values);
|
||||
factors = NonlinearFactorGraph;
|
||||
values = Values;
|
||||
|
||||
isam.calculateEstimate(currentPoseKey);
|
||||
% M = isam.marginalCovariance(key_pose);
|
||||
% =======================================================================
|
||||
|
||||
previousPoseKey = currentPoseKey;
|
||||
previousVelKey = currentVelKey;
|
||||
t_previous = t;
|
||||
end
|
||||
|
||||
disp('TODO: display results')
|
||||
% figure(1)
|
||||
% hold on;
|
||||
% plot(positions(1,:), positions(2,:), '-b');
|
||||
% plot3DTrajectory(isam.calculateEstimate, 'g-');
|
||||
% axis equal;
|
||||
% legend('true trajectory', 'traj integrated in body', 'traj integrated in nav')
|
|
@ -0,0 +1,191 @@
|
|||
close all
|
||||
clc
|
||||
|
||||
import gtsam.*;
|
||||
disp('Example of application of ISAM2 for visual-inertial navigation on the KITTI VISION BENCHMARK SUITE (http://www.computervisiononline.com/dataset/kitti-vision-benchmark-suite)')
|
||||
|
||||
%% Read metadata and compute relative sensor pose transforms
|
||||
% IMU metadata
|
||||
disp('-- Reading sensor metadata')
|
||||
IMU_metadata = importdata('KittiEquivBiasedImu_metadata.txt');
|
||||
IMU_metadata = cell2struct(num2cell(IMU_metadata.data), IMU_metadata.colheaders, 2);
|
||||
IMUinBody = Pose3.Expmap([IMU_metadata.BodyPtx; IMU_metadata.BodyPty; IMU_metadata.BodyPtz;
|
||||
IMU_metadata.BodyPrx; IMU_metadata.BodyPry; IMU_metadata.BodyPrz; ]);
|
||||
if ~IMUinBody.equals(Pose3, 1e-5)
|
||||
error 'Currently only support IMUinBody is identity, i.e. IMU and body frame are the same';
|
||||
end
|
||||
|
||||
% VO metadata
|
||||
VO_metadata = importdata('KittiRelativePose_metadata.txt');
|
||||
VO_metadata = cell2struct(num2cell(VO_metadata.data), VO_metadata.colheaders, 2);
|
||||
VOinBody = Pose3.Expmap([VO_metadata.BodyPtx; VO_metadata.BodyPty; VO_metadata.BodyPtz;
|
||||
VO_metadata.BodyPrx; VO_metadata.BodyPry; VO_metadata.BodyPrz; ]);
|
||||
VOinIMU = IMUinBody.inverse().compose(VOinBody);
|
||||
|
||||
% GPS metadata
|
||||
GPS_metadata = importdata('KittiGps_metadata.txt');
|
||||
GPS_metadata = cell2struct(num2cell(GPS_metadata.data), GPS_metadata.colheaders, 2);
|
||||
GPSinBody = Pose3.Expmap([GPS_metadata.BodyPtx; GPS_metadata.BodyPty; GPS_metadata.BodyPtz;
|
||||
GPS_metadata.BodyPrx; GPS_metadata.BodyPry; GPS_metadata.BodyPrz; ]);
|
||||
GPSinIMU = IMUinBody.inverse().compose(GPSinBody);
|
||||
|
||||
%% Read data and change coordinate frame of GPS and VO measurements to IMU frame
|
||||
disp('-- Reading sensor data from file')
|
||||
% IMU data
|
||||
IMU_data = importdata('KittiEquivBiasedImu.txt');
|
||||
IMU_data = cell2struct(num2cell(IMU_data.data), IMU_data.colheaders, 2);
|
||||
imum = cellfun(@(x) x', num2cell([ [IMU_data.accelX]' [IMU_data.accelY]' [IMU_data.accelZ]' [IMU_data.omegaX]' [IMU_data.omegaY]' [IMU_data.omegaZ]' ], 2), 'UniformOutput', false);
|
||||
[IMU_data.acc_omega] = deal(imum{:});
|
||||
%IMU_data = rmfield(IMU_data, { 'accelX' 'accelY' 'accelZ' 'omegaX' 'omegaY' 'omegaZ' });
|
||||
clear imum
|
||||
|
||||
% VO data
|
||||
VO_data = importdata('KittiRelativePose.txt');
|
||||
VO_data = cell2struct(num2cell(VO_data.data), VO_data.colheaders, 2);
|
||||
% Merge relative pose fields and convert to Pose3
|
||||
logposes = [ [VO_data.dtx]' [VO_data.dty]' [VO_data.dtz]' [VO_data.drx]' [VO_data.dry]' [VO_data.drz]' ];
|
||||
logposes = num2cell(logposes, 2);
|
||||
relposes = arrayfun(@(x) {gtsam.Pose3.Expmap(x{:}')}, logposes);
|
||||
relposes = arrayfun(@(x) {VOinIMU.compose(x{:}).compose(VOinIMU.inverse())}, relposes);
|
||||
[VO_data.RelativePose] = deal(relposes{:});
|
||||
VO_data = rmfield(VO_data, { 'dtx' 'dty' 'dtz' 'drx' 'dry' 'drz' });
|
||||
noiseModelVO = noiseModel.Diagonal.Sigmas([ VO_metadata.RotationSigma * [1;1;1]; VO_metadata.TranslationSigma * [1;1;1] ]);
|
||||
clear logposes relposes
|
||||
|
||||
% % % GPS data
|
||||
% % GPS_data = importdata('KittiGps.txt');
|
||||
% % GPS_data = cell2struct(num2cell(GPS_data.data), GPS_data.colheaders, 2);
|
||||
% % % Convert GPS from lat/long to meters
|
||||
% % [ x, y, ~ ] = deg2utm( [GPS_data.Latitude], [GPS_data.Longitude] );
|
||||
% % for i = 1:numel(x)
|
||||
% % GPS_data(i).Position = gtsam.Point3(x(i), y(i), GPS_data(i).Altitude);
|
||||
% % end
|
||||
% % % % Calculate GPS sigma in meters
|
||||
% % % [ xSig, ySig, ~ ] = deg2utm( [GPS_data.Latitude] + [GPS_data.PositionSigma], ...
|
||||
% % % [GPS_data.Longitude] + [GPS_data.PositionSigma]);
|
||||
% % % xSig = xSig - x;
|
||||
% % % ySig = ySig - y;
|
||||
% % %% Start at time of first GPS measurement
|
||||
% % % firstGPSPose = 1;
|
||||
|
||||
%% Get initial conditions for the estimated trajectory
|
||||
% % % currentPoseGlobal = Pose3(Rot3, GPS_data(firstGPSPose).Position); % initial pose is the reference frame (navigation frame)
|
||||
currentPoseGlobal = Pose3;
|
||||
currentVelocityGlobal = LieVector([0;0;0]); % the vehicle is stationary at the beginning
|
||||
currentBias = imuBias.ConstantBias(zeros(3,1), zeros(3,1));
|
||||
sigma_init_x = noiseModel.Isotropic.Sigma(6, 0.01);
|
||||
sigma_init_v = noiseModel.Isotropic.Sigma(3, 1000.0);
|
||||
sigma_init_b = noiseModel.Isotropic.Sigma(6, 0.01);
|
||||
g = [0;0;-9.8];
|
||||
w_coriolis = [0;0;0];
|
||||
|
||||
%% Solver object
|
||||
isamParams = ISAM2Params;
|
||||
isamParams.setFactorization('QR');
|
||||
isamParams.setRelinearizeSkip(1);
|
||||
isam = gtsam.ISAM2(isamParams);
|
||||
newFactors = NonlinearFactorGraph;
|
||||
newValues = Values;
|
||||
|
||||
%% Main loop:
|
||||
% (1) we read the measurements
|
||||
% (2) we create the corresponding factors in the graph
|
||||
% (3) we solve the graph to obtain and optimal estimate of robot trajectory
|
||||
timestamps = sortrows( [ ...
|
||||
[VO_data.Time]' 1*ones(length([VO_data.Time]), 1); ...
|
||||
% % %[GPS_data.Time]' 2*ones(length([GPS_data.Time]), 1); ...
|
||||
], 1); % this are the time-stamps at which we want to initialize a new node in the graph
|
||||
|
||||
timestamps = timestamps(15:end,:); % there seem to be issues with the initial IMU measurements
|
||||
IMUtimes = [IMU_data.Time];
|
||||
VOPoseKeys = []; % here we store the keys of the poses involved in VO (between) factors
|
||||
|
||||
for measurementIndex = 1:length(timestamps)
|
||||
|
||||
% At each non=IMU measurement we initialize a new node in the graph
|
||||
currentPoseKey = symbol('x',measurementIndex);
|
||||
currentVelKey = symbol('v',measurementIndex);
|
||||
currentBiasKey = symbol('b',measurementIndex);
|
||||
t = timestamps(measurementIndex, 1);
|
||||
type = timestamps(measurementIndex, 2);
|
||||
|
||||
%% bookkeeping
|
||||
if type == 1 % we store the keys corresponding to VO measurements
|
||||
VOPoseKeys = [VOPoseKeys; currentPoseKey];
|
||||
end
|
||||
|
||||
if measurementIndex == 1
|
||||
%% Create initial estimate and prior on initial pose, velocity, and biases
|
||||
newValues.insert(currentPoseKey, currentPoseGlobal);
|
||||
newValues.insert(currentVelKey, currentVelocityGlobal);
|
||||
newValues.insert(currentBiasKey, currentBias);
|
||||
newFactors.add(PriorFactorPose3(currentPoseKey, currentPoseGlobal, sigma_init_x));
|
||||
newFactors.add(PriorFactorLieVector(currentVelKey, currentVelocityGlobal, sigma_init_v));
|
||||
newFactors.add(PriorFactorConstantBias(currentBiasKey, currentBias, sigma_init_b));
|
||||
else
|
||||
t_previous = timestamps(measurementIndex-1, 1);
|
||||
%% Summarize IMU data between the previous GPS measurement and now
|
||||
IMUindices = find(IMUtimes >= t_previous & IMUtimes <= t);
|
||||
|
||||
if ~isempty(IMUindices) % if there are IMU measurements to integrate
|
||||
currentSummarizedMeasurement = gtsam.ImuFactorPreintegratedMeasurements( ...
|
||||
currentBias, IMU_metadata.AccelerometerSigma.^2 * eye(3), ...
|
||||
IMU_metadata.GyroscopeSigma.^2 * eye(3), IMU_metadata.IntegrationSigma.^2 * eye(3));
|
||||
|
||||
for imuIndex = IMUindices
|
||||
accMeas = [ IMU_data(imuIndex).accelX; IMU_data(imuIndex).accelY; IMU_data(imuIndex).accelZ ];
|
||||
omegaMeas = [ IMU_data(imuIndex).omegaX; IMU_data(imuIndex).omegaY; IMU_data(imuIndex).omegaZ ];
|
||||
deltaT = IMU_data(imuIndex).dt;
|
||||
currentSummarizedMeasurement.integrateMeasurement(accMeas, omegaMeas, deltaT);
|
||||
end
|
||||
|
||||
% Create IMU factor
|
||||
newFactors.add(ImuFactor( ...
|
||||
currentPoseKey-1, currentVelKey-1, ...
|
||||
currentPoseKey, currentVelKey, ...
|
||||
currentBiasKey, currentSummarizedMeasurement, g, w_coriolis));
|
||||
|
||||
else % if there are no IMU measurements
|
||||
error('no IMU measurements in [t_previous, t]')
|
||||
end
|
||||
|
||||
% LC: sigma_init_b is wrong: this should be some uncertainty on bias evolution given in the IMU metadata
|
||||
newFactors.add(BetweenFactorConstantBias(currentBiasKey-1, currentBiasKey, imuBias.ConstantBias(zeros(3,1), zeros(3,1)), sigma_init_b));
|
||||
|
||||
%% Create GPS factor
|
||||
if type == 2
|
||||
newFactors.add(PriorFactorPose3(currentPoseKey, Pose3(currentPoseGlobal.rotation, GPS_data(measurementIndex).Position), ...
|
||||
noiseModel.Diagonal.Precisions([ zeros(3,1); 1./(GPS_data(measurementIndex).PositionSigma).^2*ones(3,1) ])));
|
||||
end
|
||||
|
||||
%% Create VO factor
|
||||
if type == 1
|
||||
VOpose = VO_data(measurementIndex).RelativePose;
|
||||
newFactors.add(BetweenFactorPose3(VOPoseKeys(end-1), VOPoseKeys(end), VOpose, noiseModelVO));
|
||||
end
|
||||
|
||||
% Add initial value
|
||||
% newValues.insert(currentPoseKey, Pose3(currentPoseGlobal.rotation, GPS_data(measurementIndex).Position));
|
||||
newValues.insert(currentPoseKey,currentPoseGlobal);
|
||||
newValues.insert(currentVelKey, currentVelocityGlobal);
|
||||
newValues.insert(currentBiasKey, currentBias);
|
||||
|
||||
% Update solver
|
||||
% =======================================================================
|
||||
isam.update(newFactors, newValues);
|
||||
newFactors = NonlinearFactorGraph;
|
||||
newValues = Values;
|
||||
|
||||
if rem(measurementIndex,100)==0 % plot every 100 time steps
|
||||
cla;
|
||||
plot3DTrajectory(isam.calculateEstimate, 'g-');
|
||||
axis equal
|
||||
drawnow;
|
||||
end
|
||||
% =======================================================================
|
||||
currentPoseGlobal = isam.calculateEstimate(currentPoseKey);
|
||||
currentVelocityGlobal = isam.calculateEstimate(currentVelKey);
|
||||
currentBias = isam.calculateEstimate(currentBiasKey);
|
||||
end
|
||||
|
||||
end % end main loop
|
|
@ -0,0 +1,149 @@
|
|||
close all
|
||||
clc
|
||||
|
||||
import gtsam.*;
|
||||
disp('Example of application of ISAM2 for GPS-aided navigation on the KITTI VISION BENCHMARK SUITE (http://www.computervisiononline.com/dataset/kitti-vision-benchmark-suite)')
|
||||
|
||||
%% Read metadata and compute relative sensor pose transforms
|
||||
% IMU metadata
|
||||
disp('-- Reading sensor metadata')
|
||||
IMU_metadata = importdata('KittiEquivBiasedImu_metadata.txt');
|
||||
IMU_metadata = cell2struct(num2cell(IMU_metadata.data), IMU_metadata.colheaders, 2);
|
||||
IMUinBody = Pose3.Expmap([IMU_metadata.BodyPtx; IMU_metadata.BodyPty; IMU_metadata.BodyPtz;
|
||||
IMU_metadata.BodyPrx; IMU_metadata.BodyPry; IMU_metadata.BodyPrz; ]);
|
||||
if ~IMUinBody.equals(Pose3, 1e-5)
|
||||
error 'Currently only support IMUinBody is identity, i.e. IMU and body frame are the same';
|
||||
end
|
||||
|
||||
% GPS metadata
|
||||
GPS_metadata = importdata('KittiRelativePose_metadata.txt');
|
||||
GPS_metadata = cell2struct(num2cell(GPS_metadata.data), GPS_metadata.colheaders, 2);
|
||||
|
||||
%% Read data
|
||||
disp('-- Reading sensor data from file')
|
||||
% IMU data
|
||||
IMU_data = importdata('KittiEquivBiasedImu.txt');
|
||||
IMU_data = cell2struct(num2cell(IMU_data.data), IMU_data.colheaders, 2);
|
||||
imum = cellfun(@(x) x', num2cell([ [IMU_data.accelX]' [IMU_data.accelY]' [IMU_data.accelZ]' [IMU_data.omegaX]' [IMU_data.omegaY]' [IMU_data.omegaZ]' ], 2), 'UniformOutput', false);
|
||||
[IMU_data.acc_omega] = deal(imum{:});
|
||||
clear imum
|
||||
|
||||
% GPS data
|
||||
GPS_data = importdata('Gps_converted.txt');
|
||||
GPS_data = cell2struct(num2cell(GPS_data.data), GPS_data.colheaders, 2);
|
||||
for i = 1:numel(GPS_data)
|
||||
GPS_data(i).Position = gtsam.Point3(GPS_data(i).X, GPS_data(i).Y, GPS_data(i).Z);
|
||||
end
|
||||
noiseModelGPS = noiseModel.Diagonal.Precisions([ [0;0;0]; 1.0/0.07 * [1;1;1] ]);
|
||||
firstGPSPose = 2;
|
||||
GPSskip = 10; % Skip this many GPS measurements each time
|
||||
|
||||
%% Get initial conditions for the estimated trajectory
|
||||
currentPoseGlobal = Pose3(Rot3, GPS_data(firstGPSPose).Position); % initial pose is the reference frame (navigation frame)
|
||||
currentVelocityGlobal = LieVector([0;0;0]); % the vehicle is stationary at the beginning
|
||||
currentBias = imuBias.ConstantBias(zeros(3,1), zeros(3,1));
|
||||
sigma_init_x = noiseModel.Isotropic.Precisions([ 0.0; 0.0; 0.0; 1; 1; 1 ]);
|
||||
sigma_init_v = noiseModel.Isotropic.Sigma(3, 1000.0);
|
||||
sigma_init_b = noiseModel.Isotropic.Sigmas([ 0.100; 0.100; 0.100; 5.00e-05; 5.00e-05; 5.00e-05 ]);
|
||||
sigma_between_b = [ IMU_metadata.AccelerometerBiasSigma * ones(3,1); IMU_metadata.GyroscopeBiasSigma * ones(3,1) ];
|
||||
g = [0;0;-9.8];
|
||||
w_coriolis = [0;0;0];
|
||||
|
||||
%% Solver object
|
||||
isamParams = ISAM2Params;
|
||||
isamParams.setFactorization('CHOLESKY');
|
||||
isamParams.setRelinearizeSkip(10);
|
||||
isam = gtsam.ISAM2(isamParams);
|
||||
newFactors = NonlinearFactorGraph;
|
||||
newValues = Values;
|
||||
|
||||
%% Main loop:
|
||||
% (1) we read the measurements
|
||||
% (2) we create the corresponding factors in the graph
|
||||
% (3) we solve the graph to obtain and optimal estimate of robot trajectory
|
||||
IMUtimes = [IMU_data.Time];
|
||||
|
||||
disp('-- Starting main loop: inference is performed at each time step, but we plot trajectory every 10 steps')
|
||||
|
||||
for measurementIndex = firstGPSPose:length(GPS_data)
|
||||
|
||||
% At each non=IMU measurement we initialize a new node in the graph
|
||||
currentPoseKey = symbol('x',measurementIndex);
|
||||
currentVelKey = symbol('v',measurementIndex);
|
||||
currentBiasKey = symbol('b',measurementIndex);
|
||||
t = GPS_data(measurementIndex, 1).Time;
|
||||
|
||||
if measurementIndex == firstGPSPose
|
||||
%% Create initial estimate and prior on initial pose, velocity, and biases
|
||||
newValues.insert(currentPoseKey, currentPoseGlobal);
|
||||
newValues.insert(currentVelKey, currentVelocityGlobal);
|
||||
newValues.insert(currentBiasKey, currentBias);
|
||||
newFactors.add(PriorFactorPose3(currentPoseKey, currentPoseGlobal, sigma_init_x));
|
||||
newFactors.add(PriorFactorLieVector(currentVelKey, currentVelocityGlobal, sigma_init_v));
|
||||
newFactors.add(PriorFactorConstantBias(currentBiasKey, currentBias, sigma_init_b));
|
||||
else
|
||||
t_previous = GPS_data(measurementIndex-1, 1).Time;
|
||||
%% Summarize IMU data between the previous GPS measurement and now
|
||||
IMUindices = find(IMUtimes >= t_previous & IMUtimes <= t);
|
||||
|
||||
currentSummarizedMeasurement = gtsam.ImuFactorPreintegratedMeasurements( ...
|
||||
currentBias, IMU_metadata.AccelerometerSigma.^2 * eye(3), ...
|
||||
IMU_metadata.GyroscopeSigma.^2 * eye(3), IMU_metadata.IntegrationSigma.^2 * eye(3));
|
||||
|
||||
for imuIndex = IMUindices
|
||||
accMeas = [ IMU_data(imuIndex).accelX; IMU_data(imuIndex).accelY; IMU_data(imuIndex).accelZ ];
|
||||
omegaMeas = [ IMU_data(imuIndex).omegaX; IMU_data(imuIndex).omegaY; IMU_data(imuIndex).omegaZ ];
|
||||
deltaT = IMU_data(imuIndex).dt;
|
||||
currentSummarizedMeasurement.integrateMeasurement(accMeas, omegaMeas, deltaT);
|
||||
end
|
||||
|
||||
% Create IMU factor
|
||||
newFactors.add(ImuFactor( ...
|
||||
currentPoseKey-1, currentVelKey-1, ...
|
||||
currentPoseKey, currentVelKey, ...
|
||||
currentBiasKey, currentSummarizedMeasurement, g, w_coriolis));
|
||||
|
||||
% Bias evolution as given in the IMU metadata
|
||||
newFactors.add(BetweenFactorConstantBias(currentBiasKey-1, currentBiasKey, imuBias.ConstantBias(zeros(3,1), zeros(3,1)), ...
|
||||
noiseModel.Diagonal.Sigmas(sqrt(numel(IMUindices)) * sigma_between_b)));
|
||||
|
||||
% Create GPS factor
|
||||
GPSPose = Pose3(currentPoseGlobal.rotation, GPS_data(measurementIndex).Position);
|
||||
if mod(measurementIndex, GPSskip) == 0
|
||||
newFactors.add(PriorFactorPose3(currentPoseKey, GPSPose, noiseModelGPS));
|
||||
end
|
||||
|
||||
% Add initial value
|
||||
newValues.insert(currentPoseKey, GPSPose);
|
||||
newValues.insert(currentVelKey, currentVelocityGlobal);
|
||||
newValues.insert(currentBiasKey, currentBias);
|
||||
|
||||
% Update solver
|
||||
% =======================================================================
|
||||
% We accumulate 2*GPSskip GPS measurements before updating the solver at
|
||||
% first so that the heading becomes observable.
|
||||
if measurementIndex > firstGPSPose + 2*GPSskip
|
||||
isam.update(newFactors, newValues);
|
||||
newFactors = NonlinearFactorGraph;
|
||||
newValues = Values;
|
||||
|
||||
if rem(measurementIndex,10)==0 % plot every 10 time steps
|
||||
cla;
|
||||
plot3DTrajectory(isam.calculateEstimate, 'g-');
|
||||
title('Estimated trajectory using ISAM2 (IMU+GPS)')
|
||||
xlabel('[m]')
|
||||
ylabel('[m]')
|
||||
zlabel('[m]')
|
||||
axis equal
|
||||
drawnow;
|
||||
end
|
||||
% =======================================================================
|
||||
currentPoseGlobal = isam.calculateEstimate(currentPoseKey);
|
||||
currentVelocityGlobal = isam.calculateEstimate(currentVelKey);
|
||||
currentBias = isam.calculateEstimate(currentBiasKey);
|
||||
end
|
||||
end
|
||||
|
||||
end % end main loop
|
||||
|
||||
disp('-- Reached end of sensor data')
|
|
@ -1,126 +0,0 @@
|
|||
%close all
|
||||
%clc
|
||||
|
||||
import gtsam.*;
|
||||
|
||||
%% Read data
|
||||
IMU_metadata = importdata(gtsam.findExampleDataFile('KittiEquivBiasedImu_metadata.txt'));
|
||||
IMU_data = importdata(gtsam.findExampleDataFile('KittiEquivBiasedImu.txt'));
|
||||
% Make text file column headers into struct fields
|
||||
IMU_metadata = cell2struct(num2cell(IMU_metadata.data), IMU_metadata.colheaders, 2);
|
||||
IMU_data = cell2struct(num2cell(IMU_data.data), IMU_data.colheaders, 2);
|
||||
|
||||
GPS_metadata = importdata(gtsam.findExampleDataFile('KittiGps_metadata.txt'));
|
||||
GPS_data = importdata(gtsam.findExampleDataFile('KittiGps.txt'));
|
||||
% Make text file column headers into struct fields
|
||||
GPS_metadata = cell2struct(num2cell(GPS_metadata.data), GPS_metadata.colheaders, 2);
|
||||
GPS_data = cell2struct(num2cell(GPS_data.data), GPS_data.colheaders, 2);
|
||||
|
||||
%% Convert GPS from lat/long to meters
|
||||
[ x, y, ~ ] = deg2utm( [GPS_data.Latitude], [GPS_data.Longitude] );
|
||||
for i = 1:numel(x)
|
||||
GPS_data(i).Position = gtsam.Point3(x(i), y(i), GPS_data(i).Altitude);
|
||||
end
|
||||
|
||||
% % Calculate GPS sigma in meters
|
||||
% [ xSig, ySig, ~ ] = deg2utm( [GPS_data.Latitude] + [GPS_data.PositionSigma], ...
|
||||
% [GPS_data.Longitude] + [GPS_data.PositionSigma]);
|
||||
% xSig = xSig - x;
|
||||
% ySig = ySig - y;
|
||||
|
||||
%% Start at time of first GPS measurement
|
||||
firstGPSPose = 2;
|
||||
|
||||
%% Get initial conditions for the estimated trajectory
|
||||
currentPoseGlobal = Pose3(Rot3, GPS_data(firstGPSPose).Position); % initial pose is the reference frame (navigation frame)
|
||||
currentVelocityGlobal = LieVector([0;0;0]); % the vehicle is stationary at the beginning
|
||||
currentBias = imuBias.ConstantBias(zeros(3,1), zeros(3,1));
|
||||
|
||||
%% Solver object
|
||||
isamParams = ISAM2Params;
|
||||
isamParams.setFactorization('QR');
|
||||
isamParams.setRelinearizeSkip(1);
|
||||
isam = gtsam.ISAM2(isamParams);
|
||||
newFactors = NonlinearFactorGraph;
|
||||
newValues = Values;
|
||||
|
||||
%% Create initial estimate and prior on initial pose, velocity, and biases
|
||||
newValues.insert(symbol('x',firstGPSPose), currentPoseGlobal);
|
||||
newValues.insert(symbol('v',firstGPSPose), currentVelocityGlobal);
|
||||
newValues.insert(symbol('b',1), currentBias);
|
||||
|
||||
sigma_init_x = noiseModel.Diagonal.Precisions([0;0;0; 1;1;1]);
|
||||
sigma_init_v = noiseModel.Isotropic.Sigma(3, 1000.0);
|
||||
sigma_init_b = noiseModel.Isotropic.Sigma(6, 0.01);
|
||||
|
||||
newFactors.add(PriorFactorPose3(symbol('x',firstGPSPose), currentPoseGlobal, sigma_init_x));
|
||||
newFactors.add(PriorFactorLieVector(symbol('v',firstGPSPose), currentVelocityGlobal, sigma_init_v));
|
||||
newFactors.add(PriorFactorConstantBias(symbol('b',1), currentBias, sigma_init_b));
|
||||
|
||||
%% Main loop:
|
||||
% (1) we read the measurements
|
||||
% (2) we create the corresponding factors in the graph
|
||||
% (3) we solve the graph to obtain and optimal estimate of robot trajectory
|
||||
|
||||
for poseIndex = firstGPSPose:length(GPS_data)
|
||||
% At each non=IMU measurement we initialize a new node in the graph
|
||||
currentPoseKey = symbol('x',poseIndex);
|
||||
currentVelKey = symbol('v',poseIndex);
|
||||
currentBiasKey = symbol('b',1);
|
||||
|
||||
if poseIndex > firstGPSPose
|
||||
% Summarize IMU data between the previous GPS measurement and now
|
||||
IMUindices = find([IMU_data.Time] > GPS_data(poseIndex-1).Time ...
|
||||
& [IMU_data.Time] <= GPS_data(poseIndex).Time);
|
||||
|
||||
currentSummarizedMeasurement = gtsam.ImuFactorPreintegratedMeasurements( ...
|
||||
currentBias, IMU_metadata.AccelerometerSigma.^2 * eye(3), ...
|
||||
IMU_metadata.GyroscopeSigma.^2 * eye(3), IMU_metadata.IntegrationSigma.^2 * eye(3));
|
||||
|
||||
for imuIndex = IMUindices
|
||||
accMeas = [ IMU_data(imuIndex).accelX; IMU_data(imuIndex).accelY; IMU_data(imuIndex).accelZ ];
|
||||
omegaMeas = [ IMU_data(imuIndex).omegaX; IMU_data(imuIndex).omegaY; IMU_data(imuIndex).omegaZ ];
|
||||
deltaT = IMU_data(imuIndex).dt;
|
||||
currentSummarizedMeasurement.integrateMeasurement(accMeas, omegaMeas, deltaT);
|
||||
end
|
||||
|
||||
% Create IMU factor
|
||||
newFactors.add(ImuFactor( ...
|
||||
currentPoseKey-1, currentVelKey-1, ...
|
||||
currentPoseKey, currentVelKey, ...
|
||||
currentBiasKey, currentSummarizedMeasurement, [0;0;-9.8], [0;0;0]));
|
||||
|
||||
% Create GPS factor
|
||||
newFactors.add(PriorFactorPose3(currentPoseKey, Pose3(currentPoseGlobal.rotation, GPS_data(poseIndex).Position), ...
|
||||
noiseModel.Diagonal.Precisions([ zeros(3,1); 1./(GPS_data(poseIndex).PositionSigma).^2*ones(3,1) ])));
|
||||
|
||||
% Add initial value
|
||||
newValues.insert(currentPoseKey, Pose3(currentPoseGlobal.rotation, GPS_data(poseIndex).Position));
|
||||
newValues.insert(currentVelKey, currentVelocityGlobal);
|
||||
%newValues.insert(currentBiasKey, currentBias);
|
||||
|
||||
% Update solver
|
||||
% =======================================================================
|
||||
isam.update(newFactors, newValues);
|
||||
newFactors = NonlinearFactorGraph;
|
||||
newValues = Values;
|
||||
|
||||
cla;
|
||||
plot3DTrajectory(isam.calculateEstimate, 'g-');
|
||||
drawnow;
|
||||
% =======================================================================
|
||||
|
||||
currentPoseGlobal = isam.calculateEstimate(currentPoseKey);
|
||||
currentVelocityGlobal = isam.calculateEstimate(currentVelKey);
|
||||
currentBias = isam.calculateEstimate(currentBiasKey);
|
||||
|
||||
end
|
||||
end
|
||||
|
||||
disp('TODO: display results')
|
||||
% figure(1)
|
||||
% hold on;
|
||||
% plot(positions(1,:), positions(2,:), '-b');
|
||||
% plot3DTrajectory(isam.calculateEstimate, 'g-');
|
||||
% axis equal;
|
||||
% legend('true trajectory', 'traj integrated in body', 'traj integrated in nav')
|
|
@ -0,0 +1,152 @@
|
|||
close all
|
||||
clc
|
||||
|
||||
import gtsam.*;
|
||||
disp('Example of application of ISAM2 for visual-inertial navigation on the KITTI VISION BENCHMARK SUITE (http://www.computervisiononline.com/dataset/kitti-vision-benchmark-suite)')
|
||||
|
||||
%% Read metadata and compute relative sensor pose transforms
|
||||
% IMU metadata
|
||||
disp('-- Reading sensor metadata')
|
||||
IMU_metadata = importdata('KittiEquivBiasedImu_metadata.txt');
|
||||
IMU_metadata = cell2struct(num2cell(IMU_metadata.data), IMU_metadata.colheaders, 2);
|
||||
IMUinBody = Pose3.Expmap([IMU_metadata.BodyPtx; IMU_metadata.BodyPty; IMU_metadata.BodyPtz;
|
||||
IMU_metadata.BodyPrx; IMU_metadata.BodyPry; IMU_metadata.BodyPrz; ]);
|
||||
if ~IMUinBody.equals(Pose3, 1e-5)
|
||||
error 'Currently only support IMUinBody is identity, i.e. IMU and body frame are the same';
|
||||
end
|
||||
|
||||
% VO metadata
|
||||
VO_metadata = importdata('KittiRelativePose_metadata.txt');
|
||||
VO_metadata = cell2struct(num2cell(VO_metadata.data), VO_metadata.colheaders, 2);
|
||||
VOinBody = Pose3.Expmap([VO_metadata.BodyPtx; VO_metadata.BodyPty; VO_metadata.BodyPtz;
|
||||
VO_metadata.BodyPrx; VO_metadata.BodyPry; VO_metadata.BodyPrz; ]);
|
||||
VOinIMU = IMUinBody.inverse().compose(VOinBody);
|
||||
|
||||
%% Read data and change coordinate frame of GPS and VO measurements to IMU frame
|
||||
disp('-- Reading sensor data from file')
|
||||
% IMU data
|
||||
IMU_data = importdata('KittiEquivBiasedImu.txt');
|
||||
IMU_data = cell2struct(num2cell(IMU_data.data), IMU_data.colheaders, 2);
|
||||
imum = cellfun(@(x) x', num2cell([ [IMU_data.accelX]' [IMU_data.accelY]' [IMU_data.accelZ]' [IMU_data.omegaX]' [IMU_data.omegaY]' [IMU_data.omegaZ]' ], 2), 'UniformOutput', false);
|
||||
[IMU_data.acc_omega] = deal(imum{:});
|
||||
clear imum
|
||||
|
||||
% VO data
|
||||
VO_data = importdata('KittiRelativePose.txt');
|
||||
VO_data = cell2struct(num2cell(VO_data.data), VO_data.colheaders, 2);
|
||||
% Merge relative pose fields and convert to Pose3
|
||||
logposes = [ [VO_data.dtx]' [VO_data.dty]' [VO_data.dtz]' [VO_data.drx]' [VO_data.dry]' [VO_data.drz]' ];
|
||||
logposes = num2cell(logposes, 2);
|
||||
relposes = arrayfun(@(x) {gtsam.Pose3.Expmap(x{:}')}, logposes);
|
||||
relposes = arrayfun(@(x) {VOinIMU.compose(x{:}).compose(VOinIMU.inverse())}, relposes);
|
||||
[VO_data.RelativePose] = deal(relposes{:});
|
||||
VO_data = rmfield(VO_data, { 'dtx' 'dty' 'dtz' 'drx' 'dry' 'drz' });
|
||||
noiseModelVO = noiseModel.Diagonal.Sigmas([ VO_metadata.RotationSigma * [1;1;1]; VO_metadata.TranslationSigma * [1;1;1] ]);
|
||||
clear logposes relposes
|
||||
|
||||
%% Get initial conditions for the estimated trajectory
|
||||
currentPoseGlobal = Pose3;
|
||||
currentVelocityGlobal = LieVector([0;0;0]); % the vehicle is stationary at the beginning
|
||||
currentBias = imuBias.ConstantBias(zeros(3,1), zeros(3,1));
|
||||
sigma_init_x = noiseModel.Isotropic.Sigmas([ 1.0; 1.0; 0.01; 0.01; 0.01; 0.01 ]);
|
||||
sigma_init_v = noiseModel.Isotropic.Sigma(3, 1000.0);
|
||||
sigma_init_b = noiseModel.Isotropic.Sigmas([ 0.100; 0.100; 0.100; 5.00e-05; 5.00e-05; 5.00e-05 ]);
|
||||
sigma_between_b = [ IMU_metadata.AccelerometerBiasSigma * ones(3,1); IMU_metadata.GyroscopeBiasSigma * ones(3,1) ];
|
||||
g = [0;0;-9.8];
|
||||
w_coriolis = [0;0;0];
|
||||
|
||||
%% Solver object
|
||||
isamParams = ISAM2Params;
|
||||
isamParams.setFactorization('CHOLESKY');
|
||||
isamParams.setRelinearizeSkip(10);
|
||||
isam = gtsam.ISAM2(isamParams);
|
||||
newFactors = NonlinearFactorGraph;
|
||||
newValues = Values;
|
||||
|
||||
%% Main loop:
|
||||
% (1) we read the measurements
|
||||
% (2) we create the corresponding factors in the graph
|
||||
% (3) we solve the graph to obtain and optimal estimate of robot trajectory
|
||||
timestamps = [VO_data.Time]';
|
||||
|
||||
timestamps = timestamps(15:end,:); % there seem to be issues with the initial IMU measurements
|
||||
IMUtimes = [IMU_data.Time];
|
||||
|
||||
disp('-- Starting main loop: inference is performed at each time step, but we plot trajectory every 100 steps')
|
||||
|
||||
for measurementIndex = 1:length(timestamps)
|
||||
|
||||
% At each non=IMU measurement we initialize a new node in the graph
|
||||
currentPoseKey = symbol('x',measurementIndex);
|
||||
currentVelKey = symbol('v',measurementIndex);
|
||||
currentBiasKey = symbol('b',measurementIndex);
|
||||
t = timestamps(measurementIndex, 1);
|
||||
|
||||
if measurementIndex == 1
|
||||
%% Create initial estimate and prior on initial pose, velocity, and biases
|
||||
newValues.insert(currentPoseKey, currentPoseGlobal);
|
||||
newValues.insert(currentVelKey, currentVelocityGlobal);
|
||||
newValues.insert(currentBiasKey, currentBias);
|
||||
newFactors.add(PriorFactorPose3(currentPoseKey, currentPoseGlobal, sigma_init_x));
|
||||
newFactors.add(PriorFactorLieVector(currentVelKey, currentVelocityGlobal, sigma_init_v));
|
||||
newFactors.add(PriorFactorConstantBias(currentBiasKey, currentBias, sigma_init_b));
|
||||
else
|
||||
t_previous = timestamps(measurementIndex-1, 1);
|
||||
%% Summarize IMU data between the previous GPS measurement and now
|
||||
IMUindices = find(IMUtimes >= t_previous & IMUtimes <= t);
|
||||
|
||||
currentSummarizedMeasurement = gtsam.ImuFactorPreintegratedMeasurements( ...
|
||||
currentBias, IMU_metadata.AccelerometerSigma.^2 * eye(3), ...
|
||||
IMU_metadata.GyroscopeSigma.^2 * eye(3), IMU_metadata.IntegrationSigma.^2 * eye(3));
|
||||
|
||||
for imuIndex = IMUindices
|
||||
accMeas = [ IMU_data(imuIndex).accelX; IMU_data(imuIndex).accelY; IMU_data(imuIndex).accelZ ];
|
||||
omegaMeas = [ IMU_data(imuIndex).omegaX; IMU_data(imuIndex).omegaY; IMU_data(imuIndex).omegaZ ];
|
||||
deltaT = IMU_data(imuIndex).dt;
|
||||
currentSummarizedMeasurement.integrateMeasurement(accMeas, omegaMeas, deltaT);
|
||||
end
|
||||
|
||||
% Create IMU factor
|
||||
newFactors.add(ImuFactor( ...
|
||||
currentPoseKey-1, currentVelKey-1, ...
|
||||
currentPoseKey, currentVelKey, ...
|
||||
currentBiasKey, currentSummarizedMeasurement, g, w_coriolis));
|
||||
|
||||
% LC: sigma_init_b is wrong: this should be some uncertainty on bias evolution given in the IMU metadata
|
||||
newFactors.add(BetweenFactorConstantBias(currentBiasKey-1, currentBiasKey, imuBias.ConstantBias(zeros(3,1), zeros(3,1)), ...
|
||||
noiseModel.Diagonal.Sigmas(sqrt(numel(IMUindices)) * sigma_between_b)));
|
||||
|
||||
%% Create VO factor
|
||||
VOpose = VO_data(measurementIndex).RelativePose;
|
||||
newFactors.add(BetweenFactorPose3(currentPoseKey - 1, currentPoseKey, VOpose, noiseModelVO));
|
||||
|
||||
% Add initial value
|
||||
newValues.insert(currentPoseKey, currentPoseGlobal.compose(VOpose));
|
||||
newValues.insert(currentVelKey, currentVelocityGlobal);
|
||||
newValues.insert(currentBiasKey, currentBias);
|
||||
|
||||
% Update solver
|
||||
% =======================================================================
|
||||
isam.update(newFactors, newValues);
|
||||
newFactors = NonlinearFactorGraph;
|
||||
newValues = Values;
|
||||
|
||||
if rem(measurementIndex,100)==0 % plot every 100 time steps
|
||||
cla;
|
||||
plot3DTrajectory(isam.calculateEstimate, 'g-');
|
||||
title('Estimated trajectory using ISAM2 (IMU+VO)')
|
||||
xlabel('[m]')
|
||||
ylabel('[m]')
|
||||
zlabel('[m]')
|
||||
axis equal
|
||||
drawnow;
|
||||
end
|
||||
% =======================================================================
|
||||
currentPoseGlobal = isam.calculateEstimate(currentPoseKey);
|
||||
currentVelocityGlobal = isam.calculateEstimate(currentVelKey);
|
||||
currentBias = isam.calculateEstimate(currentBiasKey);
|
||||
end
|
||||
|
||||
end % end main loop
|
||||
|
||||
disp('-- Reached end of sensor data')
|
Loading…
Reference in New Issue