Renamed tic -> gttic and toc -> gttoc to avoid conflict with PCL tic/toc

release/4.3a0
Richard Roberts 2012-10-02 20:18:41 +00:00
parent c44f8f7f80
commit 89b50e7679
33 changed files with 418 additions and 418 deletions

View File

@ -79,7 +79,7 @@ int main(int argc, char** argv) {
cout << "\nComputing Node Marginals ..(Sequential Elimination)" << endl; cout << "\nComputing Node Marginals ..(Sequential Elimination)" << endl;
tic_(Sequential); gttic_(Sequential);
for (vector<DiscreteKey>::iterator itr = nodes.begin(); itr != nodes.end(); for (vector<DiscreteKey>::iterator itr = nodes.begin(); itr != nodes.end();
++itr) { ++itr) {
//Compute the marginal //Compute the marginal
@ -89,14 +89,14 @@ int main(int argc, char** argv) {
cout << "Node#" << setw(4) << itr->first << " : "; cout << "Node#" << setw(4) << itr->first << " : ";
print(margProbs); print(margProbs);
} }
toc_(Sequential); gttoc_(Sequential);
// Here we'll make use of DiscreteMarginals class, which makes use of // Here we'll make use of DiscreteMarginals class, which makes use of
// bayes-tree based shortcut evaluation of marginals // bayes-tree based shortcut evaluation of marginals
DiscreteMarginals marginals(graph); DiscreteMarginals marginals(graph);
cout << "\nComputing Node Marginals ..(BayesTree based)" << endl; cout << "\nComputing Node Marginals ..(BayesTree based)" << endl;
tic_(Multifrontal); gttic_(Multifrontal);
for (vector<DiscreteKey>::iterator itr = nodes.begin(); itr != nodes.end(); for (vector<DiscreteKey>::iterator itr = nodes.begin(); itr != nodes.end();
++itr) { ++itr) {
//Compute the marginal //Compute the marginal
@ -106,7 +106,7 @@ int main(int argc, char** argv) {
cout << "Node#" << setw(4) << itr->first << " : "; cout << "Node#" << setw(4) << itr->first << " : ";
print(margProbs); print(margProbs);
} }
toc_(Multifrontal); gttoc_(Multifrontal);
tictoc_print_(); tictoc_print_();
return 0; return 0;

View File

@ -410,17 +410,17 @@ void householder_(Matrix& A, size_t k, bool copy_vectors) {
double beta = houseInPlace(vjm); double beta = houseInPlace(vjm);
// do outer product update A(j:m,:) = (I-beta vv')*A = A - v*(beta*A'*v)' = A - v*w' // do outer product update A(j:m,:) = (I-beta vv')*A = A - v*(beta*A'*v)' = A - v*w'
tic(householder_update); // bottleneck for system gttic(householder_update); // bottleneck for system
// don't touch old columns // don't touch old columns
Vector w = beta * A.block(j,j,m-j,n-j).transpose() * vjm; Vector w = beta * A.block(j,j,m-j,n-j).transpose() * vjm;
A.block(j,j,m-j,n-j) -= vjm * w.transpose(); A.block(j,j,m-j,n-j) -= vjm * w.transpose();
toc(householder_update); gttoc(householder_update);
// the Householder vector is copied in the zeroed out part // the Householder vector is copied in the zeroed out part
if (copy_vectors) { if (copy_vectors) {
tic(householder_vector_copy); gttic(householder_vector_copy);
A.col(j).segment(j+1, m-(j+1)) = vjm.segment(1, m-(j+1)); A.col(j).segment(j+1, m-(j+1)) = vjm.segment(1, m-(j+1));
toc(householder_vector_copy); gttoc(householder_vector_copy);
} }
} // column j } // column j
} }
@ -428,14 +428,14 @@ void householder_(Matrix& A, size_t k, bool copy_vectors) {
/* ************************************************************************* */ /* ************************************************************************* */
void householder(Matrix& A, size_t k) { void householder(Matrix& A, size_t k) {
// version with zeros below diagonal // version with zeros below diagonal
tic(householder_); gttic(householder_);
householder_(A,k,false); householder_(A,k,false);
toc(householder_); gttoc(householder_);
// tic(householder_zero_fill); // gttic(householder_zero_fill);
// const size_t m = A.rows(), n = A.cols(), kprime = min(k,min(m,n)); // const size_t m = A.rows(), n = A.cols(), kprime = min(k,min(m,n));
// for(size_t j=0; j < kprime; j++) // for(size_t j=0; j < kprime; j++)
// A.col(j).segment(j+1, m-(j+1)).setZero(); // A.col(j).segment(j+1, m-(j+1)).setZero();
// toc(householder_zero_fill); // gttoc(householder_zero_fill);
} }
/* ************************************************************************* */ /* ************************************************************************* */

View File

@ -131,30 +131,30 @@ bool choleskyPartial(Matrix& ABC, size_t nFrontal) {
const size_t n = ABC.rows(); const size_t n = ABC.rows();
// Compute Cholesky factorization of A, overwrites A. // Compute Cholesky factorization of A, overwrites A.
tic(lld); gttic(lld);
Eigen::LLT<Matrix, Eigen::Upper> llt = ABC.block(0,0,nFrontal,nFrontal).selfadjointView<Eigen::Upper>().llt(); Eigen::LLT<Matrix, Eigen::Upper> llt = ABC.block(0,0,nFrontal,nFrontal).selfadjointView<Eigen::Upper>().llt();
ABC.block(0,0,nFrontal,nFrontal).triangularView<Eigen::Upper>() = llt.matrixU(); ABC.block(0,0,nFrontal,nFrontal).triangularView<Eigen::Upper>() = llt.matrixU();
toc(lld); gttoc(lld);
if(debug) cout << "R:\n" << Eigen::MatrixXd(ABC.topLeftCorner(nFrontal,nFrontal).triangularView<Eigen::Upper>()) << endl; if(debug) cout << "R:\n" << Eigen::MatrixXd(ABC.topLeftCorner(nFrontal,nFrontal).triangularView<Eigen::Upper>()) << endl;
// Compute S = inv(R') * B // Compute S = inv(R') * B
tic(compute_S); gttic(compute_S);
if(n - nFrontal > 0) { if(n - nFrontal > 0) {
ABC.topLeftCorner(nFrontal,nFrontal).triangularView<Eigen::Upper>().transpose().solveInPlace( ABC.topLeftCorner(nFrontal,nFrontal).triangularView<Eigen::Upper>().transpose().solveInPlace(
ABC.topRightCorner(nFrontal, n-nFrontal)); ABC.topRightCorner(nFrontal, n-nFrontal));
} }
if(debug) cout << "S:\n" << ABC.topRightCorner(nFrontal, n-nFrontal) << endl; if(debug) cout << "S:\n" << ABC.topRightCorner(nFrontal, n-nFrontal) << endl;
toc(compute_S); gttoc(compute_S);
// Compute L = C - S' * S // Compute L = C - S' * S
tic(compute_L); gttic(compute_L);
if(debug) cout << "C:\n" << Eigen::MatrixXd(ABC.bottomRightCorner(n-nFrontal,n-nFrontal).selfadjointView<Eigen::Upper>()) << endl; if(debug) cout << "C:\n" << Eigen::MatrixXd(ABC.bottomRightCorner(n-nFrontal,n-nFrontal).selfadjointView<Eigen::Upper>()) << endl;
if(n - nFrontal > 0) if(n - nFrontal > 0)
ABC.bottomRightCorner(n-nFrontal,n-nFrontal).selfadjointView<Eigen::Upper>().rankUpdate( ABC.bottomRightCorner(n-nFrontal,n-nFrontal).selfadjointView<Eigen::Upper>().rankUpdate(
ABC.topRightCorner(nFrontal, n-nFrontal).transpose(), -1.0); ABC.topRightCorner(nFrontal, n-nFrontal).transpose(), -1.0);
if(debug) cout << "L:\n" << Eigen::MatrixXd(ABC.bottomRightCorner(n-nFrontal,n-nFrontal).selfadjointView<Eigen::Upper>()) << endl; if(debug) cout << "L:\n" << Eigen::MatrixXd(ABC.bottomRightCorner(n-nFrontal,n-nFrontal).selfadjointView<Eigen::Upper>()) << endl;
toc(compute_L); gttoc(compute_L);
// Check last diagonal element - Eigen does not check it // Check last diagonal element - Eigen does not check it
bool ok; bool ok;

View File

@ -21,23 +21,23 @@ int main(int argc, char *argv[]) {
ticPush_("1", "top 1"); ticPush_("1", "top 1");
ticPush_("1", "sub 1"); ticPush_("1", "sub 1");
tic_("sub sub a"); gttic_("sub sub a");
toc_("sub sub a"); gttoc_("sub sub a");
ticPop_("1", "sub 1"); ticPop_("1", "sub 1");
ticPush_("2", "sub 2"); ticPush_("2", "sub 2");
tic_("sub sub b"); gttic_("sub sub b");
toc_("sub sub b"); gttoc_("sub sub b");
ticPop_("2", "sub 2"); ticPop_("2", "sub 2");
ticPop_("1", "top 1"); ticPop_("1", "top 1");
ticPush_("2", "top 2"); ticPush_("2", "top 2");
ticPush_("1", "sub 1"); ticPush_("1", "sub 1");
tic_("sub sub a"); gttic_("sub sub a");
toc_("sub sub a"); gttoc_("sub sub a");
ticPop_("1", "sub 1"); ticPop_("1", "sub 1");
ticPush_("2", "sub 2"); ticPush_("2", "sub 2");
tic_("sub sub b"); gttic_("sub sub b");
toc_("sub sub b"); gttoc_("sub sub b");
ticPop_("2", "sub 2"); ticPop_("2", "sub 2");
ticPop_("2", "top 2"); ticPop_("2", "top 2");
@ -49,10 +49,10 @@ int main(int argc, char *argv[]) {
} }
for(size_t i=0; i<1000000; ++i) { for(size_t i=0; i<1000000; ++i) {
tic(overhead_a); gttic(overhead_a);
tic(overhead_b); gttic(overhead_b);
toc(overhead_b); gttoc(overhead_b);
toc(overhead_a); gttoc(overhead_a);
} }
tictoc_print_(); tictoc_print_();

View File

@ -59,95 +59,95 @@ int main(int argc, char *argv[]) {
size_t trials = 10000000; size_t trials = 10000000;
tic_("heap plain alloc, dealloc"); gttic_("heap plain alloc, dealloc");
for(size_t i=0; i<trials; ++i) { for(size_t i=0; i<trials; ++i) {
Plain *obj = new Plain(i); Plain *obj = new Plain(i);
delete obj; delete obj;
} }
toc_("heap plain alloc, dealloc"); gttoc_("heap plain alloc, dealloc");
tic_("heap virtual alloc, dealloc"); gttic_("heap virtual alloc, dealloc");
for(size_t i=0; i<trials; ++i) { for(size_t i=0; i<trials; ++i) {
Virtual *obj = new Virtual(i); Virtual *obj = new Virtual(i);
delete obj; delete obj;
} }
toc_("heap virtual alloc, dealloc"); gttoc_("heap virtual alloc, dealloc");
tic_("stack plain alloc, dealloc"); gttic_("stack plain alloc, dealloc");
for(size_t i=0; i<trials; ++i) { for(size_t i=0; i<trials; ++i) {
Plain obj(i); Plain obj(i);
} }
toc_("stack plain alloc, dealloc"); gttoc_("stack plain alloc, dealloc");
tic_("stack virtual alloc, dealloc"); gttic_("stack virtual alloc, dealloc");
for(size_t i=0; i<trials; ++i) { for(size_t i=0; i<trials; ++i) {
Virtual obj(i); Virtual obj(i);
} }
toc_("stack virtual alloc, dealloc"); gttoc_("stack virtual alloc, dealloc");
tic_("shared plain alloc, dealloc"); gttic_("shared plain alloc, dealloc");
for(size_t i=0; i<trials; ++i) { for(size_t i=0; i<trials; ++i) {
boost::shared_ptr<Plain> obj(new Plain(i)); boost::shared_ptr<Plain> obj(new Plain(i));
} }
toc_("shared plain alloc, dealloc"); gttoc_("shared plain alloc, dealloc");
tic_("shared virtual alloc, dealloc"); gttic_("shared virtual alloc, dealloc");
for(size_t i=0; i<trials; ++i) { for(size_t i=0; i<trials; ++i) {
boost::shared_ptr<Virtual> obj(new Virtual(i)); boost::shared_ptr<Virtual> obj(new Virtual(i));
} }
toc_("shared virtual alloc, dealloc"); gttoc_("shared virtual alloc, dealloc");
tic_("heap plain alloc, dealloc, call"); gttic_("heap plain alloc, dealloc, call");
for(size_t i=0; i<trials; ++i) { for(size_t i=0; i<trials; ++i) {
Plain *obj = new Plain(i); Plain *obj = new Plain(i);
obj->setData(i+1); obj->setData(i+1);
delete obj; delete obj;
} }
toc_("heap plain alloc, dealloc, call"); gttoc_("heap plain alloc, dealloc, call");
tic_("heap virtual alloc, dealloc, call"); gttic_("heap virtual alloc, dealloc, call");
for(size_t i=0; i<trials; ++i) { for(size_t i=0; i<trials; ++i) {
Virtual *obj = new Virtual(i); Virtual *obj = new Virtual(i);
obj->setData(i+1); obj->setData(i+1);
delete obj; delete obj;
} }
toc_("heap virtual alloc, dealloc, call"); gttoc_("heap virtual alloc, dealloc, call");
tic_("stack plain alloc, dealloc, call"); gttic_("stack plain alloc, dealloc, call");
for(size_t i=0; i<trials; ++i) { for(size_t i=0; i<trials; ++i) {
Plain obj(i); Plain obj(i);
obj.setData(i+1); obj.setData(i+1);
} }
toc_("stack plain alloc, dealloc, call"); gttoc_("stack plain alloc, dealloc, call");
tic_("stack virtual alloc, dealloc, call"); gttic_("stack virtual alloc, dealloc, call");
for(size_t i=0; i<trials; ++i) { for(size_t i=0; i<trials; ++i) {
Virtual obj(i); Virtual obj(i);
obj.setData(i+1); obj.setData(i+1);
} }
toc_("stack virtual alloc, dealloc, call"); gttoc_("stack virtual alloc, dealloc, call");
tic_("shared plain alloc, dealloc, call"); gttic_("shared plain alloc, dealloc, call");
for(size_t i=0; i<trials; ++i) { for(size_t i=0; i<trials; ++i) {
boost::shared_ptr<Plain> obj(new Plain(i)); boost::shared_ptr<Plain> obj(new Plain(i));
obj->setData(i+1); obj->setData(i+1);
} }
toc_("shared plain alloc, dealloc, call"); gttoc_("shared plain alloc, dealloc, call");
tic_("shared virtual alloc, dealloc, call"); gttic_("shared virtual alloc, dealloc, call");
for(size_t i=0; i<trials; ++i) { for(size_t i=0; i<trials; ++i) {
boost::shared_ptr<Virtual> obj(new Virtual(i)); boost::shared_ptr<Virtual> obj(new Virtual(i));
obj->setData(i+1); obj->setData(i+1);
} }
toc_("shared virtual alloc, dealloc, call"); gttoc_("shared virtual alloc, dealloc, call");
tic_("intrusive virtual alloc, dealloc, call"); gttic_("intrusive virtual alloc, dealloc, call");
for(size_t i=0; i<trials; ++i) { for(size_t i=0; i<trials; ++i) {
intrusive_ptr<VirtualCounted> obj(new VirtualCounted(i)); intrusive_ptr<VirtualCounted> obj(new VirtualCounted(i));
obj->setData(i+1); obj->setData(i+1);
} }
toc_("intrusive virtual alloc, dealloc, call"); gttoc_("intrusive virtual alloc, dealloc, call");
tictoc_print_(); tictoc_print_();

View File

@ -84,51 +84,51 @@ int main(int argc, char *argv[]) {
{ {
VirtualBase** b = new VirtualBase*[n]; VirtualBase** b = new VirtualBase*[n];
tic_(Virtual); gttic_(Virtual);
tic_(new); gttic_(new);
for(int i=0; i<n; ++i) for(int i=0; i<n; ++i)
b[i] = new VirtualDerived(); b[i] = new VirtualDerived();
toc_(new); gttoc_(new);
tic_(method); gttic_(method);
for(int i=0; i<n; ++i) for(int i=0; i<n; ++i)
b[i]->method(); b[i]->method();
toc_(method); gttoc_(method);
tic_(dynamic_cast); gttic_(dynamic_cast);
for(int i=0; i<n; ++i) { for(int i=0; i<n; ++i) {
VirtualDerived* d = dynamic_cast<VirtualDerived*>(b[i]); VirtualDerived* d = dynamic_cast<VirtualDerived*>(b[i]);
if(d) if(d)
d->method(); d->method();
} }
toc_(dynamic_cast); gttoc_(dynamic_cast);
tic_(delete); gttic_(delete);
for(int i=0; i<n; ++i) for(int i=0; i<n; ++i)
delete b[i]; delete b[i];
toc_(delete); gttoc_(delete);
toc_(Virtual); gttoc_(Virtual);
delete[] b; delete[] b;
} }
{ {
NonVirtualDerived** d = new NonVirtualDerived*[n]; NonVirtualDerived** d = new NonVirtualDerived*[n];
tic_(NonVirtual); gttic_(NonVirtual);
tic_(new); gttic_(new);
for(int i=0; i<n; ++i) for(int i=0; i<n; ++i)
d[i] = new NonVirtualDerived(); d[i] = new NonVirtualDerived();
toc_(new); gttoc_(new);
tic_(method); gttic_(method);
for(int i=0; i<n; ++i) for(int i=0; i<n; ++i)
d[i]->method(); d[i]->method();
toc_(method); gttoc_(method);
tic_(dynamic_cast (does nothing)); gttic_(dynamic_cast (does nothing));
for(int i=0; i<n; ++i) for(int i=0; i<n; ++i)
d[i]->method(); d[i]->method();
toc_(dynamic_cast (does nothing)); gttoc_(dynamic_cast (does nothing));
tic_(delete); gttic_(delete);
for(int i=0; i<n; ++i) for(int i=0; i<n; ++i)
delete d[i]; delete d[i];
toc_(delete); gttoc_(delete);
toc_(NonVirtual); gttoc_(NonVirtual);
delete[] d; delete[] d;
} }

View File

@ -194,7 +194,7 @@ void TimingOutline::finishedIteration() {
void ticInternal(size_t id, const char *labelC) { void ticInternal(size_t id, const char *labelC) {
const std::string label(labelC); const std::string label(labelC);
if(ISDEBUG("timing-verbose")) if(ISDEBUG("timing-verbose"))
std::cout << "tic_(" << id << ", " << label << ")" << std::endl; std::cout << "gttic_(" << id << ", " << label << ")" << std::endl;
boost::shared_ptr<TimingOutline> node = timingCurrent.lock()->child(id, label, timingCurrent); boost::shared_ptr<TimingOutline> node = timingCurrent.lock()->child(id, label, timingCurrent);
timingCurrent = node; timingCurrent = node;
node->ticInternal(); node->ticInternal();
@ -203,18 +203,18 @@ void TimingOutline::finishedIteration() {
/* ************************************************************************* */ /* ************************************************************************* */
void tocInternal(size_t id, const char *label) { void tocInternal(size_t id, const char *label) {
if(ISDEBUG("timing-verbose")) if(ISDEBUG("timing-verbose"))
std::cout << "toc(" << id << ", " << label << ")" << std::endl; std::cout << "gttoc(" << id << ", " << label << ")" << std::endl;
boost::shared_ptr<TimingOutline> current(timingCurrent.lock()); boost::shared_ptr<TimingOutline> current(timingCurrent.lock());
if(id != current->myId_) { if(id != current->myId_) {
timingRoot->print(); timingRoot->print();
throw std::invalid_argument( throw std::invalid_argument(
(boost::format("gtsam timing: Mismatched tic/toc: toc(\"%s\") called when last tic was \"%s\".") % (boost::format("gtsam timing: Mismatched tic/toc: gttoc(\"%s\") called when last tic was \"%s\".") %
label % current->label_).str()); label % current->label_).str());
} }
if(!current->parent_.lock()) { if(!current->parent_.lock()) {
timingRoot->print(); timingRoot->print();
throw std::invalid_argument( throw std::invalid_argument(
(boost::format("gtsam timing: Mismatched tic/toc: extra toc(\"%s\"), already at the root") % (boost::format("gtsam timing: Mismatched tic/toc: extra gttoc(\"%s\"), already at the root") %
label).str()); label).str());
} }
current->tocInternal(); current->tocInternal();

View File

@ -108,10 +108,10 @@ inline void tictoc_print2_() {
} }
// Tic and toc functions using a string label // Tic and toc functions using a string label
#define tic_(label) \ #define gttic_(label) \
static const size_t label##_id_tic = ::gtsam::internal::getTicTocID(#label); \ static const size_t label##_id_tic = ::gtsam::internal::getTicTocID(#label); \
::gtsam::internal::AutoTicToc label##_obj = ::gtsam::internal::AutoTicToc(label##_id_tic, #label) ::gtsam::internal::AutoTicToc label##_obj = ::gtsam::internal::AutoTicToc(label##_id_tic, #label)
#define toc_(label) \ #define gttoc_(label) \
label##_obj.stop() label##_obj.stop()
#define longtic_(label) \ #define longtic_(label) \
static const size_t label##_id_tic = ::gtsam::internal::getTicTocID(#label); \ static const size_t label##_id_tic = ::gtsam::internal::getTicTocID(#label); \
@ -121,15 +121,15 @@ inline void tictoc_print2_() {
::gtsam::internal::tocInternal(label##_id_toc, #label) ::gtsam::internal::tocInternal(label##_id_toc, #label)
#ifdef ENABLE_TIMING #ifdef ENABLE_TIMING
#define tic(label) tic_(label) #define gttic(label) gttic_(label)
#define toc(label) toc_(label) #define gttoc(label) gttoc_(label)
#define longtic(label) longtic_(label) #define longtic(label) longtic_(label)
#define longtoc(label) longtoc_(label) #define longtoc(label) longtoc_(label)
#define tictoc_finishedIteration tictoc_finishedIteration_ #define tictoc_finishedIteration tictoc_finishedIteration_
#define tictoc_print tictoc_print_ #define tictoc_print tictoc_print_
#else #else
#define tic(label) ((void)0) #define gttic(label) ((void)0)
#define toc(label) ((void)0) #define gttoc(label) ((void)0)
#define longtic(label) ((void)0) #define longtic(label) ((void)0)
#define longtoc(label) ((void)0) #define longtoc(label) ((void)0)
inline void tictoc_finishedIteration() {} inline void tictoc_finishedIteration() {}

View File

@ -98,23 +98,23 @@ namespace gtsam {
EliminateDiscrete(const FactorGraph<DiscreteFactor>& factors, size_t num) { EliminateDiscrete(const FactorGraph<DiscreteFactor>& factors, size_t num) {
// PRODUCT: multiply all factors // PRODUCT: multiply all factors
tic(product); gttic(product);
DecisionTreeFactor product; DecisionTreeFactor product;
BOOST_FOREACH(const DiscreteFactor::shared_ptr& factor, factors){ BOOST_FOREACH(const DiscreteFactor::shared_ptr& factor, factors){
product = (*factor) * product; product = (*factor) * product;
} }
toc(product); gttoc(product);
// sum out frontals, this is the factor on the separator // sum out frontals, this is the factor on the separator
tic(sum); gttic(sum);
DecisionTreeFactor::shared_ptr sum = product.sum(num); DecisionTreeFactor::shared_ptr sum = product.sum(num);
toc(sum); gttoc(sum);
// now divide product/sum to get conditional // now divide product/sum to get conditional
tic(divide); gttic(divide);
DiscreteConditional::shared_ptr cond(new DiscreteConditional(product, *sum)); DiscreteConditional::shared_ptr cond(new DiscreteConditional(product, *sum));
toc(divide); gttoc(divide);
return std::make_pair(cond, sum); return std::make_pair(cond, sum);
} }

View File

@ -35,18 +35,18 @@ namespace gtsam {
"DiscreteSequentialSolver, elimination tree "); "DiscreteSequentialSolver, elimination tree ");
// Eliminate using the elimination tree // Eliminate using the elimination tree
tic(eliminate); gttic(eliminate);
DiscreteBayesNet::shared_ptr bayesNet = eliminate(); DiscreteBayesNet::shared_ptr bayesNet = eliminate();
toc(eliminate); gttoc(eliminate);
if (debug) bayesNet->print("DiscreteSequentialSolver, Bayes net "); if (debug) bayesNet->print("DiscreteSequentialSolver, Bayes net ");
// Allocate the solution vector if it is not already allocated // Allocate the solution vector if it is not already allocated
// Back-substitute // Back-substitute
tic(optimize); gttic(optimize);
DiscreteFactor::sharedValues solution = gtsam::optimize(*bayesNet); DiscreteFactor::sharedValues solution = gtsam::optimize(*bayesNet);
toc(optimize); gttoc(optimize);
if (debug) solution->print("DiscreteSequentialSolver, solution "); if (debug) solution->print("DiscreteSequentialSolver, solution ");

View File

@ -115,10 +115,10 @@ typename EliminationTree<FACTOR>::shared_ptr EliminationTree<FACTOR>::Create(
static const bool debug = false; static const bool debug = false;
tic(ET_ComputeParents); gttic(ET_ComputeParents);
// Compute the tree structure // Compute the tree structure
std::vector<Index> parents(ComputeParents(structure)); std::vector<Index> parents(ComputeParents(structure));
toc(ET_ComputeParents); gttoc(ET_ComputeParents);
// Number of variables // Number of variables
const size_t n = structure.size(); const size_t n = structure.size();
@ -126,7 +126,7 @@ typename EliminationTree<FACTOR>::shared_ptr EliminationTree<FACTOR>::Create(
static const Index none = std::numeric_limits<Index>::max(); static const Index none = std::numeric_limits<Index>::max();
// Create tree structure // Create tree structure
tic(assemble_tree); gttic(assemble_tree);
std::vector<shared_ptr> trees(n); std::vector<shared_ptr> trees(n);
for (Index k = 1; k <= n; k++) { for (Index k = 1; k <= n; k++) {
Index j = n - k; // Start at the last variable and loop down to 0 Index j = n - k; // Start at the last variable and loop down to 0
@ -136,10 +136,10 @@ typename EliminationTree<FACTOR>::shared_ptr EliminationTree<FACTOR>::Create(
else if(!structure[j].empty() && j != n - 1) // If a node other than the last has no parents, this is a forest else if(!structure[j].empty() && j != n - 1) // If a node other than the last has no parents, this is a forest
throw DisconnectedGraphException(); throw DisconnectedGraphException();
} }
toc(assemble_tree); gttoc(assemble_tree);
// Hang factors in right places // Hang factors in right places
tic(hang_factors); gttic(hang_factors);
BOOST_FOREACH(const typename boost::shared_ptr<DERIVEDFACTOR>& derivedFactor, factorGraph) { BOOST_FOREACH(const typename boost::shared_ptr<DERIVEDFACTOR>& derivedFactor, factorGraph) {
// Here we upwards-cast to the factor type of this EliminationTree. This // Here we upwards-cast to the factor type of this EliminationTree. This
// allows performing symbolic elimination on, for example, GaussianFactors. // allows performing symbolic elimination on, for example, GaussianFactors.
@ -150,7 +150,7 @@ typename EliminationTree<FACTOR>::shared_ptr EliminationTree<FACTOR>::Create(
trees[j]->add(factor); trees[j]->add(factor);
} }
} }
toc(hang_factors); gttoc(hang_factors);
if(debug) if(debug)
trees.back()->print("ETree: "); trees.back()->print("ETree: ");
@ -165,9 +165,9 @@ typename EliminationTree<FACTOR>::shared_ptr
EliminationTree<FACTOR>::Create(const FactorGraph<DERIVEDFACTOR>& factorGraph) { EliminationTree<FACTOR>::Create(const FactorGraph<DERIVEDFACTOR>& factorGraph) {
// Build variable index // Build variable index
tic(ET_Create_variable_index); gttic(ET_Create_variable_index);
const VariableIndex variableIndex(factorGraph); const VariableIndex variableIndex(factorGraph);
toc(ET_Create_variable_index); gttoc(ET_Create_variable_index);
// Build elimination tree // Build elimination tree
return Create(factorGraph, variableIndex); return Create(factorGraph, variableIndex);
@ -205,21 +205,21 @@ typename EliminationTree<FACTOR>::BayesNet::shared_ptr
EliminationTree<FACTOR>::eliminatePartial(typename EliminationTree<FACTOR>::Eliminate function, size_t nrToEliminate) const { EliminationTree<FACTOR>::eliminatePartial(typename EliminationTree<FACTOR>::Eliminate function, size_t nrToEliminate) const {
// call recursive routine // call recursive routine
tic(ET_recursive_eliminate); gttic(ET_recursive_eliminate);
if(nrToEliminate > this->key_ + 1) if(nrToEliminate > this->key_ + 1)
throw std::invalid_argument("Requested that EliminationTree::eliminatePartial eliminate more variables than exist"); throw std::invalid_argument("Requested that EliminationTree::eliminatePartial eliminate more variables than exist");
Conditionals conditionals(nrToEliminate); // reserve a vector of conditional shared pointers Conditionals conditionals(nrToEliminate); // reserve a vector of conditional shared pointers
(void)eliminate_(function, conditionals); // modify in place (void)eliminate_(function, conditionals); // modify in place
toc(ET_recursive_eliminate); gttoc(ET_recursive_eliminate);
// Add conditionals to BayesNet // Add conditionals to BayesNet
tic(assemble_BayesNet); gttic(assemble_BayesNet);
typename BayesNet::shared_ptr bayesNet(new BayesNet); typename BayesNet::shared_ptr bayesNet(new BayesNet);
BOOST_FOREACH(const typename BayesNet::sharedConditional& conditional, conditionals) { BOOST_FOREACH(const typename BayesNet::sharedConditional& conditional, conditionals) {
if(conditional) if(conditional)
bayesNet->push_back(conditional); bayesNet->push_back(conditional);
} }
toc(assemble_BayesNet); gttoc(assemble_BayesNet);
return bayesNet; return bayesNet;
} }

View File

@ -31,29 +31,29 @@ namespace gtsam {
/* ************************************************************************* */ /* ************************************************************************* */
template <class FG, class BTCLIQUE> template <class FG, class BTCLIQUE>
void JunctionTree<FG,BTCLIQUE>::construct(const FG& fg, const VariableIndex& variableIndex) { void JunctionTree<FG,BTCLIQUE>::construct(const FG& fg, const VariableIndex& variableIndex) {
tic(JT_symbolic_ET); gttic(JT_symbolic_ET);
const typename EliminationTree<IndexFactor>::shared_ptr symETree = const typename EliminationTree<IndexFactor>::shared_ptr symETree =
EliminationTree<IndexFactor>::Create(fg, variableIndex); EliminationTree<IndexFactor>::Create(fg, variableIndex);
toc(JT_symbolic_ET); gttoc(JT_symbolic_ET);
tic(JT_symbolic_eliminate); gttic(JT_symbolic_eliminate);
SymbolicBayesNet::shared_ptr sbn = symETree->eliminate(&EliminateSymbolic); SymbolicBayesNet::shared_ptr sbn = symETree->eliminate(&EliminateSymbolic);
toc(JT_symbolic_eliminate); gttoc(JT_symbolic_eliminate);
tic(symbolic_BayesTree); gttic(symbolic_BayesTree);
SymbolicBayesTree sbt(*sbn); SymbolicBayesTree sbt(*sbn);
toc(symbolic_BayesTree); gttoc(symbolic_BayesTree);
// distribute factors // distribute factors
tic(distributeFactors); gttic(distributeFactors);
this->root_ = distributeFactors(fg, sbt.root()); this->root_ = distributeFactors(fg, sbt.root());
toc(distributeFactors); gttoc(distributeFactors);
} }
/* ************************************************************************* */ /* ************************************************************************* */
template <class FG, class BTCLIQUE> template <class FG, class BTCLIQUE>
JunctionTree<FG,BTCLIQUE>::JunctionTree(const FG& fg) { JunctionTree<FG,BTCLIQUE>::JunctionTree(const FG& fg) {
tic(VariableIndex); gttic(VariableIndex);
VariableIndex varIndex(fg); VariableIndex varIndex(fg);
toc(VariableIndex); gttoc(VariableIndex);
construct(fg, varIndex); construct(fg, varIndex);
} }
@ -162,14 +162,14 @@ namespace gtsam {
// Now that we know which factors and variables, and where variables // Now that we know which factors and variables, and where variables
// come from and go to, create and eliminate the new joint factor. // come from and go to, create and eliminate the new joint factor.
tic(CombineAndEliminate); gttic(CombineAndEliminate);
typename FG::EliminationResult eliminated(function(fg, typename FG::EliminationResult eliminated(function(fg,
current->frontal.size())); current->frontal.size()));
toc(CombineAndEliminate); gttoc(CombineAndEliminate);
assert(std::equal(eliminated.second->begin(), eliminated.second->end(), current->separator.begin())); assert(std::equal(eliminated.second->begin(), eliminated.second->end(), current->separator.begin()));
tic(Update_tree); gttic(Update_tree);
// create a new clique corresponding the combined factors // create a new clique corresponding the combined factors
typename BTClique::shared_ptr new_clique(BTClique::Create(eliminated)); typename BTClique::shared_ptr new_clique(BTClique::Create(eliminated));
new_clique->children_ = children; new_clique->children_ = children;
@ -177,7 +177,7 @@ namespace gtsam {
BOOST_FOREACH(typename BTClique::shared_ptr& childRoot, children) { BOOST_FOREACH(typename BTClique::shared_ptr& childRoot, children) {
childRoot->parent_ = new_clique; childRoot->parent_ = new_clique;
} }
toc(Update_tree); gttoc(Update_tree);
return std::make_pair(new_clique, eliminated.second); return std::make_pair(new_clique, eliminated.second);
} }
@ -187,12 +187,12 @@ namespace gtsam {
typename BTCLIQUE::shared_ptr JunctionTree<FG,BTCLIQUE>::eliminate( typename BTCLIQUE::shared_ptr JunctionTree<FG,BTCLIQUE>::eliminate(
typename FG::Eliminate function) const { typename FG::Eliminate function) const {
if (this->root()) { if (this->root()) {
tic(JT_eliminate); gttic(JT_eliminate);
std::pair<typename BTClique::shared_ptr, typename FG::sharedFactor> ret = std::pair<typename BTClique::shared_ptr, typename FG::sharedFactor> ret =
this->eliminateOneClique(function, this->root()); this->eliminateOneClique(function, this->root());
if (ret.second->size() != 0) throw std::runtime_error( if (ret.second->size() != 0) throw std::runtime_error(
"JuntionTree::eliminate: elimination failed because of factors left over!"); "JuntionTree::eliminate: elimination failed because of factors left over!");
toc(JT_eliminate); gttoc(JT_eliminate);
return ret.first; return ret.first;
} else } else
return typename BTClique::shared_ptr(); return typename BTClique::shared_ptr();

View File

@ -142,9 +142,9 @@ VectorValues backSubstituteTranspose(const GaussianBayesNet& bn,
/* ************************************************************************* */ /* ************************************************************************* */
VectorValues optimizeGradientSearch(const GaussianBayesNet& Rd) { VectorValues optimizeGradientSearch(const GaussianBayesNet& Rd) {
tic(Allocate_VectorValues); gttic(Allocate_VectorValues);
VectorValues grad = *allocateVectorValues(Rd); VectorValues grad = *allocateVectorValues(Rd);
toc(Allocate_VectorValues); gttoc(Allocate_VectorValues);
optimizeGradientSearchInPlace(Rd, grad); optimizeGradientSearchInPlace(Rd, grad);
@ -153,27 +153,27 @@ VectorValues optimizeGradientSearch(const GaussianBayesNet& Rd) {
/* ************************************************************************* */ /* ************************************************************************* */
void optimizeGradientSearchInPlace(const GaussianBayesNet& Rd, VectorValues& grad) { void optimizeGradientSearchInPlace(const GaussianBayesNet& Rd, VectorValues& grad) {
tic(Compute_Gradient); gttic(Compute_Gradient);
// Compute gradient (call gradientAtZero function, which is defined for various linear systems) // Compute gradient (call gradientAtZero function, which is defined for various linear systems)
gradientAtZero(Rd, grad); gradientAtZero(Rd, grad);
double gradientSqNorm = grad.dot(grad); double gradientSqNorm = grad.dot(grad);
toc(Compute_Gradient); gttoc(Compute_Gradient);
tic(Compute_Rg); gttic(Compute_Rg);
// Compute R * g // Compute R * g
FactorGraph<JacobianFactor> Rd_jfg(Rd); FactorGraph<JacobianFactor> Rd_jfg(Rd);
Errors Rg = Rd_jfg * grad; Errors Rg = Rd_jfg * grad;
toc(Compute_Rg); gttoc(Compute_Rg);
tic(Compute_minimizing_step_size); gttic(Compute_minimizing_step_size);
// Compute minimizing step size // Compute minimizing step size
double step = -gradientSqNorm / dot(Rg, Rg); double step = -gradientSqNorm / dot(Rg, Rg);
toc(Compute_minimizing_step_size); gttoc(Compute_minimizing_step_size);
tic(Compute_point); gttic(Compute_point);
// Compute steepest descent point // Compute steepest descent point
scal(step, grad); scal(step, grad);
toc(Compute_point); gttoc(Compute_point);
} }
/* ************************************************************************* */ /* ************************************************************************* */

View File

@ -36,9 +36,9 @@ void optimizeInPlace(const GaussianBayesTree& bayesTree, VectorValues& result) {
/* ************************************************************************* */ /* ************************************************************************* */
VectorValues optimizeGradientSearch(const GaussianBayesTree& bayesTree) { VectorValues optimizeGradientSearch(const GaussianBayesTree& bayesTree) {
tic(Allocate_VectorValues); gttic(Allocate_VectorValues);
VectorValues grad = *allocateVectorValues(bayesTree); VectorValues grad = *allocateVectorValues(bayesTree);
toc(Allocate_VectorValues); gttoc(Allocate_VectorValues);
optimizeGradientSearchInPlace(bayesTree, grad); optimizeGradientSearchInPlace(bayesTree, grad);
@ -47,27 +47,27 @@ VectorValues optimizeGradientSearch(const GaussianBayesTree& bayesTree) {
/* ************************************************************************* */ /* ************************************************************************* */
void optimizeGradientSearchInPlace(const GaussianBayesTree& bayesTree, VectorValues& grad) { void optimizeGradientSearchInPlace(const GaussianBayesTree& bayesTree, VectorValues& grad) {
tic(Compute_Gradient); gttic(Compute_Gradient);
// Compute gradient (call gradientAtZero function, which is defined for various linear systems) // Compute gradient (call gradientAtZero function, which is defined for various linear systems)
gradientAtZero(bayesTree, grad); gradientAtZero(bayesTree, grad);
double gradientSqNorm = grad.dot(grad); double gradientSqNorm = grad.dot(grad);
toc(Compute_Gradient); gttoc(Compute_Gradient);
tic(Compute_Rg); gttic(Compute_Rg);
// Compute R * g // Compute R * g
FactorGraph<JacobianFactor> Rd_jfg(bayesTree); FactorGraph<JacobianFactor> Rd_jfg(bayesTree);
Errors Rg = Rd_jfg * grad; Errors Rg = Rd_jfg * grad;
toc(Compute_Rg); gttoc(Compute_Rg);
tic(Compute_minimizing_step_size); gttic(Compute_minimizing_step_size);
// Compute minimizing step size // Compute minimizing step size
double step = -gradientSqNorm / dot(Rg, Rg); double step = -gradientSqNorm / dot(Rg, Rg);
toc(Compute_minimizing_step_size); gttoc(Compute_minimizing_step_size);
tic(Compute_point); gttic(Compute_point);
// Compute steepest descent point // Compute steepest descent point
scal(step, grad); scal(step, grad);
toc(Compute_point); gttoc(Compute_point);
} }
/* ************************************************************************* */ /* ************************************************************************* */

View File

@ -253,7 +253,7 @@ break;
if (debug) variableSlots.print(); if (debug) variableSlots.print();
if (debug) cout << "Determine dimensions" << endl; if (debug) cout << "Determine dimensions" << endl;
tic(countDims); gttic(countDims);
vector<size_t> varDims; vector<size_t> varDims;
size_t m, n; size_t m, n;
boost::tie(varDims, m, n) = countDims(factors, variableSlots); boost::tie(varDims, m, n) = countDims(factors, variableSlots);
@ -262,17 +262,17 @@ break;
BOOST_FOREACH(const size_t dim, varDims) cout << dim << " "; BOOST_FOREACH(const size_t dim, varDims) cout << dim << " ";
cout << endl; cout << endl;
} }
toc(countDims); gttoc(countDims);
if (debug) cout << "Allocate new factor" << endl; if (debug) cout << "Allocate new factor" << endl;
tic(allocate); gttic(allocate);
JacobianFactor::shared_ptr combined(new JacobianFactor()); JacobianFactor::shared_ptr combined(new JacobianFactor());
combined->allocate(variableSlots, varDims, m); combined->allocate(variableSlots, varDims, m);
Vector sigmas(m); Vector sigmas(m);
toc(allocate); gttoc(allocate);
if (debug) cout << "Copy blocks" << endl; if (debug) cout << "Copy blocks" << endl;
tic(copy_blocks); gttic(copy_blocks);
// Loop over slots in combined factor // Loop over slots in combined factor
Index combinedSlot = 0; Index combinedSlot = 0;
BOOST_FOREACH(const VariableSlots::value_type& varslot, variableSlots) { BOOST_FOREACH(const VariableSlots::value_type& varslot, variableSlots) {
@ -293,10 +293,10 @@ break;
} }
++combinedSlot; ++combinedSlot;
} }
toc(copy_blocks); gttoc(copy_blocks);
if (debug) cout << "Copy rhs (b) and sigma" << endl; if (debug) cout << "Copy rhs (b) and sigma" << endl;
tic(copy_vectors); gttic(copy_vectors);
bool anyConstrained = false; bool anyConstrained = false;
// Loop over source factors // Loop over source factors
size_t nextRow = 0; size_t nextRow = 0;
@ -307,12 +307,12 @@ break;
if (factors[factorI]->isConstrained()) anyConstrained = true; if (factors[factorI]->isConstrained()) anyConstrained = true;
nextRow += sourceRows; nextRow += sourceRows;
} }
toc(copy_vectors); gttoc(copy_vectors);
if (debug) cout << "Create noise model from sigmas" << endl; if (debug) cout << "Create noise model from sigmas" << endl;
tic(noise_model); gttic(noise_model);
combined->setModel(anyConstrained, sigmas); combined->setModel(anyConstrained, sigmas);
toc(noise_model); gttoc(noise_model);
if (debug) cout << "Assert Invariants" << endl; if (debug) cout << "Assert Invariants" << endl;
combined->assertInvariants(); combined->assertInvariants();
@ -323,13 +323,13 @@ break;
/* ************************************************************************* */ /* ************************************************************************* */
GaussianFactorGraph::EliminationResult EliminateJacobians(const FactorGraph< GaussianFactorGraph::EliminationResult EliminateJacobians(const FactorGraph<
JacobianFactor>& factors, size_t nrFrontals) { JacobianFactor>& factors, size_t nrFrontals) {
tic(Combine); gttic(Combine);
JacobianFactor::shared_ptr jointFactor = JacobianFactor::shared_ptr jointFactor =
CombineJacobians(factors, VariableSlots(factors)); CombineJacobians(factors, VariableSlots(factors));
toc(Combine); gttoc(Combine);
tic(eliminate); gttic(eliminate);
GaussianConditional::shared_ptr gbn = jointFactor->eliminate(nrFrontals); GaussianConditional::shared_ptr gbn = jointFactor->eliminate(nrFrontals);
toc(eliminate); gttoc(eliminate);
return make_pair(gbn, jointFactor); return make_pair(gbn, jointFactor);
} }
@ -397,42 +397,42 @@ break;
const bool debug = ISDEBUG("EliminateCholesky"); const bool debug = ISDEBUG("EliminateCholesky");
// Find the scatter and variable dimensions // Find the scatter and variable dimensions
tic(find_scatter); gttic(find_scatter);
Scatter scatter(findScatterAndDims(factors)); Scatter scatter(findScatterAndDims(factors));
toc(find_scatter); gttoc(find_scatter);
// Pull out keys and dimensions // Pull out keys and dimensions
tic(keys); gttic(keys);
vector<size_t> dimensions(scatter.size() + 1); vector<size_t> dimensions(scatter.size() + 1);
BOOST_FOREACH(const Scatter::value_type& var_slot, scatter) { BOOST_FOREACH(const Scatter::value_type& var_slot, scatter) {
dimensions[var_slot.second.slot] = var_slot.second.dimension; dimensions[var_slot.second.slot] = var_slot.second.dimension;
} }
// This is for the r.h.s. vector // This is for the r.h.s. vector
dimensions.back() = 1; dimensions.back() = 1;
toc(keys); gttoc(keys);
// Form Ab' * Ab // Form Ab' * Ab
tic(combine); gttic(combine);
HessianFactor::shared_ptr combinedFactor(new HessianFactor(factors, dimensions, scatter)); HessianFactor::shared_ptr combinedFactor(new HessianFactor(factors, dimensions, scatter));
toc(combine); gttoc(combine);
// Do Cholesky, note that after this, the lower triangle still contains // Do Cholesky, note that after this, the lower triangle still contains
// some untouched non-zeros that should be zero. We zero them while // some untouched non-zeros that should be zero. We zero them while
// extracting submatrices next. // extracting submatrices next.
tic(partial_Cholesky); gttic(partial_Cholesky);
combinedFactor->partialCholesky(nrFrontals); combinedFactor->partialCholesky(nrFrontals);
toc(partial_Cholesky); gttoc(partial_Cholesky);
// Extract conditional and fill in details of the remaining factor // Extract conditional and fill in details of the remaining factor
tic(split); gttic(split);
GaussianConditional::shared_ptr conditional = GaussianConditional::shared_ptr conditional =
combinedFactor->splitEliminatedFactor(nrFrontals); combinedFactor->splitEliminatedFactor(nrFrontals);
if (debug) { if (debug) {
conditional->print("Extracted conditional: "); conditional->print("Extracted conditional: ");
combinedFactor->print("Eliminated factor (L piece): "); combinedFactor->print("Eliminated factor (L piece): ");
} }
toc(split); gttoc(split);
combinedFactor->assertInvariants(); combinedFactor->assertInvariants();
return make_pair(conditional, combinedFactor); return make_pair(conditional, combinedFactor);
@ -482,15 +482,15 @@ break;
// Convert all factors to the appropriate type and call the type-specific EliminateGaussian. // Convert all factors to the appropriate type and call the type-specific EliminateGaussian.
if (debug) cout << "Using QR" << endl; if (debug) cout << "Using QR" << endl;
tic(convert_to_Jacobian); gttic(convert_to_Jacobian);
FactorGraph<JacobianFactor> jacobians = convertToJacobians(factors); FactorGraph<JacobianFactor> jacobians = convertToJacobians(factors);
toc(convert_to_Jacobian); gttoc(convert_to_Jacobian);
tic(Jacobian_EliminateGaussian); gttic(Jacobian_EliminateGaussian);
GaussianConditional::shared_ptr conditional; GaussianConditional::shared_ptr conditional;
GaussianFactor::shared_ptr factor; GaussianFactor::shared_ptr factor;
boost::tie(conditional, factor) = EliminateJacobians(jacobians, nrFrontals); boost::tie(conditional, factor) = EliminateJacobians(jacobians, nrFrontals);
toc(Jacobian_EliminateGaussian); gttoc(Jacobian_EliminateGaussian);
return make_pair(conditional, factor); return make_pair(conditional, factor);
} // \EliminateQR } // \EliminateQR
@ -522,9 +522,9 @@ break;
return EliminateQR(factors, nrFrontals); return EliminateQR(factors, nrFrontals);
else { else {
GaussianFactorGraph::EliminationResult ret; GaussianFactorGraph::EliminationResult ret;
tic(EliminateCholesky); gttic(EliminateCholesky);
ret = EliminateCholesky(factors, nrFrontals); ret = EliminateCholesky(factors, nrFrontals);
toc(EliminateCholesky); gttoc(EliminateCholesky);
return ret; return ret;
} }

View File

@ -36,22 +36,22 @@ namespace gtsam {
/* ************************************************************************* */ /* ************************************************************************* */
VectorValues GaussianJunctionTree::optimize(Eliminate function) const { VectorValues GaussianJunctionTree::optimize(Eliminate function) const {
tic(GJT_eliminate); gttic(GJT_eliminate);
// eliminate from leaves to the root // eliminate from leaves to the root
BTClique::shared_ptr rootClique(this->eliminate(function)); BTClique::shared_ptr rootClique(this->eliminate(function));
toc(GJT_eliminate); gttoc(GJT_eliminate);
// Allocate solution vector and copy RHS // Allocate solution vector and copy RHS
tic(allocate_VectorValues); gttic(allocate_VectorValues);
vector<size_t> dims(rootClique->conditional()->back()+1, 0); vector<size_t> dims(rootClique->conditional()->back()+1, 0);
countDims(rootClique, dims); countDims(rootClique, dims);
VectorValues result(dims); VectorValues result(dims);
toc(allocate_VectorValues); gttoc(allocate_VectorValues);
// back-substitution // back-substitution
tic(backsubstitute); gttic(backsubstitute);
internal::optimizeInPlace<GaussianBayesTree>(rootClique, result); internal::optimizeInPlace<GaussianBayesTree>(rootClique, result);
toc(backsubstitute); gttoc(backsubstitute);
return result; return result;
} }

View File

@ -51,13 +51,13 @@ GaussianBayesTree::shared_ptr GaussianMultifrontalSolver::eliminate() const {
/* ************************************************************************* */ /* ************************************************************************* */
VectorValues::shared_ptr GaussianMultifrontalSolver::optimize() const { VectorValues::shared_ptr GaussianMultifrontalSolver::optimize() const {
tic(optimize); gttic(optimize);
VectorValues::shared_ptr values; VectorValues::shared_ptr values;
if (useQR_) if (useQR_)
values = VectorValues::shared_ptr(new VectorValues(junctionTree_->optimize(&EliminateQR))); values = VectorValues::shared_ptr(new VectorValues(junctionTree_->optimize(&EliminateQR)));
else else
values= VectorValues::shared_ptr(new VectorValues(junctionTree_->optimize(&EliminatePreferCholesky))); values= VectorValues::shared_ptr(new VectorValues(junctionTree_->optimize(&EliminatePreferCholesky)));
toc(optimize); gttoc(optimize);
return values; return values;
} }

View File

@ -64,21 +64,21 @@ VectorValues::shared_ptr GaussianSequentialSolver::optimize() const {
if(debug) this->factors_->print("GaussianSequentialSolver, eliminating "); if(debug) this->factors_->print("GaussianSequentialSolver, eliminating ");
if(debug) this->eliminationTree_->print("GaussianSequentialSolver, elimination tree "); if(debug) this->eliminationTree_->print("GaussianSequentialSolver, elimination tree ");
tic(eliminate); gttic(eliminate);
// Eliminate using the elimination tree // Eliminate using the elimination tree
GaussianBayesNet::shared_ptr bayesNet(this->eliminate()); GaussianBayesNet::shared_ptr bayesNet(this->eliminate());
toc(eliminate); gttoc(eliminate);
if(debug) bayesNet->print("GaussianSequentialSolver, Bayes net "); if(debug) bayesNet->print("GaussianSequentialSolver, Bayes net ");
// Allocate the solution vector if it is not already allocated // Allocate the solution vector if it is not already allocated
// VectorValues::shared_ptr solution = allocateVectorValues(*bayesNet); // VectorValues::shared_ptr solution = allocateVectorValues(*bayesNet);
tic(optimize); gttic(optimize);
// Back-substitute // Back-substitute
VectorValues::shared_ptr solution( VectorValues::shared_ptr solution(
new VectorValues(gtsam::optimize(*bayesNet))); new VectorValues(gtsam::optimize(*bayesNet)));
toc(optimize); gttoc(optimize);
if(debug) solution->print("GaussianSequentialSolver, solution "); if(debug) solution->print("GaussianSequentialSolver, solution ");

View File

@ -251,16 +251,16 @@ HessianFactor::HessianFactor(const FactorGraph<GaussianFactor>& factors,
const bool debug = ISDEBUG("EliminateCholesky"); const bool debug = ISDEBUG("EliminateCholesky");
// Form Ab' * Ab // Form Ab' * Ab
tic(allocate); gttic(allocate);
info_.resize(dimensions.begin(), dimensions.end(), false); info_.resize(dimensions.begin(), dimensions.end(), false);
// Fill in keys // Fill in keys
keys_.resize(scatter.size()); keys_.resize(scatter.size());
std::transform(scatter.begin(), scatter.end(), keys_.begin(), boost::bind(&Scatter::value_type::first, ::_1)); std::transform(scatter.begin(), scatter.end(), keys_.begin(), boost::bind(&Scatter::value_type::first, ::_1));
toc(allocate); gttoc(allocate);
tic(zero); gttic(zero);
matrix_.noalias() = Matrix::Zero(matrix_.rows(),matrix_.cols()); matrix_.noalias() = Matrix::Zero(matrix_.rows(),matrix_.cols());
toc(zero); gttoc(zero);
tic(update); gttic(update);
if (debug) cout << "Combining " << factors.size() << " factors" << endl; if (debug) cout << "Combining " << factors.size() << " factors" << endl;
BOOST_FOREACH(const GaussianFactor::shared_ptr& factor, factors) BOOST_FOREACH(const GaussianFactor::shared_ptr& factor, factors)
{ {
@ -273,7 +273,7 @@ HessianFactor::HessianFactor(const FactorGraph<GaussianFactor>& factors,
throw invalid_argument("GaussianFactor is neither Hessian nor Jacobian"); throw invalid_argument("GaussianFactor is neither Hessian nor Jacobian");
} }
} }
toc(update); gttoc(update);
if (debug) gtsam::print(matrix_, "Ab' * Ab: "); if (debug) gtsam::print(matrix_, "Ab' * Ab: ");
@ -335,14 +335,14 @@ void HessianFactor::updateATA(const HessianFactor& update, const Scatter& scatte
const bool debug = ISDEBUG("updateATA"); const bool debug = ISDEBUG("updateATA");
// First build an array of slots // First build an array of slots
tic(slots); gttic(slots);
size_t* slots = (size_t*)alloca(sizeof(size_t)*update.size()); // FIXME: alloca is bad, just ask Google. size_t* slots = (size_t*)alloca(sizeof(size_t)*update.size()); // FIXME: alloca is bad, just ask Google.
size_t slot = 0; size_t slot = 0;
BOOST_FOREACH(Index j, update) { BOOST_FOREACH(Index j, update) {
slots[slot] = scatter.find(j)->second.slot; slots[slot] = scatter.find(j)->second.slot;
++ slot; ++ slot;
} }
toc(slots); gttoc(slots);
if(debug) { if(debug) {
this->print("Updating this: "); this->print("Updating this: ");
@ -350,7 +350,7 @@ void HessianFactor::updateATA(const HessianFactor& update, const Scatter& scatte
} }
// Apply updates to the upper triangle // Apply updates to the upper triangle
tic(update); gttic(update);
for(size_t j2=0; j2<update.info_.nBlocks(); ++j2) { for(size_t j2=0; j2<update.info_.nBlocks(); ++j2) {
size_t slot2 = (j2 == update.size()) ? this->info_.nBlocks()-1 : slots[j2]; size_t slot2 = (j2 == update.size()) ? this->info_.nBlocks()-1 : slots[j2];
for(size_t j1=0; j1<=j2; ++j1) { for(size_t j1=0; j1<=j2; ++j1) {
@ -375,7 +375,7 @@ void HessianFactor::updateATA(const HessianFactor& update, const Scatter& scatte
if(debug) this->print(); if(debug) this->print();
} }
} }
toc(update); gttoc(update);
} }
/* ************************************************************************* */ /* ************************************************************************* */
@ -388,16 +388,16 @@ void HessianFactor::updateATA(const JacobianFactor& update, const Scatter& scatt
const bool debug = ISDEBUG("updateATA"); const bool debug = ISDEBUG("updateATA");
// First build an array of slots // First build an array of slots
tic(slots); gttic(slots);
size_t* slots = (size_t*)alloca(sizeof(size_t)*update.size()); // FIXME: alloca is bad, just ask Google. size_t* slots = (size_t*)alloca(sizeof(size_t)*update.size()); // FIXME: alloca is bad, just ask Google.
size_t slot = 0; size_t slot = 0;
BOOST_FOREACH(Index j, update) { BOOST_FOREACH(Index j, update) {
slots[slot] = scatter.find(j)->second.slot; slots[slot] = scatter.find(j)->second.slot;
++ slot; ++ slot;
} }
toc(slots); gttoc(slots);
tic(form_ATA); gttic(form_ATA);
if(update.model_->isConstrained()) if(update.model_->isConstrained())
throw invalid_argument("Cannot update HessianFactor from JacobianFactor with constrained noise model"); throw invalid_argument("Cannot update HessianFactor from JacobianFactor with constrained noise model");
@ -423,10 +423,10 @@ void HessianFactor::updateATA(const JacobianFactor& update, const Scatter& scatt
throw invalid_argument("In HessianFactor::updateATA, JacobianFactor noise model is neither Unit nor Diagonal"); throw invalid_argument("In HessianFactor::updateATA, JacobianFactor noise model is neither Unit nor Diagonal");
} }
if (debug) cout << "updateInform: \n" << updateInform << endl; if (debug) cout << "updateInform: \n" << updateInform << endl;
toc(form_ATA); gttoc(form_ATA);
// Apply updates to the upper triangle // Apply updates to the upper triangle
tic(update); gttic(update);
for(size_t j2=0; j2<update.Ab_.nBlocks(); ++j2) { for(size_t j2=0; j2<update.Ab_.nBlocks(); ++j2) {
size_t slot2 = (j2 == update.size()) ? this->info_.nBlocks()-1 : slots[j2]; size_t slot2 = (j2 == update.size()) ? this->info_.nBlocks()-1 : slots[j2];
for(size_t j1=0; j1<=j2; ++j1) { for(size_t j1=0; j1<=j2; ++j1) {
@ -452,7 +452,7 @@ void HessianFactor::updateATA(const JacobianFactor& update, const Scatter& scatt
if(debug) this->print(); if(debug) this->print();
} }
} }
toc(update); gttoc(update);
} }
/* ************************************************************************* */ /* ************************************************************************* */
@ -467,7 +467,7 @@ GaussianConditional::shared_ptr HessianFactor::splitEliminatedFactor(size_t nrFr
static const bool debug = false; static const bool debug = false;
// Extract conditionals // Extract conditionals
tic(extract_conditionals); gttic(extract_conditionals);
GaussianConditional::shared_ptr conditional(new GaussianConditional()); GaussianConditional::shared_ptr conditional(new GaussianConditional());
typedef VerticalBlockView<Matrix> BlockAb; typedef VerticalBlockView<Matrix> BlockAb;
BlockAb Ab(matrix_, info_); BlockAb Ab(matrix_, info_);
@ -476,22 +476,22 @@ GaussianConditional::shared_ptr HessianFactor::splitEliminatedFactor(size_t nrFr
Ab.rowEnd() = Ab.rowStart() + varDim; Ab.rowEnd() = Ab.rowStart() + varDim;
// Create one big conditionals with many frontal variables. // Create one big conditionals with many frontal variables.
tic(construct_cond); gttic(construct_cond);
Vector sigmas = Vector::Ones(varDim); Vector sigmas = Vector::Ones(varDim);
conditional = boost::make_shared<ConditionalType>(keys_.begin(), keys_.end(), nrFrontals, Ab, sigmas); conditional = boost::make_shared<ConditionalType>(keys_.begin(), keys_.end(), nrFrontals, Ab, sigmas);
toc(construct_cond); gttoc(construct_cond);
if(debug) conditional->print("Extracted conditional: "); if(debug) conditional->print("Extracted conditional: ");
toc(extract_conditionals); gttoc(extract_conditionals);
// Take lower-right block of Ab_ to get the new factor // Take lower-right block of Ab_ to get the new factor
tic(remaining_factor); gttic(remaining_factor);
info_.blockStart() = nrFrontals; info_.blockStart() = nrFrontals;
// Assign the keys // Assign the keys
vector<Index> remainingKeys(keys_.size() - nrFrontals); vector<Index> remainingKeys(keys_.size() - nrFrontals);
remainingKeys.assign(keys_.begin() + nrFrontals, keys_.end()); remainingKeys.assign(keys_.begin() + nrFrontals, keys_.end());
keys_.swap(remainingKeys); keys_.swap(remainingKeys);
toc(remaining_factor); gttoc(remaining_factor);
return conditional; return conditional;
} }

View File

@ -388,7 +388,7 @@ namespace gtsam {
throw IndeterminantLinearSystemException(this->keys().front()); throw IndeterminantLinearSystemException(this->keys().front());
// Extract conditional // Extract conditional
tic(cond_Rd); gttic(cond_Rd);
// Restrict the matrix to be in the first nrFrontals variables // Restrict the matrix to be in the first nrFrontals variables
Ab_.rowEnd() = Ab_.rowStart() + frontalDim; Ab_.rowEnd() = Ab_.rowStart() + frontalDim;
@ -397,11 +397,11 @@ namespace gtsam {
if(debug) conditional->print("Extracted conditional: "); if(debug) conditional->print("Extracted conditional: ");
Ab_.rowStart() += frontalDim; Ab_.rowStart() += frontalDim;
Ab_.firstBlock() += nrFrontals; Ab_.firstBlock() += nrFrontals;
toc(cond_Rd); gttoc(cond_Rd);
if(debug) conditional->print("Extracted conditional: "); if(debug) conditional->print("Extracted conditional: ");
tic(remaining_factor); gttic(remaining_factor);
// Take lower-right block of Ab to get the new factor // Take lower-right block of Ab to get the new factor
Ab_.rowEnd() = model_->dim(); Ab_.rowEnd() = model_->dim();
keys_.erase(begin(), begin() + nrFrontals); keys_.erase(begin(), begin() + nrFrontals);
@ -412,7 +412,7 @@ namespace gtsam {
model_ = noiseModel::Diagonal::Sigmas(sub(model_->sigmas(), frontalDim, model_->dim())); model_ = noiseModel::Diagonal::Sigmas(sub(model_->sigmas(), frontalDim, model_->dim()));
if(debug) this->print("Eliminated factor: "); if(debug) this->print("Eliminated factor: ");
assert(Ab_.rows() <= Ab_.cols()-1); assert(Ab_.rows() <= Ab_.cols()-1);
toc(remaining_factor); gttoc(remaining_factor);
if(debug) print("Eliminated factor: "); if(debug) print("Eliminated factor: ");
@ -439,9 +439,9 @@ namespace gtsam {
if(debug) cout << "frontalDim = " << frontalDim << endl; if(debug) cout << "frontalDim = " << frontalDim << endl;
// Use in-place QR dense Ab appropriate to NoiseModel // Use in-place QR dense Ab appropriate to NoiseModel
tic(QR); gttic(QR);
SharedDiagonal noiseModel = model_->QR(matrix_); SharedDiagonal noiseModel = model_->QR(matrix_);
toc(QR); gttoc(QR);
// Zero the lower-left triangle. todo: not all of these entries actually // Zero the lower-left triangle. todo: not all of these entries actually
// need to be zeroed if we are careful to start copying rows after the last // need to be zeroed if we are careful to start copying rows after the last

View File

@ -329,22 +329,22 @@ SharedDiagonal Constrained::QR(Matrix& Ab) const {
Vector a = Ab.col(j); Vector a = Ab.col(j);
// Calculate weighted pseudo-inverse and corresponding precision // Calculate weighted pseudo-inverse and corresponding precision
tic(constrained_QR_weightedPseudoinverse); gttic(constrained_QR_weightedPseudoinverse);
double precision = weightedPseudoinverse(a, weights, pseudo); double precision = weightedPseudoinverse(a, weights, pseudo);
toc(constrained_QR_weightedPseudoinverse); gttoc(constrained_QR_weightedPseudoinverse);
// If precision is zero, no information on this column // If precision is zero, no information on this column
// This is actually not limited to constraints, could happen in Gaussian::QR // This is actually not limited to constraints, could happen in Gaussian::QR
// In that case, we're probably hosed. TODO: make sure Householder is rank-revealing // In that case, we're probably hosed. TODO: make sure Householder is rank-revealing
if (precision < 1e-8) continue; if (precision < 1e-8) continue;
tic(constrained_QR_create_rd); gttic(constrained_QR_create_rd);
// create solution [r d], rhs is automatically r(n) // create solution [r d], rhs is automatically r(n)
Vector rd(n+1); // uninitialized ! Vector rd(n+1); // uninitialized !
rd(j)=1.0; // put 1 on diagonal rd(j)=1.0; // put 1 on diagonal
for (size_t j2=j+1; j2<n+1; ++j2) // and fill in remainder with dot-products for (size_t j2=j+1; j2<n+1; ++j2) // and fill in remainder with dot-products
rd(j2) = pseudo.dot(Ab.col(j2)); rd(j2) = pseudo.dot(Ab.col(j2));
toc(constrained_QR_create_rd); gttoc(constrained_QR_create_rd);
// construct solution (r, d, sigma) // construct solution (r, d, sigma)
Rd.push_back(boost::make_tuple(j, rd, precision)); Rd.push_back(boost::make_tuple(j, rd, precision));
@ -353,15 +353,15 @@ SharedDiagonal Constrained::QR(Matrix& Ab) const {
if (Rd.size()>=maxRank) break; if (Rd.size()>=maxRank) break;
// update Ab, expensive, using outer product // update Ab, expensive, using outer product
tic(constrained_QR_update_Ab); gttic(constrained_QR_update_Ab);
Ab.middleCols(j+1,n-j) -= a * rd.segment(j+1, n-j).transpose(); Ab.middleCols(j+1,n-j) -= a * rd.segment(j+1, n-j).transpose();
toc(constrained_QR_update_Ab); gttoc(constrained_QR_update_Ab);
} }
// Create storage for precisions // Create storage for precisions
Vector precisions(Rd.size()); Vector precisions(Rd.size());
tic(constrained_QR_write_back_into_Ab); gttic(constrained_QR_write_back_into_Ab);
// Write back result in Ab, imperative as we are // Write back result in Ab, imperative as we are
// TODO: test that is correct if a column was skipped !!!! // TODO: test that is correct if a column was skipped !!!!
size_t i = 0; // start with first row size_t i = 0; // start with first row
@ -377,7 +377,7 @@ SharedDiagonal Constrained::QR(Matrix& Ab) const {
Ab(i,j2) = rd(j2); Ab(i,j2) = rd(j2);
i+=1; i+=1;
} }
toc(constrained_QR_write_back_into_Ab); gttoc(constrained_QR_write_back_into_Ab);
// Must include mu, as the defaults might be higher, resulting in non-convergence // Must include mu, as the defaults might be higher, resulting in non-convergence
return mixed ? Constrained::MixedPrecisions(mu_, precisions) : Diagonal::Precisions(precisions); return mixed ? Constrained::MixedPrecisions(mu_, precisions) : Diagonal::Precisions(precisions);

View File

@ -149,22 +149,22 @@ typename DoglegOptimizerImpl::IterationResult DoglegOptimizerImpl::Iterate(
const F& f, const VALUES& x0, const Ordering& ordering, const double f_error, const bool verbose) { const F& f, const VALUES& x0, const Ordering& ordering, const double f_error, const bool verbose) {
// Compute steepest descent and Newton's method points // Compute steepest descent and Newton's method points
tic(optimizeGradientSearch); gttic(optimizeGradientSearch);
tic(allocateVectorValues); gttic(allocateVectorValues);
VectorValues dx_u = *allocateVectorValues(Rd); VectorValues dx_u = *allocateVectorValues(Rd);
toc(allocateVectorValues); gttoc(allocateVectorValues);
tic(optimizeGradientSearchInPlace); gttic(optimizeGradientSearchInPlace);
optimizeGradientSearchInPlace(Rd, dx_u); optimizeGradientSearchInPlace(Rd, dx_u);
toc(optimizeGradientSearchInPlace); gttoc(optimizeGradientSearchInPlace);
toc(optimizeGradientSearch); gttoc(optimizeGradientSearch);
tic(optimizeInPlace); gttic(optimizeInPlace);
VectorValues dx_n(VectorValues::SameStructure(dx_u)); VectorValues dx_n(VectorValues::SameStructure(dx_u));
optimizeInPlace(Rd, dx_n); optimizeInPlace(Rd, dx_n);
toc(optimizeInPlace); gttoc(optimizeInPlace);
tic(jfg_error); gttic(jfg_error);
const GaussianFactorGraph jfg(Rd); const GaussianFactorGraph jfg(Rd);
const double M_error = jfg.error(VectorValues::Zero(dx_u)); const double M_error = jfg.error(VectorValues::Zero(dx_u));
toc(jfg_error); gttoc(jfg_error);
// Result to return // Result to return
IterationResult result; IterationResult result;
@ -172,32 +172,32 @@ typename DoglegOptimizerImpl::IterationResult DoglegOptimizerImpl::Iterate(
bool stay = true; bool stay = true;
enum { NONE, INCREASED_DELTA, DECREASED_DELTA } lastAction = NONE; // Used to prevent alternating between increasing and decreasing in one iteration enum { NONE, INCREASED_DELTA, DECREASED_DELTA } lastAction = NONE; // Used to prevent alternating between increasing and decreasing in one iteration
while(stay) { while(stay) {
tic(Dog_leg_point); gttic(Dog_leg_point);
// Compute dog leg point // Compute dog leg point
result.dx_d = ComputeDoglegPoint(Delta, dx_u, dx_n, verbose); result.dx_d = ComputeDoglegPoint(Delta, dx_u, dx_n, verbose);
toc(Dog_leg_point); gttoc(Dog_leg_point);
if(verbose) std::cout << "Delta = " << Delta << ", dx_d_norm = " << result.dx_d.vector().norm() << std::endl; if(verbose) std::cout << "Delta = " << Delta << ", dx_d_norm = " << result.dx_d.vector().norm() << std::endl;
tic(retract); gttic(retract);
// Compute expmapped solution // Compute expmapped solution
const VALUES x_d(x0.retract(result.dx_d, ordering)); const VALUES x_d(x0.retract(result.dx_d, ordering));
toc(retract); gttoc(retract);
tic(decrease_in_f); gttic(decrease_in_f);
// Compute decrease in f // Compute decrease in f
result.f_error = f.error(x_d); result.f_error = f.error(x_d);
toc(decrease_in_f); gttoc(decrease_in_f);
tic(decrease_in_M); gttic(decrease_in_M);
// Compute decrease in M // Compute decrease in M
const double new_M_error = jfg.error(result.dx_d); const double new_M_error = jfg.error(result.dx_d);
toc(decrease_in_M); gttoc(decrease_in_M);
if(verbose) std::cout << std::setprecision(15) << "f error: " << f_error << " -> " << result.f_error << std::endl; if(verbose) std::cout << std::setprecision(15) << "f error: " << f_error << " -> " << result.f_error << std::endl;
if(verbose) std::cout << std::setprecision(15) << "M error: " << M_error << " -> " << new_M_error << std::endl; if(verbose) std::cout << std::setprecision(15) << "M error: " << M_error << " -> " << new_M_error << std::endl;
tic(adjust_Delta); gttic(adjust_Delta);
// Compute gain ratio. Here we take advantage of the invariant that the // Compute gain ratio. Here we take advantage of the invariant that the
// Bayes' net error at zero is equal to the nonlinear error // Bayes' net error at zero is equal to the nonlinear error
const double rho = fabs(f_error - result.f_error) < 1e-15 || fabs(M_error - new_M_error) < 1e-15 ? const double rho = fabs(f_error - result.f_error) < 1e-15 || fabs(M_error - new_M_error) < 1e-15 ?
@ -266,7 +266,7 @@ typename DoglegOptimizerImpl::IterationResult DoglegOptimizerImpl::Iterate(
stay = false; stay = false;
} }
} }
toc(adjust_Delta); gttoc(adjust_Delta);
} }
// dx_d and f_error have already been filled in during the loop // dx_d and f_error have already been filled in during the loop

View File

@ -302,7 +302,7 @@ ISAM2::Impl::PartialSolve(GaussianFactorGraph& factors,
PartialSolveResult result; PartialSolveResult result;
tic(select_affected_variables); gttic(select_affected_variables);
#ifndef NDEBUG #ifndef NDEBUG
// Debug check that all variables involved in the factors to be re-eliminated // Debug check that all variables involved in the factors to be re-eliminated
// are in affectedKeys, since we will use it to select a subset of variables. // are in affectedKeys, since we will use it to select a subset of variables.
@ -326,12 +326,12 @@ ISAM2::Impl::PartialSolve(GaussianFactorGraph& factors,
if(debug) affectedKeysSelectorInverse.print("affectedKeysSelectorInverse: "); if(debug) affectedKeysSelectorInverse.print("affectedKeysSelectorInverse: ");
factors.permuteWithInverse(affectedKeysSelectorInverse); factors.permuteWithInverse(affectedKeysSelectorInverse);
if(debug) factors.print("Factors to reorder/re-eliminate: "); if(debug) factors.print("Factors to reorder/re-eliminate: ");
toc(select_affected_variables); gttoc(select_affected_variables);
tic(variable_index); gttic(variable_index);
VariableIndex affectedFactorsIndex(factors); // Create a variable index for the factors to be re-eliminated VariableIndex affectedFactorsIndex(factors); // Create a variable index for the factors to be re-eliminated
if(debug) affectedFactorsIndex.print("affectedFactorsIndex: "); if(debug) affectedFactorsIndex.print("affectedFactorsIndex: ");
toc(variable_index); gttoc(variable_index);
tic(ccolamd); gttic(ccolamd);
vector<int> cmember(affectedKeysSelector.size(), 0); vector<int> cmember(affectedKeysSelector.size(), 0);
if(reorderingMode.constrain == ReorderingMode::CONSTRAIN_LAST) { if(reorderingMode.constrain == ReorderingMode::CONSTRAIN_LAST) {
assert(reorderingMode.constrainedKeys); assert(reorderingMode.constrainedKeys);
@ -348,8 +348,8 @@ ISAM2::Impl::PartialSolve(GaussianFactorGraph& factors,
} }
} }
Permutation::shared_ptr affectedColamd(inference::PermutationCOLAMD_(affectedFactorsIndex, cmember)); Permutation::shared_ptr affectedColamd(inference::PermutationCOLAMD_(affectedFactorsIndex, cmember));
toc(ccolamd); gttoc(ccolamd);
tic(ccolamd_permutations); gttic(ccolamd_permutations);
Permutation::shared_ptr affectedColamdInverse(affectedColamd->inverse()); Permutation::shared_ptr affectedColamdInverse(affectedColamd->inverse());
if(debug) affectedColamd->print("affectedColamd: "); if(debug) affectedColamd->print("affectedColamd: ");
if(debug) affectedColamdInverse->print("affectedColamdInverse: "); if(debug) affectedColamdInverse->print("affectedColamdInverse: ");
@ -358,15 +358,15 @@ ISAM2::Impl::PartialSolve(GaussianFactorGraph& factors,
result.fullReorderingInverse = result.fullReorderingInverse =
*Permutation::Identity(reorderingMode.nFullSystemVars).partialPermutation(affectedKeysSelector, *affectedColamdInverse); *Permutation::Identity(reorderingMode.nFullSystemVars).partialPermutation(affectedKeysSelector, *affectedColamdInverse);
if(debug) result.fullReordering.print("partialReordering: "); if(debug) result.fullReordering.print("partialReordering: ");
toc(ccolamd_permutations); gttoc(ccolamd_permutations);
tic(permute_affected_variable_index); gttic(permute_affected_variable_index);
affectedFactorsIndex.permuteInPlace(*affectedColamd); affectedFactorsIndex.permuteInPlace(*affectedColamd);
toc(permute_affected_variable_index); gttoc(permute_affected_variable_index);
tic(permute_affected_factors); gttic(permute_affected_factors);
factors.permuteWithInverse(*affectedColamdInverse); factors.permuteWithInverse(*affectedColamdInverse);
toc(permute_affected_factors); gttoc(permute_affected_factors);
if(debug) factors.print("Colamd-ordered affected factors: "); if(debug) factors.print("Colamd-ordered affected factors: ");
@ -376,15 +376,15 @@ ISAM2::Impl::PartialSolve(GaussianFactorGraph& factors,
#endif #endif
// eliminate into a Bayes net // eliminate into a Bayes net
tic(eliminate); gttic(eliminate);
JunctionTree<GaussianFactorGraph, ISAM2::Clique> jt(factors, affectedFactorsIndex); JunctionTree<GaussianFactorGraph, ISAM2::Clique> jt(factors, affectedFactorsIndex);
if(!useQR) if(!useQR)
result.bayesTree = jt.eliminate(EliminatePreferCholesky); result.bayesTree = jt.eliminate(EliminatePreferCholesky);
else else
result.bayesTree = jt.eliminate(EliminateQR); result.bayesTree = jt.eliminate(EliminateQR);
toc(eliminate); gttoc(eliminate);
tic(permute_eliminated); gttic(permute_eliminated);
if(result.bayesTree) result.bayesTree->permuteWithInverse(affectedKeysSelector); if(result.bayesTree) result.bayesTree->permuteWithInverse(affectedKeysSelector);
if(debug && result.bayesTree) { if(debug && result.bayesTree) {
cout << "Full var-ordered eliminated BT:\n"; cout << "Full var-ordered eliminated BT:\n";
@ -393,7 +393,7 @@ ISAM2::Impl::PartialSolve(GaussianFactorGraph& factors,
// Undo permutation on our subset of cached factors, we must later permute *all* of the cached factors // Undo permutation on our subset of cached factors, we must later permute *all* of the cached factors
factors.permuteWithInverse(*affectedColamd); factors.permuteWithInverse(*affectedColamd);
factors.permuteWithInverse(affectedKeysSelector); factors.permuteWithInverse(affectedKeysSelector);
toc(permute_eliminated); gttoc(permute_eliminated);
return result; return result;
} }

View File

@ -171,19 +171,19 @@ FastList<size_t> ISAM2::getAffectedFactors(const FastList<Index>& keys) const {
FactorGraph<GaussianFactor>::shared_ptr FactorGraph<GaussianFactor>::shared_ptr
ISAM2::relinearizeAffectedFactors(const FastList<Index>& affectedKeys, const FastSet<Index>& relinKeys) const { ISAM2::relinearizeAffectedFactors(const FastList<Index>& affectedKeys, const FastSet<Index>& relinKeys) const {
tic(getAffectedFactors); gttic(getAffectedFactors);
FastList<size_t> candidates = getAffectedFactors(affectedKeys); FastList<size_t> candidates = getAffectedFactors(affectedKeys);
toc(getAffectedFactors); gttoc(getAffectedFactors);
NonlinearFactorGraph nonlinearAffectedFactors; NonlinearFactorGraph nonlinearAffectedFactors;
tic(affectedKeysSet); gttic(affectedKeysSet);
// for fast lookup below // for fast lookup below
FastSet<Index> affectedKeysSet; FastSet<Index> affectedKeysSet;
affectedKeysSet.insert(affectedKeys.begin(), affectedKeys.end()); affectedKeysSet.insert(affectedKeys.begin(), affectedKeys.end());
toc(affectedKeysSet); gttoc(affectedKeysSet);
tic(check_candidates_and_linearize); gttic(check_candidates_and_linearize);
FactorGraph<GaussianFactor>::shared_ptr linearized = boost::make_shared<FactorGraph<GaussianFactor> >(); FactorGraph<GaussianFactor>::shared_ptr linearized = boost::make_shared<FactorGraph<GaussianFactor> >();
BOOST_FOREACH(size_t idx, candidates) { BOOST_FOREACH(size_t idx, candidates) {
bool inside = true; bool inside = true;
@ -212,7 +212,7 @@ ISAM2::relinearizeAffectedFactors(const FastList<Index>& affectedKeys, const Fas
} }
} }
} }
toc(check_candidates_and_linearize); gttoc(check_candidates_and_linearize);
return linearized; return linearized;
} }
@ -283,11 +283,11 @@ boost::shared_ptr<FastSet<Index> > ISAM2::recalculate(const FastSet<Index>& mark
// 1. Remove top of Bayes tree and convert to a factor graph: // 1. Remove top of Bayes tree and convert to a factor graph:
// (a) For each affected variable, remove the corresponding clique and all parents up to the root. // (a) For each affected variable, remove the corresponding clique and all parents up to the root.
// (b) Store orphaned sub-trees \BayesTree_{O} of removed cliques. // (b) Store orphaned sub-trees \BayesTree_{O} of removed cliques.
tic(removetop); gttic(removetop);
Cliques orphans; Cliques orphans;
BayesNet<GaussianConditional> affectedBayesNet; BayesNet<GaussianConditional> affectedBayesNet;
this->removeTop(markedKeys, affectedBayesNet, orphans); this->removeTop(markedKeys, affectedBayesNet, orphans);
toc(removetop); gttoc(removetop);
if(debug) affectedBayesNet.print("Removed top: "); if(debug) affectedBayesNet.print("Removed top: ");
if(debug) orphans.print("Orphans: "); if(debug) orphans.print("Orphans: ");
@ -304,22 +304,22 @@ boost::shared_ptr<FastSet<Index> > ISAM2::recalculate(const FastSet<Index>& mark
// BEGIN OF COPIED CODE // BEGIN OF COPIED CODE
// ordering provides all keys in conditionals, there cannot be others because path to root included // ordering provides all keys in conditionals, there cannot be others because path to root included
tic(affectedKeys); gttic(affectedKeys);
FastList<Index> affectedKeys = affectedBayesNet.ordering(); FastList<Index> affectedKeys = affectedBayesNet.ordering();
toc(affectedKeys); gttoc(affectedKeys);
boost::shared_ptr<FastSet<Index> > affectedKeysSet(new FastSet<Index>()); // Will return this result boost::shared_ptr<FastSet<Index> > affectedKeysSet(new FastSet<Index>()); // Will return this result
if(affectedKeys.size() >= theta_.size() * batchThreshold) { if(affectedKeys.size() >= theta_.size() * batchThreshold) {
tic(batch); gttic(batch);
tic(add_keys); gttic(add_keys);
BOOST_FOREACH(const Ordering::value_type& key_index, ordering_) { affectedKeysSet->insert(key_index.second); } BOOST_FOREACH(const Ordering::value_type& key_index, ordering_) { affectedKeysSet->insert(key_index.second); }
toc(add_keys); gttoc(add_keys);
tic(reorder); gttic(reorder);
tic(CCOLAMD); gttic(CCOLAMD);
// Do a batch step - reorder and relinearize all variables // Do a batch step - reorder and relinearize all variables
vector<int> cmember(theta_.size(), 0); vector<int> cmember(theta_.size(), 0);
if(constrainKeys) { if(constrainKeys) {
@ -341,29 +341,29 @@ boost::shared_ptr<FastSet<Index> > ISAM2::recalculate(const FastSet<Index>& mark
} }
Permutation::shared_ptr colamd(inference::PermutationCOLAMD_(variableIndex_, cmember)); Permutation::shared_ptr colamd(inference::PermutationCOLAMD_(variableIndex_, cmember));
Permutation::shared_ptr colamdInverse(colamd->inverse()); Permutation::shared_ptr colamdInverse(colamd->inverse());
toc(CCOLAMD); gttoc(CCOLAMD);
// Reorder // Reorder
tic(permute_global_variable_index); gttic(permute_global_variable_index);
variableIndex_.permuteInPlace(*colamd); variableIndex_.permuteInPlace(*colamd);
toc(permute_global_variable_index); gttoc(permute_global_variable_index);
tic(permute_delta); gttic(permute_delta);
delta_ = delta_.permute(*colamd); delta_ = delta_.permute(*colamd);
deltaNewton_ = deltaNewton_.permute(*colamd); deltaNewton_ = deltaNewton_.permute(*colamd);
RgProd_ = RgProd_.permute(*colamd); RgProd_ = RgProd_.permute(*colamd);
toc(permute_delta); gttoc(permute_delta);
tic(permute_ordering); gttic(permute_ordering);
ordering_.permuteWithInverse(*colamdInverse); ordering_.permuteWithInverse(*colamdInverse);
toc(permute_ordering); gttoc(permute_ordering);
toc(reorder); gttoc(reorder);
tic(linearize); gttic(linearize);
GaussianFactorGraph linearized = *nonlinearFactors_.linearize(theta_, ordering_); GaussianFactorGraph linearized = *nonlinearFactors_.linearize(theta_, ordering_);
if(params_.cacheLinearizedFactors) if(params_.cacheLinearizedFactors)
linearFactors_ = linearized; linearFactors_ = linearized;
toc(linearize); gttoc(linearize);
tic(eliminate); gttic(eliminate);
JunctionTree<GaussianFactorGraph, Base::Clique> jt(linearized, variableIndex_); JunctionTree<GaussianFactorGraph, Base::Clique> jt(linearized, variableIndex_);
sharedClique newRoot; sharedClique newRoot;
if(params_.factorization == ISAM2Params::CHOLESKY) if(params_.factorization == ISAM2Params::CHOLESKY)
@ -372,12 +372,12 @@ boost::shared_ptr<FastSet<Index> > ISAM2::recalculate(const FastSet<Index>& mark
newRoot = jt.eliminate(EliminateQR); newRoot = jt.eliminate(EliminateQR);
else assert(false); else assert(false);
if(debug) newRoot->print("Eliminated: "); if(debug) newRoot->print("Eliminated: ");
toc(eliminate); gttoc(eliminate);
tic(insert); gttic(insert);
this->clear(); this->clear();
this->insert(newRoot); this->insert(newRoot);
toc(insert); gttoc(insert);
result.variablesReeliminated = affectedKeysSet->size(); result.variablesReeliminated = affectedKeysSet->size();
@ -392,20 +392,20 @@ boost::shared_ptr<FastSet<Index> > ISAM2::recalculate(const FastSet<Index>& mark
} }
} }
toc(batch); gttoc(batch);
} else { } else {
tic(incremental); gttic(incremental);
// 2. Add the new factors \Factors' into the resulting factor graph // 2. Add the new factors \Factors' into the resulting factor graph
FastList<Index> affectedAndNewKeys; FastList<Index> affectedAndNewKeys;
affectedAndNewKeys.insert(affectedAndNewKeys.end(), affectedKeys.begin(), affectedKeys.end()); affectedAndNewKeys.insert(affectedAndNewKeys.end(), affectedKeys.begin(), affectedKeys.end());
affectedAndNewKeys.insert(affectedAndNewKeys.end(), observedKeys.begin(), observedKeys.end()); affectedAndNewKeys.insert(affectedAndNewKeys.end(), observedKeys.begin(), observedKeys.end());
tic(relinearizeAffected); gttic(relinearizeAffected);
GaussianFactorGraph factors(*relinearizeAffectedFactors(affectedAndNewKeys, relinKeys)); GaussianFactorGraph factors(*relinearizeAffectedFactors(affectedAndNewKeys, relinKeys));
if(debug) factors.print("Relinearized factors: "); if(debug) factors.print("Relinearized factors: ");
toc(relinearizeAffected); gttoc(relinearizeAffected);
if(debug) { cout << "Affected keys: "; BOOST_FOREACH(const Index key, affectedKeys) { cout << key << " "; } cout << endl; } if(debug) { cout << "Affected keys: "; BOOST_FOREACH(const Index key, affectedKeys) { cout << key << " "; } cout << endl; }
@ -428,27 +428,27 @@ boost::shared_ptr<FastSet<Index> > ISAM2::recalculate(const FastSet<Index>& mark
<< " avgCliqueSize: " << avgClique << " #Cliques: " << numCliques << " nnzR: " << nnzR << endl; << " avgCliqueSize: " << avgClique << " #Cliques: " << numCliques << " nnzR: " << nnzR << endl;
#endif #endif
tic(cached); gttic(cached);
// add the cached intermediate results from the boundary of the orphans ... // add the cached intermediate results from the boundary of the orphans ...
GaussianFactorGraph cachedBoundary = getCachedBoundaryFactors(orphans); GaussianFactorGraph cachedBoundary = getCachedBoundaryFactors(orphans);
if(debug) cachedBoundary.print("Boundary factors: "); if(debug) cachedBoundary.print("Boundary factors: ");
factors.push_back(cachedBoundary); factors.push_back(cachedBoundary);
toc(cached); gttoc(cached);
// END OF COPIED CODE // END OF COPIED CODE
// 3. Re-order and eliminate the factor graph into a Bayes net (Algorithm [alg:eliminate]), and re-assemble into a new Bayes tree (Algorithm [alg:BayesTree]) // 3. Re-order and eliminate the factor graph into a Bayes net (Algorithm [alg:eliminate]), and re-assemble into a new Bayes tree (Algorithm [alg:BayesTree])
tic(reorder_and_eliminate); gttic(reorder_and_eliminate);
tic(list_to_set); gttic(list_to_set);
// create a partial reordering for the new and contaminated factors // create a partial reordering for the new and contaminated factors
// markedKeys are passed in: those variables will be forced to the end in the ordering // markedKeys are passed in: those variables will be forced to the end in the ordering
affectedKeysSet->insert(markedKeys.begin(), markedKeys.end()); affectedKeysSet->insert(markedKeys.begin(), markedKeys.end());
affectedKeysSet->insert(affectedKeys.begin(), affectedKeys.end()); affectedKeysSet->insert(affectedKeys.begin(), affectedKeys.end());
toc(list_to_set); gttoc(list_to_set);
tic(PartialSolve); gttic(PartialSolve);
Impl::ReorderingMode reorderingMode; Impl::ReorderingMode reorderingMode;
reorderingMode.nFullSystemVars = ordering_.nVars(); reorderingMode.nFullSystemVars = ordering_.nVars();
reorderingMode.algorithm = Impl::ReorderingMode::COLAMD; reorderingMode.algorithm = Impl::ReorderingMode::COLAMD;
@ -465,50 +465,50 @@ boost::shared_ptr<FastSet<Index> > ISAM2::recalculate(const FastSet<Index>& mark
} }
Impl::PartialSolveResult partialSolveResult = Impl::PartialSolveResult partialSolveResult =
Impl::PartialSolve(factors, affectedUsedKeys, reorderingMode, (params_.factorization == ISAM2Params::QR)); Impl::PartialSolve(factors, affectedUsedKeys, reorderingMode, (params_.factorization == ISAM2Params::QR));
toc(PartialSolve); gttoc(PartialSolve);
// We now need to permute everything according this partial reordering: the // We now need to permute everything according this partial reordering: the
// delta vector, the global ordering, and the factors we're about to // delta vector, the global ordering, and the factors we're about to
// re-eliminate. The reordered variables are also mentioned in the // re-eliminate. The reordered variables are also mentioned in the
// orphans and the leftover cached factors. // orphans and the leftover cached factors.
tic(permute_global_variable_index); gttic(permute_global_variable_index);
variableIndex_.permuteInPlace(partialSolveResult.fullReordering); variableIndex_.permuteInPlace(partialSolveResult.fullReordering);
toc(permute_global_variable_index); gttoc(permute_global_variable_index);
tic(permute_delta); gttic(permute_delta);
delta_ = delta_.permute(partialSolveResult.fullReordering); delta_ = delta_.permute(partialSolveResult.fullReordering);
deltaNewton_ = deltaNewton_.permute(partialSolveResult.fullReordering); deltaNewton_ = deltaNewton_.permute(partialSolveResult.fullReordering);
RgProd_ = RgProd_.permute(partialSolveResult.fullReordering); RgProd_ = RgProd_.permute(partialSolveResult.fullReordering);
toc(permute_delta); gttoc(permute_delta);
tic(permute_ordering); gttic(permute_ordering);
ordering_.permuteWithInverse(partialSolveResult.fullReorderingInverse); ordering_.permuteWithInverse(partialSolveResult.fullReorderingInverse);
toc(permute_ordering); gttoc(permute_ordering);
if(params_.cacheLinearizedFactors) { if(params_.cacheLinearizedFactors) {
tic(permute_cached_linear); gttic(permute_cached_linear);
//linearFactors_.permuteWithInverse(partialSolveResult.fullReorderingInverse); //linearFactors_.permuteWithInverse(partialSolveResult.fullReorderingInverse);
FastList<size_t> permuteLinearIndices = getAffectedFactors(affectedAndNewKeys); FastList<size_t> permuteLinearIndices = getAffectedFactors(affectedAndNewKeys);
BOOST_FOREACH(size_t idx, permuteLinearIndices) { BOOST_FOREACH(size_t idx, permuteLinearIndices) {
linearFactors_[idx]->permuteWithInverse(partialSolveResult.fullReorderingInverse); linearFactors_[idx]->permuteWithInverse(partialSolveResult.fullReorderingInverse);
} }
toc(permute_cached_linear); gttoc(permute_cached_linear);
} }
toc(reorder_and_eliminate); gttoc(reorder_and_eliminate);
tic(reassemble); gttic(reassemble);
if(partialSolveResult.bayesTree) { if(partialSolveResult.bayesTree) {
assert(!this->root_); assert(!this->root_);
this->insert(partialSolveResult.bayesTree); this->insert(partialSolveResult.bayesTree);
} }
toc(reassemble); gttoc(reassemble);
// 4. Insert the orphans back into the new Bayes tree. // 4. Insert the orphans back into the new Bayes tree.
tic(orphans); gttic(orphans);
tic(permute); gttic(permute);
BOOST_FOREACH(sharedClique orphan, orphans) { BOOST_FOREACH(sharedClique orphan, orphans) {
(void)orphan->permuteSeparatorWithInverse(partialSolveResult.fullReorderingInverse); (void)orphan->permuteSeparatorWithInverse(partialSolveResult.fullReorderingInverse);
} }
toc(permute); gttoc(permute);
tic(insert); gttic(insert);
// add orphans to the bottom of the new tree // add orphans to the bottom of the new tree
BOOST_FOREACH(sharedClique orphan, orphans) { BOOST_FOREACH(sharedClique orphan, orphans) {
// Because the affectedKeysSelector is sorted, the orphan separator keys // Because the affectedKeysSelector is sorted, the orphan separator keys
@ -520,10 +520,10 @@ boost::shared_ptr<FastSet<Index> > ISAM2::recalculate(const FastSet<Index>& mark
parent->children_ += orphan; parent->children_ += orphan;
orphan->parent_ = parent; // set new parent! orphan->parent_ = parent; // set new parent!
} }
toc(insert); gttoc(insert);
toc(orphans); gttoc(orphans);
toc(incremental); gttoc(incremental);
} }
// Root clique variables for detailed results // Root clique variables for detailed results
@ -565,12 +565,12 @@ ISAM2Result ISAM2::update(
// Update delta if we need it to check relinearization later // Update delta if we need it to check relinearization later
if(relinearizeThisStep) { if(relinearizeThisStep) {
tic(updateDelta); gttic(updateDelta);
updateDelta(disableReordering); updateDelta(disableReordering);
toc(updateDelta); gttoc(updateDelta);
} }
tic(push_back_factors); gttic(push_back_factors);
// Add the new factor indices to the result struct // Add the new factor indices to the result struct
result.newFactorsIndices.resize(newFactors.size()); result.newFactorsIndices.resize(newFactors.size());
for(size_t i=0; i<newFactors.size(); ++i) for(size_t i=0; i<newFactors.size(); ++i)
@ -612,23 +612,23 @@ ISAM2Result ISAM2::update(
unusedIndices.insert(unusedIndices.end(), ordering_[key]); unusedIndices.insert(unusedIndices.end(), ordering_[key]);
} }
} }
toc(push_back_factors); gttoc(push_back_factors);
tic(add_new_variables); gttic(add_new_variables);
// 2. Initialize any new variables \Theta_{new} and add \Theta:=\Theta\cup\Theta_{new}. // 2. Initialize any new variables \Theta_{new} and add \Theta:=\Theta\cup\Theta_{new}.
Impl::AddVariables(newTheta, theta_, delta_, deltaNewton_, RgProd_, deltaReplacedMask_, ordering_); Impl::AddVariables(newTheta, theta_, delta_, deltaNewton_, RgProd_, deltaReplacedMask_, ordering_);
// New keys for detailed results // New keys for detailed results
if(params_.enableDetailedResults) { if(params_.enableDetailedResults) {
inverseOrdering_ = ordering_.invert(); inverseOrdering_ = ordering_.invert();
BOOST_FOREACH(Key key, newTheta.keys()) { result.detail->variableStatus[key].isNew = true; } } BOOST_FOREACH(Key key, newTheta.keys()) { result.detail->variableStatus[key].isNew = true; } }
toc(add_new_variables); gttoc(add_new_variables);
tic(evaluate_error_before); gttic(evaluate_error_before);
if(params_.evaluateNonlinearError) if(params_.evaluateNonlinearError)
result.errorBefore.reset(nonlinearFactors_.error(calculateEstimate())); result.errorBefore.reset(nonlinearFactors_.error(calculateEstimate()));
toc(evaluate_error_before); gttoc(evaluate_error_before);
tic(gather_involved_keys); gttic(gather_involved_keys);
// 3. Mark linear update // 3. Mark linear update
FastSet<Index> markedKeys = Impl::IndicesFromFactors(ordering_, newFactors); // Get keys from new factors FastSet<Index> markedKeys = Impl::IndicesFromFactors(ordering_, newFactors); // Get keys from new factors
// Also mark keys involved in removed factors // Also mark keys involved in removed factors
@ -651,12 +651,12 @@ ISAM2Result ISAM2::update(
if(unusedIndices.find(index) == unusedIndices.end()) // Only add if not unused if(unusedIndices.find(index) == unusedIndices.end()) // Only add if not unused
observedKeys.push_back(index); // Make a copy of these, as we'll soon add to them observedKeys.push_back(index); // Make a copy of these, as we'll soon add to them
} }
toc(gather_involved_keys); gttoc(gather_involved_keys);
// Check relinearization if we're at the nth step, or we are using a looser loop relin threshold // Check relinearization if we're at the nth step, or we are using a looser loop relin threshold
FastSet<Index> relinKeys; FastSet<Index> relinKeys;
if (relinearizeThisStep) { if (relinearizeThisStep) {
tic(gather_relinearize_keys); gttic(gather_relinearize_keys);
vector<bool> markedRelinMask(ordering_.nVars(), false); vector<bool> markedRelinMask(ordering_.nVars(), false);
// 4. Mark keys in \Delta above threshold \beta: J=\{\Delta_{j}\in\Delta|\Delta_{j}\geq\beta\}. // 4. Mark keys in \Delta above threshold \beta: J=\{\Delta_{j}\in\Delta|\Delta_{j}\geq\beta\}.
if(params_.enablePartialRelinearizationCheck) if(params_.enablePartialRelinearizationCheck)
@ -674,9 +674,9 @@ ISAM2Result ISAM2::update(
// Add the variables being relinearized to the marked keys // Add the variables being relinearized to the marked keys
BOOST_FOREACH(const Index j, relinKeys) { markedRelinMask[j] = true; } BOOST_FOREACH(const Index j, relinKeys) { markedRelinMask[j] = true; }
markedKeys.insert(relinKeys.begin(), relinKeys.end()); markedKeys.insert(relinKeys.begin(), relinKeys.end());
toc(gather_relinearize_keys); gttoc(gather_relinearize_keys);
tic(fluid_find_all); gttic(fluid_find_all);
// 5. Mark all cliques that involve marked variables \Theta_{J} and all their ancestors. // 5. Mark all cliques that involve marked variables \Theta_{J} and all their ancestors.
if (!relinKeys.empty() && this->root()) { if (!relinKeys.empty() && this->root()) {
// add other cliques that have the marked ones in the separator // add other cliques that have the marked ones in the separator
@ -692,38 +692,38 @@ ISAM2Result ISAM2::update(
result.detail->variableStatus[inverseOrdering_->at(index)].isRelinearized = true; } } result.detail->variableStatus[inverseOrdering_->at(index)].isRelinearized = true; } }
} }
} }
toc(fluid_find_all); gttoc(fluid_find_all);
tic(expmap); gttic(expmap);
// 6. Update linearization point for marked variables: \Theta_{J}:=\Theta_{J}+\Delta_{J}. // 6. Update linearization point for marked variables: \Theta_{J}:=\Theta_{J}+\Delta_{J}.
if (!relinKeys.empty()) if (!relinKeys.empty())
Impl::ExpmapMasked(theta_, delta_, ordering_, markedRelinMask, delta_); Impl::ExpmapMasked(theta_, delta_, ordering_, markedRelinMask, delta_);
toc(expmap); gttoc(expmap);
result.variablesRelinearized = markedKeys.size(); result.variablesRelinearized = markedKeys.size();
} else { } else {
result.variablesRelinearized = 0; result.variablesRelinearized = 0;
} }
tic(linearize_new); gttic(linearize_new);
// 7. Linearize new factors // 7. Linearize new factors
if(params_.cacheLinearizedFactors) { if(params_.cacheLinearizedFactors) {
tic(linearize); gttic(linearize);
FactorGraph<GaussianFactor>::shared_ptr linearFactors = newFactors.linearize(theta_, ordering_); FactorGraph<GaussianFactor>::shared_ptr linearFactors = newFactors.linearize(theta_, ordering_);
linearFactors_.push_back(*linearFactors); linearFactors_.push_back(*linearFactors);
assert(nonlinearFactors_.size() == linearFactors_.size()); assert(nonlinearFactors_.size() == linearFactors_.size());
toc(linearize); gttoc(linearize);
tic(augment_VI); gttic(augment_VI);
// Augment the variable index with the new factors // Augment the variable index with the new factors
variableIndex_.augment(*linearFactors); variableIndex_.augment(*linearFactors);
toc(augment_VI); gttoc(augment_VI);
} else { } else {
variableIndex_.augment(*newFactors.symbolic(ordering_)); variableIndex_.augment(*newFactors.symbolic(ordering_));
} }
toc(linearize_new); gttoc(linearize_new);
tic(recalculate); gttic(recalculate);
// 8. Redo top of Bayes tree // 8. Redo top of Bayes tree
// Convert constrained symbols to indices // Convert constrained symbols to indices
boost::optional<FastMap<Index,int> > constrainedIndices; boost::optional<FastMap<Index,int> > constrainedIndices;
@ -742,25 +742,25 @@ ISAM2Result ISAM2::update(
if(replacedKeys) { if(replacedKeys) {
BOOST_FOREACH(const Index var, *replacedKeys) { BOOST_FOREACH(const Index var, *replacedKeys) {
deltaReplacedMask_[var] = true; } } deltaReplacedMask_[var] = true; } }
toc(recalculate); gttoc(recalculate);
// After the top of the tree has been redone and may have index gaps from // After the top of the tree has been redone and may have index gaps from
// unused keys, condense the indices to remove gaps by rearranging indices // unused keys, condense the indices to remove gaps by rearranging indices
// in all data structures. // in all data structures.
if(!unusedKeys.empty()) { if(!unusedKeys.empty()) {
tic(remove_variables); gttic(remove_variables);
Impl::RemoveVariables(unusedKeys, root_, theta_, variableIndex_, delta_, deltaNewton_, RgProd_, Impl::RemoveVariables(unusedKeys, root_, theta_, variableIndex_, delta_, deltaNewton_, RgProd_,
deltaReplacedMask_, ordering_, Base::nodes_, linearFactors_); deltaReplacedMask_, ordering_, Base::nodes_, linearFactors_);
toc(remove_variables); gttoc(remove_variables);
} }
result.cliques = this->nodes().size(); result.cliques = this->nodes().size();
deltaDoglegUptodate_ = false; deltaDoglegUptodate_ = false;
deltaUptodate_ = false; deltaUptodate_ = false;
tic(evaluate_error_after); gttic(evaluate_error_after);
if(params_.evaluateNonlinearError) if(params_.evaluateNonlinearError)
result.errorAfter.reset(nonlinearFactors_.error(calculateEstimate())); result.errorAfter.reset(nonlinearFactors_.error(calculateEstimate()));
toc(evaluate_error_after); gttoc(evaluate_error_after);
return result; return result;
} }
@ -773,9 +773,9 @@ void ISAM2::updateDelta(bool forceFullSolve) const {
const ISAM2GaussNewtonParams& gaussNewtonParams = const ISAM2GaussNewtonParams& gaussNewtonParams =
boost::get<ISAM2GaussNewtonParams>(params_.optimizationParams); boost::get<ISAM2GaussNewtonParams>(params_.optimizationParams);
const double effectiveWildfireThreshold = forceFullSolve ? 0.0 : gaussNewtonParams.wildfireThreshold; const double effectiveWildfireThreshold = forceFullSolve ? 0.0 : gaussNewtonParams.wildfireThreshold;
tic(Wildfire_update); gttic(Wildfire_update);
lastBacksubVariableCount = Impl::UpdateDelta(this->root(), deltaReplacedMask_, delta_, effectiveWildfireThreshold); lastBacksubVariableCount = Impl::UpdateDelta(this->root(), deltaReplacedMask_, delta_, effectiveWildfireThreshold);
toc(Wildfire_update); gttoc(Wildfire_update);
} else if(params_.optimizationParams.type() == typeid(ISAM2DoglegParams)) { } else if(params_.optimizationParams.type() == typeid(ISAM2DoglegParams)) {
// If using Dogleg, do a Dogleg step // If using Dogleg, do a Dogleg step
@ -783,16 +783,16 @@ void ISAM2::updateDelta(bool forceFullSolve) const {
boost::get<ISAM2DoglegParams>(params_.optimizationParams); boost::get<ISAM2DoglegParams>(params_.optimizationParams);
// Do one Dogleg iteration // Do one Dogleg iteration
tic(Dogleg_Iterate); gttic(Dogleg_Iterate);
DoglegOptimizerImpl::IterationResult doglegResult(DoglegOptimizerImpl::Iterate( DoglegOptimizerImpl::IterationResult doglegResult(DoglegOptimizerImpl::Iterate(
*doglegDelta_, doglegParams.adaptationMode, *this, nonlinearFactors_, theta_, ordering_, nonlinearFactors_.error(theta_), doglegParams.verbose)); *doglegDelta_, doglegParams.adaptationMode, *this, nonlinearFactors_, theta_, ordering_, nonlinearFactors_.error(theta_), doglegParams.verbose));
toc(Dogleg_Iterate); gttoc(Dogleg_Iterate);
tic(Copy_dx_d); gttic(Copy_dx_d);
// Update Delta and linear step // Update Delta and linear step
doglegDelta_ = doglegResult.Delta; doglegDelta_ = doglegResult.Delta;
delta_ = doglegResult.dx_d; // Copy the VectorValues containing with the linear solution delta_ = doglegResult.dx_d; // Copy the VectorValues containing with the linear solution
toc(Copy_dx_d); gttoc(Copy_dx_d);
} }
deltaUptodate_ = true; deltaUptodate_ = true;
@ -802,16 +802,16 @@ void ISAM2::updateDelta(bool forceFullSolve) const {
Values ISAM2::calculateEstimate() const { Values ISAM2::calculateEstimate() const {
// We use ExpmapMasked here instead of regular expmap because the former // We use ExpmapMasked here instead of regular expmap because the former
// handles Permuted<VectorValues> // handles Permuted<VectorValues>
tic(Copy_Values); gttic(Copy_Values);
Values ret(theta_); Values ret(theta_);
toc(Copy_Values); gttoc(Copy_Values);
tic(getDelta); gttic(getDelta);
const VectorValues& delta(getDelta()); const VectorValues& delta(getDelta());
toc(getDelta); gttoc(getDelta);
tic(Expmap); gttic(Expmap);
vector<bool> mask(ordering_.nVars(), true); vector<bool> mask(ordering_.nVars(), true);
Impl::ExpmapMasked(ret, delta, ordering_, mask); Impl::ExpmapMasked(ret, delta, ordering_, mask);
toc(Expmap); gttoc(Expmap);
return ret; return ret;
} }
@ -831,9 +831,9 @@ const VectorValues& ISAM2::getDelta() const {
/* ************************************************************************* */ /* ************************************************************************* */
VectorValues optimize(const ISAM2& isam) { VectorValues optimize(const ISAM2& isam) {
tic(allocateVectorValues); gttic(allocateVectorValues);
VectorValues delta = *allocateVectorValues(isam); VectorValues delta = *allocateVectorValues(isam);
toc(allocateVectorValues); gttoc(allocateVectorValues);
optimizeInPlace(isam, delta); optimizeInPlace(isam, delta);
return delta; return delta;
} }
@ -842,7 +842,7 @@ VectorValues optimize(const ISAM2& isam) {
void optimizeInPlace(const ISAM2& isam, VectorValues& delta) { void optimizeInPlace(const ISAM2& isam, VectorValues& delta) {
// We may need to update the solution calcaulations // We may need to update the solution calcaulations
if(!isam.deltaDoglegUptodate_) { if(!isam.deltaDoglegUptodate_) {
tic(UpdateDoglegDeltas); gttic(UpdateDoglegDeltas);
double wildfireThreshold = 0.0; double wildfireThreshold = 0.0;
if(isam.params().optimizationParams.type() == typeid(ISAM2GaussNewtonParams)) if(isam.params().optimizationParams.type() == typeid(ISAM2GaussNewtonParams))
wildfireThreshold = boost::get<ISAM2GaussNewtonParams>(isam.params().optimizationParams).wildfireThreshold; wildfireThreshold = boost::get<ISAM2GaussNewtonParams>(isam.params().optimizationParams).wildfireThreshold;
@ -852,19 +852,19 @@ void optimizeInPlace(const ISAM2& isam, VectorValues& delta) {
assert(false); assert(false);
ISAM2::Impl::UpdateDoglegDeltas(isam, wildfireThreshold, isam.deltaReplacedMask_, isam.deltaNewton_, isam.RgProd_); ISAM2::Impl::UpdateDoglegDeltas(isam, wildfireThreshold, isam.deltaReplacedMask_, isam.deltaNewton_, isam.RgProd_);
isam.deltaDoglegUptodate_ = true; isam.deltaDoglegUptodate_ = true;
toc(UpdateDoglegDeltas); gttoc(UpdateDoglegDeltas);
} }
tic(copy_delta); gttic(copy_delta);
delta = isam.deltaNewton_; delta = isam.deltaNewton_;
toc(copy_delta); gttoc(copy_delta);
} }
/* ************************************************************************* */ /* ************************************************************************* */
VectorValues optimizeGradientSearch(const ISAM2& isam) { VectorValues optimizeGradientSearch(const ISAM2& isam) {
tic(Allocate_VectorValues); gttic(Allocate_VectorValues);
VectorValues grad = *allocateVectorValues(isam); VectorValues grad = *allocateVectorValues(isam);
toc(Allocate_VectorValues); gttoc(Allocate_VectorValues);
optimizeGradientSearchInPlace(isam, grad); optimizeGradientSearchInPlace(isam, grad);
@ -875,7 +875,7 @@ VectorValues optimizeGradientSearch(const ISAM2& isam) {
void optimizeGradientSearchInPlace(const ISAM2& isam, VectorValues& grad) { void optimizeGradientSearchInPlace(const ISAM2& isam, VectorValues& grad) {
// We may need to update the solution calcaulations // We may need to update the solution calcaulations
if(!isam.deltaDoglegUptodate_) { if(!isam.deltaDoglegUptodate_) {
tic(UpdateDoglegDeltas); gttic(UpdateDoglegDeltas);
double wildfireThreshold = 0.0; double wildfireThreshold = 0.0;
if(isam.params().optimizationParams.type() == typeid(ISAM2GaussNewtonParams)) if(isam.params().optimizationParams.type() == typeid(ISAM2GaussNewtonParams))
wildfireThreshold = boost::get<ISAM2GaussNewtonParams>(isam.params().optimizationParams).wildfireThreshold; wildfireThreshold = boost::get<ISAM2GaussNewtonParams>(isam.params().optimizationParams).wildfireThreshold;
@ -885,25 +885,25 @@ void optimizeGradientSearchInPlace(const ISAM2& isam, VectorValues& grad) {
assert(false); assert(false);
ISAM2::Impl::UpdateDoglegDeltas(isam, wildfireThreshold, isam.deltaReplacedMask_, isam.deltaNewton_, isam.RgProd_); ISAM2::Impl::UpdateDoglegDeltas(isam, wildfireThreshold, isam.deltaReplacedMask_, isam.deltaNewton_, isam.RgProd_);
isam.deltaDoglegUptodate_ = true; isam.deltaDoglegUptodate_ = true;
toc(UpdateDoglegDeltas); gttoc(UpdateDoglegDeltas);
} }
tic(Compute_Gradient); gttic(Compute_Gradient);
// Compute gradient (call gradientAtZero function, which is defined for various linear systems) // Compute gradient (call gradientAtZero function, which is defined for various linear systems)
gradientAtZero(isam, grad); gradientAtZero(isam, grad);
double gradientSqNorm = grad.dot(grad); double gradientSqNorm = grad.dot(grad);
toc(Compute_Gradient); gttoc(Compute_Gradient);
tic(Compute_minimizing_step_size); gttic(Compute_minimizing_step_size);
// Compute minimizing step size // Compute minimizing step size
double RgNormSq = isam.RgProd_.vector().squaredNorm(); double RgNormSq = isam.RgProd_.vector().squaredNorm();
double step = -gradientSqNorm / RgNormSq; double step = -gradientSqNorm / RgNormSq;
toc(Compute_minimizing_step_size); gttoc(Compute_minimizing_step_size);
tic(Compute_point); gttic(Compute_point);
// Compute steepest descent point // Compute steepest descent point
grad.vector() *= step; grad.vector() *= step;
toc(Compute_point); gttoc(Compute_point);
} }
/* ************************************************************************* */ /* ************************************************************************* */

View File

@ -71,7 +71,7 @@ void LevenbergMarquardtParams::print(const std::string& str) const {
/* ************************************************************************* */ /* ************************************************************************* */
void LevenbergMarquardtOptimizer::iterate() { void LevenbergMarquardtOptimizer::iterate() {
tic(LM_iterate); gttic(LM_iterate);
// Linearize graph // Linearize graph
GaussianFactorGraph::shared_ptr linear = graph_.linearize(state_.values, *params_.ordering); GaussianFactorGraph::shared_ptr linear = graph_.linearize(state_.values, *params_.ordering);
@ -87,7 +87,7 @@ void LevenbergMarquardtOptimizer::iterate() {
// Add prior-factors // Add prior-factors
// TODO: replace this dampening with a backsubstitution approach // TODO: replace this dampening with a backsubstitution approach
tic(damp); gttic(damp);
GaussianFactorGraph dampedSystem(*linear); GaussianFactorGraph dampedSystem(*linear);
{ {
double sigma = 1.0 / std::sqrt(state_.lambda); double sigma = 1.0 / std::sqrt(state_.lambda);
@ -102,7 +102,7 @@ void LevenbergMarquardtOptimizer::iterate() {
dampedSystem.push_back(prior); dampedSystem.push_back(prior);
} }
} }
toc(damp); gttoc(damp);
if (lmVerbosity >= LevenbergMarquardtParams::DAMPED) dampedSystem.print("damped"); if (lmVerbosity >= LevenbergMarquardtParams::DAMPED) dampedSystem.print("damped");
// Try solving // Try solving
@ -114,14 +114,14 @@ void LevenbergMarquardtOptimizer::iterate() {
if (lmVerbosity >= LevenbergMarquardtParams::TRYDELTA) delta.print("delta"); if (lmVerbosity >= LevenbergMarquardtParams::TRYDELTA) delta.print("delta");
// update values // update values
tic(retract); gttic(retract);
Values newValues = state_.values.retract(delta, *params_.ordering); Values newValues = state_.values.retract(delta, *params_.ordering);
toc(retract); gttoc(retract);
// create new optimization state with more adventurous lambda // create new optimization state with more adventurous lambda
tic(compute_error); gttic(compute_error);
double error = graph_.error(newValues); double error = graph_.error(newValues);
toc(compute_error); gttoc(compute_error);
if (lmVerbosity >= LevenbergMarquardtParams::TRYLAMBDA) cout << "next error = " << error << endl; if (lmVerbosity >= LevenbergMarquardtParams::TRYLAMBDA) cout << "next error = " << error << endl;

View File

@ -44,7 +44,7 @@ void NonlinearFactorGraph::print(const std::string& str, const KeyFormatter& key
/* ************************************************************************* */ /* ************************************************************************* */
double NonlinearFactorGraph::error(const Values& c) const { double NonlinearFactorGraph::error(const Values& c) const {
tic(NonlinearFactorGraph_error); gttic(NonlinearFactorGraph_error);
double total_error = 0.; double total_error = 0.;
// iterate over all the factors_ to accumulate the log probabilities // iterate over all the factors_ to accumulate the log probabilities
BOOST_FOREACH(const sharedFactor& factor, this->factors_) { BOOST_FOREACH(const sharedFactor& factor, this->factors_) {
@ -68,7 +68,7 @@ FastSet<Key> NonlinearFactorGraph::keys() const {
Ordering::shared_ptr NonlinearFactorGraph::orderingCOLAMD( Ordering::shared_ptr NonlinearFactorGraph::orderingCOLAMD(
const Values& config) const const Values& config) const
{ {
tic(NonlinearFactorGraph_orderingCOLAMD); gttic(NonlinearFactorGraph_orderingCOLAMD);
// Create symbolic graph and initial (iterator) ordering // Create symbolic graph and initial (iterator) ordering
SymbolicFactorGraph::shared_ptr symbolic; SymbolicFactorGraph::shared_ptr symbolic;
@ -93,7 +93,7 @@ Ordering::shared_ptr NonlinearFactorGraph::orderingCOLAMD(
Ordering::shared_ptr NonlinearFactorGraph::orderingCOLAMDConstrained(const Values& config, Ordering::shared_ptr NonlinearFactorGraph::orderingCOLAMDConstrained(const Values& config,
const std::map<Key, int>& constraints) const const std::map<Key, int>& constraints) const
{ {
tic(NonlinearFactorGraph_orderingCOLAMDConstrained); gttic(NonlinearFactorGraph_orderingCOLAMDConstrained);
// Create symbolic graph and initial (iterator) ordering // Create symbolic graph and initial (iterator) ordering
SymbolicFactorGraph::shared_ptr symbolic; SymbolicFactorGraph::shared_ptr symbolic;
@ -122,7 +122,7 @@ Ordering::shared_ptr NonlinearFactorGraph::orderingCOLAMDConstrained(const Value
/* ************************************************************************* */ /* ************************************************************************* */
SymbolicFactorGraph::shared_ptr NonlinearFactorGraph::symbolic(const Ordering& ordering) const { SymbolicFactorGraph::shared_ptr NonlinearFactorGraph::symbolic(const Ordering& ordering) const {
tic(NonlinearFactorGraph_symbolic_from_Ordering); gttic(NonlinearFactorGraph_symbolic_from_Ordering);
// Generate the symbolic factor graph // Generate the symbolic factor graph
SymbolicFactorGraph::shared_ptr symbolicfg(new SymbolicFactorGraph); SymbolicFactorGraph::shared_ptr symbolicfg(new SymbolicFactorGraph);
@ -142,7 +142,7 @@ SymbolicFactorGraph::shared_ptr NonlinearFactorGraph::symbolic(const Ordering& o
pair<SymbolicFactorGraph::shared_ptr, Ordering::shared_ptr> NonlinearFactorGraph::symbolic( pair<SymbolicFactorGraph::shared_ptr, Ordering::shared_ptr> NonlinearFactorGraph::symbolic(
const Values& config) const const Values& config) const
{ {
tic(NonlinearFactorGraph_symbolic_from_Values); gttic(NonlinearFactorGraph_symbolic_from_Values);
// Generate an initial key ordering in iterator order // Generate an initial key ordering in iterator order
Ordering::shared_ptr ordering(config.orderingArbitrary()); Ordering::shared_ptr ordering(config.orderingArbitrary());
@ -153,7 +153,7 @@ pair<SymbolicFactorGraph::shared_ptr, Ordering::shared_ptr> NonlinearFactorGraph
GaussianFactorGraph::shared_ptr NonlinearFactorGraph::linearize( GaussianFactorGraph::shared_ptr NonlinearFactorGraph::linearize(
const Values& config, const Ordering& ordering) const const Values& config, const Ordering& ordering) const
{ {
tic(NonlinearFactorGraph_linearize); gttic(NonlinearFactorGraph_linearize);
// create an empty linear FG // create an empty linear FG
GaussianFactorGraph::shared_ptr linearFG(new GaussianFactorGraph); GaussianFactorGraph::shared_ptr linearFG(new GaussianFactorGraph);

View File

@ -54,7 +54,7 @@ void SuccessiveLinearizationParams::print(const std::string& str) const {
} }
VectorValues solveGaussianFactorGraph(const GaussianFactorGraph &gfg, const SuccessiveLinearizationParams &params) { VectorValues solveGaussianFactorGraph(const GaussianFactorGraph &gfg, const SuccessiveLinearizationParams &params) {
tic(solveGaussianFactorGraph); gttic(solveGaussianFactorGraph);
VectorValues delta; VectorValues delta;
if (params.isMultifrontal()) { if (params.isMultifrontal()) {
delta = GaussianJunctionTree(gfg).optimize(params.getEliminationFunction()); delta = GaussianJunctionTree(gfg).optimize(params.getEliminationFunction());

View File

@ -253,12 +253,12 @@ namespace gtsam {
/** Eliminate, return a Bayes net */ /** Eliminate, return a Bayes net */
DiscreteBayesNet::shared_ptr Scheduler::eliminate() const { DiscreteBayesNet::shared_ptr Scheduler::eliminate() const {
tic(my_solver); gttic(my_solver);
DiscreteSequentialSolver solver(*this); DiscreteSequentialSolver solver(*this);
toc(my_solver); gttoc(my_solver);
tic(my_eliminate); gttic(my_eliminate);
DiscreteBayesNet::shared_ptr chordal = solver.eliminate(); DiscreteBayesNet::shared_ptr chordal = solver.eliminate();
toc(my_eliminate); gttoc(my_eliminate);
return chordal; return chordal;
} }
@ -273,9 +273,9 @@ namespace gtsam {
(*it)->print(student.name_); (*it)->print(student.name_);
} }
tic(my_optimize); gttic(my_optimize);
sharedValues mpe = optimize(*chordal); sharedValues mpe = optimize(*chordal);
toc(my_optimize); gttoc(my_optimize);
return mpe; return mpe;
} }

View File

@ -117,9 +117,9 @@ void runLargeExample() {
// Do exact inference // Do exact inference
// SETDEBUG("timing-verbose", true); // SETDEBUG("timing-verbose", true);
SETDEBUG("DiscreteConditional::DiscreteConditional", true); SETDEBUG("DiscreteConditional::DiscreteConditional", true);
tic(large); gttic(large);
DiscreteFactor::sharedValues MPE = scheduler.optimalAssignment(); DiscreteFactor::sharedValues MPE = scheduler.optimalAssignment();
toc(large); gttoc(large);
tictoc_finishedIteration(); tictoc_finishedIteration();
tictoc_print(); tictoc_print();
scheduler.printAssignment(MPE); scheduler.printAssignment(MPE);
@ -151,9 +151,9 @@ void solveStaged(size_t addMutex = 2) {
scheduler.buildGraph(addMutex); scheduler.buildGraph(addMutex);
// Do EXACT INFERENCE // Do EXACT INFERENCE
tic_(eliminate); gttic_(eliminate);
DiscreteBayesNet::shared_ptr chordal = scheduler.eliminate(); DiscreteBayesNet::shared_ptr chordal = scheduler.eliminate();
toc_(eliminate); gttoc_(eliminate);
// find root node // find root node
DiscreteConditional::shared_ptr root = *(chordal->rbegin()); DiscreteConditional::shared_ptr root = *(chordal->rbegin());

View File

@ -124,9 +124,9 @@ void runLargeExample() {
SETDEBUG("DiscreteConditional::DiscreteConditional", true); SETDEBUG("DiscreteConditional::DiscreteConditional", true);
#define SAMPLE #define SAMPLE
#ifdef SAMPLE #ifdef SAMPLE
tic(large); gttic(large);
DiscreteBayesNet::shared_ptr chordal = scheduler.eliminate(); DiscreteBayesNet::shared_ptr chordal = scheduler.eliminate();
toc(large); gttoc(large);
tictoc_finishedIteration(); tictoc_finishedIteration();
tictoc_print(); tictoc_print();
for (size_t i=0;i<100;i++) { for (size_t i=0;i<100;i++) {
@ -143,9 +143,9 @@ void runLargeExample() {
} }
} }
#else #else
tic(large); gttic(large);
DiscreteFactor::sharedValues MPE = scheduler.optimalAssignment(); DiscreteFactor::sharedValues MPE = scheduler.optimalAssignment();
toc(large); gttoc(large);
tictoc_finishedIteration(); tictoc_finishedIteration();
tictoc_print(); tictoc_print();
scheduler.printAssignment(MPE); scheduler.printAssignment(MPE);
@ -178,9 +178,9 @@ void solveStaged(size_t addMutex = 2) {
scheduler.buildGraph(addMutex); scheduler.buildGraph(addMutex);
// Do EXACT INFERENCE // Do EXACT INFERENCE
tic_(eliminate); gttic_(eliminate);
DiscreteBayesNet::shared_ptr chordal = scheduler.eliminate(); DiscreteBayesNet::shared_ptr chordal = scheduler.eliminate();
toc_(eliminate); gttoc_(eliminate);
// find root node // find root node
DiscreteConditional::shared_ptr root = *(chordal->rbegin()); DiscreteConditional::shared_ptr root = *(chordal->rbegin());

View File

@ -125,9 +125,9 @@ TEST( schedulingExample, test)
//product.dot("scheduling", false); //product.dot("scheduling", false);
// Do exact inference // Do exact inference
tic(small); gttic(small);
DiscreteFactor::sharedValues MPE = s.optimalAssignment(); DiscreteFactor::sharedValues MPE = s.optimalAssignment();
toc(small); gttoc(small);
// print MPE, commented out as unit tests don't print // print MPE, commented out as unit tests don't print
// s.printAssignment(MPE); // s.printAssignment(MPE);

View File

@ -34,15 +34,15 @@ int main(int argc, char *argv[]) {
cout << "Optimizing..." << endl; cout << "Optimizing..." << endl;
tic_(Create_optimizer); gttic_(Create_optimizer);
LevenbergMarquardtOptimizer optimizer(graph, initial); LevenbergMarquardtOptimizer optimizer(graph, initial);
toc_(Create_optimizer); gttoc_(Create_optimizer);
tictoc_print_(); tictoc_print_();
double lastError = optimizer.error(); double lastError = optimizer.error();
do { do {
tic_(Iterate_optimizer); gttic_(Iterate_optimizer);
optimizer.iterate(); optimizer.iterate();
toc_(Iterate_optimizer); gttoc_(Iterate_optimizer);
tictoc_finishedIteration_(); tictoc_finishedIteration_();
tictoc_print_(); tictoc_print_();
cout << "Error: " << optimizer.error() << ", lambda: " << optimizer.lambda() << endl; cout << "Error: " << optimizer.error() << ", lambda: " << optimizer.lambda() << endl;

View File

@ -46,11 +46,11 @@ int main(int argc, char *argv[]) {
cout << "Loading data..." << endl; cout << "Loading data..." << endl;
tic_(Find_datafile); gttic_(Find_datafile);
string datasetFile = findExampleDataFile("w10000-odom"); string datasetFile = findExampleDataFile("w10000-odom");
std::pair<NonlinearFactorGraph::shared_ptr, Values::shared_ptr> data = std::pair<NonlinearFactorGraph::shared_ptr, Values::shared_ptr> data =
load2D(datasetFile); load2D(datasetFile);
toc_(Find_datafile); gttoc_(Find_datafile);
NonlinearFactorGraph measurements = *data.first; NonlinearFactorGraph measurements = *data.first;
Values initial = *data.second; Values initial = *data.second;
@ -66,7 +66,7 @@ int main(int argc, char *argv[]) {
NonlinearFactorGraph newFactors; NonlinearFactorGraph newFactors;
// Collect measurements and new variables for the current step // Collect measurements and new variables for the current step
tic_(Collect_measurements); gttic_(Collect_measurements);
if(step == 1) { if(step == 1) {
// cout << "Initializing " << 0 << endl; // cout << "Initializing " << 0 << endl;
newVariables.insert(0, Pose()); newVariables.insert(0, Pose());
@ -114,19 +114,19 @@ int main(int argc, char *argv[]) {
} }
++ nextMeasurement; ++ nextMeasurement;
} }
toc_(Collect_measurements); gttoc_(Collect_measurements);
// Update iSAM2 // Update iSAM2
tic_(Update_ISAM2); gttic_(Update_ISAM2);
isam2.update(newFactors, newVariables); isam2.update(newFactors, newVariables);
toc_(Update_ISAM2); gttoc_(Update_ISAM2);
if(step % 100 == 0) { if(step % 100 == 0) {
tic_(chi2); gttic_(chi2);
Values estimate(isam2.calculateEstimate()); Values estimate(isam2.calculateEstimate());
double chi2 = chi2_red(isam2.getFactorsUnsafe(), estimate); double chi2 = chi2_red(isam2.getFactorsUnsafe(), estimate);
cout << "chi2 = " << chi2 << endl; cout << "chi2 = " << chi2 << endl;
toc_(chi2); gttoc_(chi2);
} }
tictoc_finishedIteration_(); tictoc_finishedIteration_();
@ -141,9 +141,9 @@ int main(int argc, char *argv[]) {
Marginals marginals(isam2.getFactorsUnsafe(), isam2.calculateEstimate()); Marginals marginals(isam2.getFactorsUnsafe(), isam2.calculateEstimate());
int i=0; int i=0;
BOOST_FOREACH(Key key, initial.keys()) { BOOST_FOREACH(Key key, initial.keys()) {
tic_(marginalInformation); gttic_(marginalInformation);
Matrix info = marginals.marginalInformation(key); Matrix info = marginals.marginalInformation(key);
toc_(marginalInformation); gttoc_(marginalInformation);
tictoc_finishedIteration_(); tictoc_finishedIteration_();
if(i % 1000 == 0) if(i % 1000 == 0)
tictoc_print_(); tictoc_print_();