From 0a842cf0ec1cd5d1b306ef95cbd464b9e78233b2 Mon Sep 17 00:00:00 2001 From: Alex Cunningham Date: Thu, 2 Feb 2012 22:45:41 +0000 Subject: [PATCH 01/18] Added empty() to graphs --- gtsam/inference/FactorGraph.h | 3 +++ 1 file changed, 3 insertions(+) diff --git a/gtsam/inference/FactorGraph.h b/gtsam/inference/FactorGraph.h index 458588b7b..12855e0c0 100644 --- a/gtsam/inference/FactorGraph.h +++ b/gtsam/inference/FactorGraph.h @@ -138,6 +138,9 @@ template class BayesTree; /** return the number of factors and NULLS */ size_t size() const { return factors_.size();} + /** Simple check for an empty graph - faster than comparing size() to zero */ + bool empty() const { return factors_.empty(); } + /** const cast to the underlying vector of factors */ operator const std::vector&() const { return factors_; } From bc7293a0a7f2132acb4b240b77d5ffad79d0c7e0 Mon Sep 17 00:00:00 2001 From: Yong-Dian Jian Date: Thu, 2 Feb 2012 23:16:45 +0000 Subject: [PATCH 02/18] disable old subgraph preconditioners temporarily to remove name conflict --- gtsam/linear/SubgraphPreconditioner.cpp | 300 ++++++++++++------------ gtsam/linear/SubgraphPreconditioner.h | 232 +++++++++--------- gtsam/linear/SubgraphSolver.cpp | 100 ++++---- gtsam/linear/SubgraphSolver.h | 200 ++++++++-------- 4 files changed, 416 insertions(+), 416 deletions(-) diff --git a/gtsam/linear/SubgraphPreconditioner.cpp b/gtsam/linear/SubgraphPreconditioner.cpp index b41b0c1d7..cce8eea9d 100644 --- a/gtsam/linear/SubgraphPreconditioner.cpp +++ b/gtsam/linear/SubgraphPreconditioner.cpp @@ -1,150 +1,150 @@ -/* ---------------------------------------------------------------------------- - - * GTSAM Copyright 2010, Georgia Tech Research Corporation, - * Atlanta, Georgia 30332-0415 - * All Rights Reserved - * Authors: Frank Dellaert, et al. (see THANKS for the full author list) - - * See LICENSE for the license information - - * -------------------------------------------------------------------------- */ - -/** - * @file SubgraphPreconditioner.cpp - * @date Dec 31, 2009 - * @author: Frank Dellaert - */ - -#include -#include -#include -#include - -using namespace std; - -namespace gtsam { - - /* ************************************************************************* */ - SubgraphPreconditioner::SubgraphPreconditioner(const sharedFG& Ab1, const sharedFG& Ab2, - const sharedBayesNet& Rc1, const sharedValues& xbar) : - Ab1_(Ab1), Ab2_(Ab2), Rc1_(Rc1), xbar_(xbar), b2bar_(gaussianErrors_(*Ab2_,*xbar)) { - } - - /* ************************************************************************* */ - // x = xbar + inv(R1)*y - VectorValues SubgraphPreconditioner::x(const VectorValues& y) const { -#ifdef VECTORBTREE - if (!y.cloned(*xbar_)) throw - invalid_argument("SubgraphPreconditioner::x: y needs to be cloned from xbar"); -#endif - VectorValues x = y; - backSubstituteInPlace(*Rc1_,x); - x += *xbar_; - return x; - } - -// SubgraphPreconditioner SubgraphPreconditioner::add_priors(double sigma) const { -// SubgraphPreconditioner result = *this ; -// result.Ab2_ = sharedFG(new GaussianFactorGraph(Ab2_->add_priors(sigma))) ; -// return result ; -// } - - /* ************************************************************************* */ - double error(const SubgraphPreconditioner& sp, const VectorValues& y) { - - Errors e(y); - VectorValues x = sp.x(y); - Errors e2 = gaussianErrors(*sp.Ab2(),x); - return 0.5 * (dot(e, e) + dot(e2,e2)); - } - - /* ************************************************************************* */ - // gradient is y + inv(R1')*A2'*(A2*inv(R1)*y-b2bar), - VectorValues gradient(const SubgraphPreconditioner& sp, const VectorValues& y) { - VectorValues x = sp.x(y); // x = inv(R1)*y - Errors e2 = gaussianErrors(*sp.Ab2(),x); - VectorValues gx2 = VectorValues::Zero(y); - gtsam::transposeMultiplyAdd(*sp.Ab2(),1.0,e2,gx2); // A2'*e2; - VectorValues gy2 = gtsam::backSubstituteTranspose(*sp.Rc1(), gx2); // inv(R1')*gx2 - return y + gy2; - } - - /* ************************************************************************* */ - // Apply operator A, A*y = [I;A2*inv(R1)]*y = [y; A2*inv(R1)*y] - Errors operator*(const SubgraphPreconditioner& sp, const VectorValues& y) { - - Errors e(y); - - // Add A2 contribution - VectorValues x = y; // TODO avoid ? - gtsam::backSubstituteInPlace(*sp.Rc1(), x); // x=inv(R1)*y - Errors e2 = *sp.Ab2() * x; // A2*x - e.splice(e.end(), e2); - - return e; - } - - /* ************************************************************************* */ - // In-place version that overwrites e - void multiplyInPlace(const SubgraphPreconditioner& sp, const VectorValues& y, Errors& e) { - - - Errors::iterator ei = e.begin(); - for ( Index i = 0 ; i < y.size() ; ++i, ++ei ) { - *ei = y[i]; - } - - // Add A2 contribution - VectorValues x = y; // TODO avoid ? - gtsam::backSubstituteInPlace(*sp.Rc1(), x); // x=inv(R1)*y - gtsam::multiplyInPlace(*sp.Ab2(),x,ei); // use iterator version - } - - /* ************************************************************************* */ - // Apply operator A', A'*e = [I inv(R1')*A2']*e = e1 + inv(R1')*A2'*e2 - VectorValues operator^(const SubgraphPreconditioner& sp, const Errors& e) { - - Errors::const_iterator it = e.begin(); - VectorValues y = sp.zero(); - for ( Index i = 0 ; i < y.size() ; ++i, ++it ) - y[i] = *it ; - sp.transposeMultiplyAdd2(1.0,it,e.end(),y); - return y; - } - - /* ************************************************************************* */ - // y += alpha*A'*e - void transposeMultiplyAdd - (const SubgraphPreconditioner& sp, double alpha, const Errors& e, VectorValues& y) { - - - Errors::const_iterator it = e.begin(); - for ( Index i = 0 ; i < y.size() ; ++i, ++it ) { - const Vector& ei = *it; - axpy(alpha,ei,y[i]); - } - sp.transposeMultiplyAdd2(alpha,it,e.end(),y); - } - - /* ************************************************************************* */ - // y += alpha*inv(R1')*A2'*e2 - void SubgraphPreconditioner::transposeMultiplyAdd2 (double alpha, - Errors::const_iterator it, Errors::const_iterator end, VectorValues& y) const { - - // create e2 with what's left of e - // TODO can we avoid creating e2 by passing iterator to transposeMultiplyAdd ? - Errors e2; - while (it != end) - e2.push_back(*(it++)); - - VectorValues x = VectorValues::Zero(y); // x = 0 - gtsam::transposeMultiplyAdd(*Ab2_,1.0,e2,x); // x += A2'*e2 - axpy(alpha, gtsam::backSubstituteTranspose(*Rc1_, x), y); // y += alpha*inv(R1')*x - } - - /* ************************************************************************* */ - void SubgraphPreconditioner::print(const std::string& s) const { - cout << s << endl; - Ab2_->print(); - } -} // nsamespace gtsam +///* ---------------------------------------------------------------------------- +// +// * GTSAM Copyright 2010, Georgia Tech Research Corporation, +// * Atlanta, Georgia 30332-0415 +// * All Rights Reserved +// * Authors: Frank Dellaert, et al. (see THANKS for the full author list) +// +// * See LICENSE for the license information +// +// * -------------------------------------------------------------------------- */ +// +///** +// * @file SubgraphPreconditioner.cpp +// * @date Dec 31, 2009 +// * @author: Frank Dellaert +// */ +// +//#include +//#include +//#include +//#include +// +//using namespace std; +// +//namespace gtsam { +// +// /* ************************************************************************* */ +// SubgraphPreconditioner::SubgraphPreconditioner(const sharedFG& Ab1, const sharedFG& Ab2, +// const sharedBayesNet& Rc1, const sharedValues& xbar) : +// Ab1_(Ab1), Ab2_(Ab2), Rc1_(Rc1), xbar_(xbar), b2bar_(gaussianErrors_(*Ab2_,*xbar)) { +// } +// +// /* ************************************************************************* */ +// // x = xbar + inv(R1)*y +// VectorValues SubgraphPreconditioner::x(const VectorValues& y) const { +//#ifdef VECTORBTREE +// if (!y.cloned(*xbar_)) throw +// invalid_argument("SubgraphPreconditioner::x: y needs to be cloned from xbar"); +//#endif +// VectorValues x = y; +// backSubstituteInPlace(*Rc1_,x); +// x += *xbar_; +// return x; +// } +// +//// SubgraphPreconditioner SubgraphPreconditioner::add_priors(double sigma) const { +//// SubgraphPreconditioner result = *this ; +//// result.Ab2_ = sharedFG(new GaussianFactorGraph(Ab2_->add_priors(sigma))) ; +//// return result ; +//// } +// +// /* ************************************************************************* */ +// double error(const SubgraphPreconditioner& sp, const VectorValues& y) { +// +// Errors e(y); +// VectorValues x = sp.x(y); +// Errors e2 = gaussianErrors(*sp.Ab2(),x); +// return 0.5 * (dot(e, e) + dot(e2,e2)); +// } +// +// /* ************************************************************************* */ +// // gradient is y + inv(R1')*A2'*(A2*inv(R1)*y-b2bar), +// VectorValues gradient(const SubgraphPreconditioner& sp, const VectorValues& y) { +// VectorValues x = sp.x(y); // x = inv(R1)*y +// Errors e2 = gaussianErrors(*sp.Ab2(),x); +// VectorValues gx2 = VectorValues::Zero(y); +// gtsam::transposeMultiplyAdd(*sp.Ab2(),1.0,e2,gx2); // A2'*e2; +// VectorValues gy2 = gtsam::backSubstituteTranspose(*sp.Rc1(), gx2); // inv(R1')*gx2 +// return y + gy2; +// } +// +// /* ************************************************************************* */ +// // Apply operator A, A*y = [I;A2*inv(R1)]*y = [y; A2*inv(R1)*y] +// Errors operator*(const SubgraphPreconditioner& sp, const VectorValues& y) { +// +// Errors e(y); +// +// // Add A2 contribution +// VectorValues x = y; // TODO avoid ? +// gtsam::backSubstituteInPlace(*sp.Rc1(), x); // x=inv(R1)*y +// Errors e2 = *sp.Ab2() * x; // A2*x +// e.splice(e.end(), e2); +// +// return e; +// } +// +// /* ************************************************************************* */ +// // In-place version that overwrites e +// void multiplyInPlace(const SubgraphPreconditioner& sp, const VectorValues& y, Errors& e) { +// +// +// Errors::iterator ei = e.begin(); +// for ( Index i = 0 ; i < y.size() ; ++i, ++ei ) { +// *ei = y[i]; +// } +// +// // Add A2 contribution +// VectorValues x = y; // TODO avoid ? +// gtsam::backSubstituteInPlace(*sp.Rc1(), x); // x=inv(R1)*y +// gtsam::multiplyInPlace(*sp.Ab2(),x,ei); // use iterator version +// } +// +// /* ************************************************************************* */ +// // Apply operator A', A'*e = [I inv(R1')*A2']*e = e1 + inv(R1')*A2'*e2 +// VectorValues operator^(const SubgraphPreconditioner& sp, const Errors& e) { +// +// Errors::const_iterator it = e.begin(); +// VectorValues y = sp.zero(); +// for ( Index i = 0 ; i < y.size() ; ++i, ++it ) +// y[i] = *it ; +// sp.transposeMultiplyAdd2(1.0,it,e.end(),y); +// return y; +// } +// +// /* ************************************************************************* */ +// // y += alpha*A'*e +// void transposeMultiplyAdd +// (const SubgraphPreconditioner& sp, double alpha, const Errors& e, VectorValues& y) { +// +// +// Errors::const_iterator it = e.begin(); +// for ( Index i = 0 ; i < y.size() ; ++i, ++it ) { +// const Vector& ei = *it; +// axpy(alpha,ei,y[i]); +// } +// sp.transposeMultiplyAdd2(alpha,it,e.end(),y); +// } +// +// /* ************************************************************************* */ +// // y += alpha*inv(R1')*A2'*e2 +// void SubgraphPreconditioner::transposeMultiplyAdd2 (double alpha, +// Errors::const_iterator it, Errors::const_iterator end, VectorValues& y) const { +// +// // create e2 with what's left of e +// // TODO can we avoid creating e2 by passing iterator to transposeMultiplyAdd ? +// Errors e2; +// while (it != end) +// e2.push_back(*(it++)); +// +// VectorValues x = VectorValues::Zero(y); // x = 0 +// gtsam::transposeMultiplyAdd(*Ab2_,1.0,e2,x); // x += A2'*e2 +// axpy(alpha, gtsam::backSubstituteTranspose(*Rc1_, x), y); // y += alpha*inv(R1')*x +// } +// +// /* ************************************************************************* */ +// void SubgraphPreconditioner::print(const std::string& s) const { +// cout << s << endl; +// Ab2_->print(); +// } +//} // nsamespace gtsam diff --git a/gtsam/linear/SubgraphPreconditioner.h b/gtsam/linear/SubgraphPreconditioner.h index 1e7e6e972..2cc760bfa 100644 --- a/gtsam/linear/SubgraphPreconditioner.h +++ b/gtsam/linear/SubgraphPreconditioner.h @@ -1,116 +1,116 @@ -/* ---------------------------------------------------------------------------- - - * GTSAM Copyright 2010, Georgia Tech Research Corporation, - * Atlanta, Georgia 30332-0415 - * All Rights Reserved - * Authors: Frank Dellaert, et al. (see THANKS for the full author list) - - * See LICENSE for the license information - - * -------------------------------------------------------------------------- */ - -/** - * @file SubgraphPreconditioner.h - * @date Dec 31, 2009 - * @author Frank Dellaert - */ - -#pragma once - -#include -#include -#include // FIXME shouldn't have nonlinear things in linear - -namespace gtsam { - - /** - * Subgraph conditioner class, as explained in the RSS 2010 submission. - * Starting with a graph A*x=b, we split it in two systems A1*x=b1 and A2*x=b2 - * We solve R1*x=c1, and make the substitution y=R1*x-c1. - * To use the class, give the Bayes Net R1*x=c1 and Graph A2*x=b2. - * Then solve for yhat using CG, and solve for xhat = system.x(yhat). - */ - class SubgraphPreconditioner { - - public: - typedef boost::shared_ptr sharedBayesNet; - typedef boost::shared_ptr > sharedFG; - typedef boost::shared_ptr sharedValues; - typedef boost::shared_ptr sharedErrors; - - private: - sharedFG Ab1_, Ab2_; - sharedBayesNet Rc1_; - sharedValues xbar_; - sharedErrors b2bar_; /** b2 - A2*xbar */ - - public: - - SubgraphPreconditioner(); - /** - * Constructor - * @param Ab1: the Graph A1*x=b1 - * @param Ab2: the Graph A2*x=b2 - * @param Rc1: the Bayes Net R1*x=c1 - * @param xbar: the solution to R1*x=c1 - */ - SubgraphPreconditioner(const sharedFG& Ab1, const sharedFG& Ab2, const sharedBayesNet& Rc1, const sharedValues& xbar); - - /** Access Ab1 */ - const sharedFG& Ab1() const { return Ab1_; } - - /** Access Ab2 */ - const sharedFG& Ab2() const { return Ab2_; } - - /** Access Rc1 */ - const sharedBayesNet& Rc1() const { return Rc1_; } - - /** - * Add zero-mean i.i.d. Gaussian prior terms to each variable - * @param sigma Standard deviation of Gaussian - */ -// SubgraphPreconditioner add_priors(double sigma) const; - - /* x = xbar + inv(R1)*y */ - VectorValues x(const VectorValues& y) const; - - /* A zero VectorValues with the structure of xbar */ - VectorValues zero() const { - VectorValues V(VectorValues::Zero(*xbar_)) ; - return V ; - } - - /** - * Add constraint part of the error only, used in both calls above - * y += alpha*inv(R1')*A2'*e2 - * Takes a range indicating e2 !!!! - */ - void transposeMultiplyAdd2(double alpha, Errors::const_iterator begin, - Errors::const_iterator end, VectorValues& y) const; - - /** print the object */ - void print(const std::string& s = "SubgraphPreconditioner") const; - }; - - /* error, given y */ - double error(const SubgraphPreconditioner& sp, const VectorValues& y); - - /** gradient = y + inv(R1')*A2'*(A2*inv(R1)*y-b2bar) */ - VectorValues gradient(const SubgraphPreconditioner& sp, const VectorValues& y); - - /** Apply operator A */ - Errors operator*(const SubgraphPreconditioner& sp, const VectorValues& y); - - /** Apply operator A in place: needs e allocated already */ - void multiplyInPlace(const SubgraphPreconditioner& sp, const VectorValues& y, Errors& e); - - /** Apply operator A' */ - VectorValues operator^(const SubgraphPreconditioner& sp, const Errors& e); - - /** - * Add A'*e to y - * y += alpha*A'*[e1;e2] = [alpha*e1; alpha*inv(R1')*A2'*e2] - */ - void transposeMultiplyAdd(const SubgraphPreconditioner& sp, double alpha, const Errors& e, VectorValues& y); - -} // namespace gtsam +///* ---------------------------------------------------------------------------- +// +// * GTSAM Copyright 2010, Georgia Tech Research Corporation, +// * Atlanta, Georgia 30332-0415 +// * All Rights Reserved +// * Authors: Frank Dellaert, et al. (see THANKS for the full author list) +// +// * See LICENSE for the license information +// +// * -------------------------------------------------------------------------- */ +// +///** +// * @file SubgraphPreconditioner.h +// * @date Dec 31, 2009 +// * @author Frank Dellaert +// */ +// +//#pragma once +// +//#include +//#include +//#include // FIXME shouldn't have nonlinear things in linear +// +//namespace gtsam { +// +// /** +// * Subgraph conditioner class, as explained in the RSS 2010 submission. +// * Starting with a graph A*x=b, we split it in two systems A1*x=b1 and A2*x=b2 +// * We solve R1*x=c1, and make the substitution y=R1*x-c1. +// * To use the class, give the Bayes Net R1*x=c1 and Graph A2*x=b2. +// * Then solve for yhat using CG, and solve for xhat = system.x(yhat). +// */ +// class SubgraphPreconditioner { +// +// public: +// typedef boost::shared_ptr sharedBayesNet; +// typedef boost::shared_ptr > sharedFG; +// typedef boost::shared_ptr sharedValues; +// typedef boost::shared_ptr sharedErrors; +// +// private: +// sharedFG Ab1_, Ab2_; +// sharedBayesNet Rc1_; +// sharedValues xbar_; +// sharedErrors b2bar_; /** b2 - A2*xbar */ +// +// public: +// +// SubgraphPreconditioner(); +// /** +// * Constructor +// * @param Ab1: the Graph A1*x=b1 +// * @param Ab2: the Graph A2*x=b2 +// * @param Rc1: the Bayes Net R1*x=c1 +// * @param xbar: the solution to R1*x=c1 +// */ +// SubgraphPreconditioner(const sharedFG& Ab1, const sharedFG& Ab2, const sharedBayesNet& Rc1, const sharedValues& xbar); +// +// /** Access Ab1 */ +// const sharedFG& Ab1() const { return Ab1_; } +// +// /** Access Ab2 */ +// const sharedFG& Ab2() const { return Ab2_; } +// +// /** Access Rc1 */ +// const sharedBayesNet& Rc1() const { return Rc1_; } +// +// /** +// * Add zero-mean i.i.d. Gaussian prior terms to each variable +// * @param sigma Standard deviation of Gaussian +// */ +//// SubgraphPreconditioner add_priors(double sigma) const; +// +// /* x = xbar + inv(R1)*y */ +// VectorValues x(const VectorValues& y) const; +// +// /* A zero VectorValues with the structure of xbar */ +// VectorValues zero() const { +// VectorValues V(VectorValues::Zero(*xbar_)) ; +// return V ; +// } +// +// /** +// * Add constraint part of the error only, used in both calls above +// * y += alpha*inv(R1')*A2'*e2 +// * Takes a range indicating e2 !!!! +// */ +// void transposeMultiplyAdd2(double alpha, Errors::const_iterator begin, +// Errors::const_iterator end, VectorValues& y) const; +// +// /** print the object */ +// void print(const std::string& s = "SubgraphPreconditioner") const; +// }; +// +// /* error, given y */ +// double error(const SubgraphPreconditioner& sp, const VectorValues& y); +// +// /** gradient = y + inv(R1')*A2'*(A2*inv(R1)*y-b2bar) */ +// VectorValues gradient(const SubgraphPreconditioner& sp, const VectorValues& y); +// +// /** Apply operator A */ +// Errors operator*(const SubgraphPreconditioner& sp, const VectorValues& y); +// +// /** Apply operator A in place: needs e allocated already */ +// void multiplyInPlace(const SubgraphPreconditioner& sp, const VectorValues& y, Errors& e); +// +// /** Apply operator A' */ +// VectorValues operator^(const SubgraphPreconditioner& sp, const Errors& e); +// +// /** +// * Add A'*e to y +// * y += alpha*A'*[e1;e2] = [alpha*e1; alpha*inv(R1')*A2'*e2] +// */ +// void transposeMultiplyAdd(const SubgraphPreconditioner& sp, double alpha, const Errors& e, VectorValues& y); +// +//} // namespace gtsam diff --git a/gtsam/linear/SubgraphSolver.cpp b/gtsam/linear/SubgraphSolver.cpp index ce0934ffe..609b427f2 100644 --- a/gtsam/linear/SubgraphSolver.cpp +++ b/gtsam/linear/SubgraphSolver.cpp @@ -1,50 +1,50 @@ -/* ---------------------------------------------------------------------------- - - * GTSAM Copyright 2010, Georgia Tech Research Corporation, - * Atlanta, Georgia 30332-0415 - * All Rights Reserved - * Authors: Frank Dellaert, et al. (see THANKS for the full author list) - - * See LICENSE for the license information - - * -------------------------------------------------------------------------- */ - -#include - -using namespace std; - -namespace gtsam { - -/* split the gaussian factor graph Ab into Ab1 and Ab2 according to the map */ -bool split(const std::map &M, - const GaussianFactorGraph &Ab, - GaussianFactorGraph &Ab1, - GaussianFactorGraph &Ab2) { - - Ab1 = GaussianFactorGraph(); - Ab2 = GaussianFactorGraph(); - - for ( size_t i = 0 ; i < Ab.size() ; ++i ) { - - boost::shared_ptr factor = Ab[i] ; - - if (factor->keys().size() > 2) - throw(invalid_argument("split: only support factors with at most two keys")); - if (factor->keys().size() == 1) { - Ab1.push_back(factor); - Ab2.push_back(factor); - continue; - } - Index key1 = factor->keys()[0]; - Index key2 = factor->keys()[1]; - - if ((M.find(key1) != M.end() && M.find(key1)->second == key2) || - (M.find(key2) != M.end() && M.find(key2)->second == key1)) - Ab1.push_back(factor); - else - Ab2.push_back(factor); - } - return true ; -} - -} // \namespace gtsam +///* ---------------------------------------------------------------------------- +// +// * GTSAM Copyright 2010, Georgia Tech Research Corporation, +// * Atlanta, Georgia 30332-0415 +// * All Rights Reserved +// * Authors: Frank Dellaert, et al. (see THANKS for the full author list) +// +// * See LICENSE for the license information +// +// * -------------------------------------------------------------------------- */ +// +//#include +// +//using namespace std; +// +//namespace gtsam { +// +///* split the gaussian factor graph Ab into Ab1 and Ab2 according to the map */ +//bool split(const std::map &M, +// const GaussianFactorGraph &Ab, +// GaussianFactorGraph &Ab1, +// GaussianFactorGraph &Ab2) { +// +// Ab1 = GaussianFactorGraph(); +// Ab2 = GaussianFactorGraph(); +// +// for ( size_t i = 0 ; i < Ab.size() ; ++i ) { +// +// boost::shared_ptr factor = Ab[i] ; +// +// if (factor->keys().size() > 2) +// throw(invalid_argument("split: only support factors with at most two keys")); +// if (factor->keys().size() == 1) { +// Ab1.push_back(factor); +// Ab2.push_back(factor); +// continue; +// } +// Index key1 = factor->keys()[0]; +// Index key2 = factor->keys()[1]; +// +// if ((M.find(key1) != M.end() && M.find(key1)->second == key2) || +// (M.find(key2) != M.end() && M.find(key2)->second == key1)) +// Ab1.push_back(factor); +// else +// Ab2.push_back(factor); +// } +// return true ; +//} +// +//} // \namespace gtsam diff --git a/gtsam/linear/SubgraphSolver.h b/gtsam/linear/SubgraphSolver.h index 9e0f0a9d7..f4fa34427 100644 --- a/gtsam/linear/SubgraphSolver.h +++ b/gtsam/linear/SubgraphSolver.h @@ -1,100 +1,100 @@ -/* ---------------------------------------------------------------------------- - - * GTSAM Copyright 2010, Georgia Tech Research Corporation, - * Atlanta, Georgia 30332-0415 - * All Rights Reserved - * Authors: Frank Dellaert, et al. (see THANKS for the full author list) - - * See LICENSE for the license information - - * -------------------------------------------------------------------------- */ - -#pragma once - -#include - -#include -#include -#include - -namespace gtsam { - -/* split the gaussian factor graph Ab into Ab1 and Ab2 according to the map */ -bool split(const std::map &M, - const GaussianFactorGraph &Ab, - GaussianFactorGraph &Ab1, - GaussianFactorGraph &Ab2); - -/** - * A nonlinear system solver using subgraph preconditioning conjugate gradient - * Concept NonLinearSolver implements - * linearize: G * T -> L - * solve : L -> VectorValues - */ -template -class SubgraphSolver : public IterativeSolver { - -private: - typedef typename VALUES::Key Key; - typedef typename GRAPH::Pose Pose; - typedef typename GRAPH::Constraint Constraint; - - typedef boost::shared_ptr shared_ptr ; - typedef boost::shared_ptr shared_ordering ; - typedef boost::shared_ptr shared_graph ; - typedef boost::shared_ptr shared_linear ; - typedef boost::shared_ptr shared_values ; - typedef boost::shared_ptr shared_preconditioner ; - typedef std::map mapPairIndex ; - - /* the ordering derived from the spanning tree */ - shared_ordering ordering_; - - /* the indice of two vertices in the gaussian factor graph */ - mapPairIndex pairs_; - - /* preconditioner */ - shared_preconditioner pc_; - - /* flag for direct solver - either QR or LDL */ - bool useQR_; - -public: - - SubgraphSolver(const GRAPH& G, const VALUES& theta0, const Parameters ¶meters = Parameters(), bool useQR = false): - IterativeSolver(parameters), useQR_(useQR) { initialize(G,theta0); } - - SubgraphSolver(const LINEAR& GFG) { - std::cout << "[SubgraphSolver] Unexpected usage.." << std::endl; - throw std::runtime_error("SubgraphSolver: gaussian factor graph initialization not supported"); - } - - SubgraphSolver(const shared_linear& GFG, const boost::shared_ptr& structure, bool useQR = false) { - std::cout << "[SubgraphSolver] Unexpected usage.." << std::endl; - throw std::runtime_error("SubgraphSolver: gaussian factor graph and variable index initialization not supported"); - } - - SubgraphSolver(const SubgraphSolver& solver) : - IterativeSolver(solver), ordering_(solver.ordering_), pairs_(solver.pairs_), pc_(solver.pc_), useQR_(solver.useQR_) {} - - SubgraphSolver(shared_ordering ordering, - mapPairIndex pairs, - shared_preconditioner pc, - sharedParameters parameters = boost::make_shared(), - bool useQR = true) : - IterativeSolver(parameters), ordering_(ordering), pairs_(pairs), pc_(pc), useQR_(useQR) {} - - void replaceFactors(const typename LINEAR::shared_ptr &graph); - VectorValues::shared_ptr optimize() ; - shared_ordering ordering() const { return ordering_; } - -protected: - void initialize(const GRAPH& G, const VALUES& theta0); - -private: - SubgraphSolver():IterativeSolver(){} -}; - -} // namespace gtsam - -#include +///* ---------------------------------------------------------------------------- +// +// * GTSAM Copyright 2010, Georgia Tech Research Corporation, +// * Atlanta, Georgia 30332-0415 +// * All Rights Reserved +// * Authors: Frank Dellaert, et al. (see THANKS for the full author list) +// +// * See LICENSE for the license information +// +// * -------------------------------------------------------------------------- */ +// +//#pragma once +// +//#include +// +//#include +//#include +//#include +// +//namespace gtsam { +// +///* split the gaussian factor graph Ab into Ab1 and Ab2 according to the map */ +//bool split(const std::map &M, +// const GaussianFactorGraph &Ab, +// GaussianFactorGraph &Ab1, +// GaussianFactorGraph &Ab2); +// +///** +// * A nonlinear system solver using subgraph preconditioning conjugate gradient +// * Concept NonLinearSolver implements +// * linearize: G * T -> L +// * solve : L -> VectorValues +// */ +//template +//class SubgraphSolver : public IterativeSolver { +// +//private: +// typedef typename VALUES::Key Key; +// typedef typename GRAPH::Pose Pose; +// typedef typename GRAPH::Constraint Constraint; +// +// typedef boost::shared_ptr shared_ptr ; +// typedef boost::shared_ptr shared_ordering ; +// typedef boost::shared_ptr shared_graph ; +// typedef boost::shared_ptr shared_linear ; +// typedef boost::shared_ptr shared_values ; +// typedef boost::shared_ptr shared_preconditioner ; +// typedef std::map mapPairIndex ; +// +// /* the ordering derived from the spanning tree */ +// shared_ordering ordering_; +// +// /* the indice of two vertices in the gaussian factor graph */ +// mapPairIndex pairs_; +// +// /* preconditioner */ +// shared_preconditioner pc_; +// +// /* flag for direct solver - either QR or LDL */ +// bool useQR_; +// +//public: +// +// SubgraphSolver(const GRAPH& G, const VALUES& theta0, const Parameters ¶meters = Parameters(), bool useQR = false): +// IterativeSolver(parameters), useQR_(useQR) { initialize(G,theta0); } +// +// SubgraphSolver(const LINEAR& GFG) { +// std::cout << "[SubgraphSolver] Unexpected usage.." << std::endl; +// throw std::runtime_error("SubgraphSolver: gaussian factor graph initialization not supported"); +// } +// +// SubgraphSolver(const shared_linear& GFG, const boost::shared_ptr& structure, bool useQR = false) { +// std::cout << "[SubgraphSolver] Unexpected usage.." << std::endl; +// throw std::runtime_error("SubgraphSolver: gaussian factor graph and variable index initialization not supported"); +// } +// +// SubgraphSolver(const SubgraphSolver& solver) : +// IterativeSolver(solver), ordering_(solver.ordering_), pairs_(solver.pairs_), pc_(solver.pc_), useQR_(solver.useQR_) {} +// +// SubgraphSolver(shared_ordering ordering, +// mapPairIndex pairs, +// shared_preconditioner pc, +// sharedParameters parameters = boost::make_shared(), +// bool useQR = true) : +// IterativeSolver(parameters), ordering_(ordering), pairs_(pairs), pc_(pc), useQR_(useQR) {} +// +// void replaceFactors(const typename LINEAR::shared_ptr &graph); +// VectorValues::shared_ptr optimize() ; +// shared_ordering ordering() const { return ordering_; } +// +//protected: +// void initialize(const GRAPH& G, const VALUES& theta0); +// +//private: +// SubgraphSolver():IterativeSolver(){} +//}; +// +//} // namespace gtsam +// +//#include From f551edddc6990e0b74355bf81268328b8b432cea Mon Sep 17 00:00:00 2001 From: Yong-Dian Jian Date: Fri, 3 Feb 2012 23:21:30 +0000 Subject: [PATCH 03/18] fix interface and parameters --- .../linear/IterativeOptimizationParameters.h | 2 +- gtsam/linear/IterativeSolver.h | 30 ++++++------------- 2 files changed, 10 insertions(+), 22 deletions(-) diff --git a/gtsam/linear/IterativeOptimizationParameters.h b/gtsam/linear/IterativeOptimizationParameters.h index cc9a648aa..e779b7519 100644 --- a/gtsam/linear/IterativeOptimizationParameters.h +++ b/gtsam/linear/IterativeOptimizationParameters.h @@ -38,7 +38,7 @@ public: public: IterativeOptimizationParameters() : - maxIterations_(100), reset_(101), epsilon_(1e-5), epsilon_abs_(1e-5), + maxIterations_(500), reset_(501), epsilon_(1e-3), epsilon_abs_(1e-3), verbosity_(SILENT), nReduce_(0), skeleton_spec_(), est_cond_(false) { } diff --git a/gtsam/linear/IterativeSolver.h b/gtsam/linear/IterativeSolver.h index 7fbcfaa55..600c267ac 100644 --- a/gtsam/linear/IterativeSolver.h +++ b/gtsam/linear/IterativeSolver.h @@ -34,35 +34,23 @@ public: protected: - GaussianFactorGraph::shared_ptr graph_; - VariableIndex::shared_ptr variableIndex_; Parameters::shared_ptr parameters_ ; public: - IterativeSolver( - const GaussianFactorGraph::shared_ptr& factorGraph, - const VariableIndex::shared_ptr& variableIndex): - graph_(factorGraph), variableIndex_(variableIndex), - parameters_(new Parameters()) { } + IterativeSolver(): parameters_(new Parameters()) {} - IterativeSolver( - const GaussianFactorGraph::shared_ptr& factorGraph, - const VariableIndex::shared_ptr& variableIndex, - const Parameters::shared_ptr& parameters): - graph_(factorGraph), variableIndex_(variableIndex), parameters_(parameters) { } + IterativeSolver(const Parameters::shared_ptr& parameters) + : parameters_(parameters) {} - IterativeSolver(): - parameters_(new IterativeOptimizationParameters()) {} + IterativeSolver(const IterativeSolver &solver) + : parameters_(solver.parameters_) {} - IterativeSolver(const IterativeSolver &solver): - parameters_(solver.parameters_) {} + IterativeSolver(const Parameters ¶meters) + : parameters_(new Parameters(parameters)) {} - IterativeSolver(const IterativeOptimizationParameters ¶meters): - parameters_(new IterativeOptimizationParameters(parameters)) {} - - IterativeSolver(const sharedParameters parameters): - parameters_(parameters) {} + IterativeSolver(const sharedParameters parameters) + : parameters_(parameters) {} virtual ~IterativeSolver() {} From 13efb0e4ea62b35a1759b42459d8726fd321693b Mon Sep 17 00:00:00 2001 From: Alex Cunningham Date: Sat, 4 Feb 2012 04:40:35 +0000 Subject: [PATCH 04/18] Removed nonexistant Pose3 constructor and added localCoordinates to Pose3 --- gtsam.h | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/gtsam.h b/gtsam.h index b8aba73ff..d73fd563b 100644 --- a/gtsam.h +++ b/gtsam.h @@ -187,7 +187,6 @@ class Pose2 { class Pose3 { Pose3(); Pose3(const gtsam::Rot3& r, const gtsam::Point3& t); - Pose3(Vector v); Pose3(Matrix t); Pose3(const gtsam::Pose2& pose2); static gtsam::Pose3 Expmap(Vector v); @@ -203,6 +202,7 @@ class Pose3 { gtsam::Pose3 between(const gtsam::Pose3& p2); gtsam::Pose3 retract(Vector v); gtsam::Pose3 retractFirstOrder(Vector v); + Vector localCoordinates(const gtsam::Pose3& T2) const; gtsam::Point3 translation() const; gtsam::Rot3 rotation() const; }; From 9f1f38ac29e0342c66baea0ab946c3bb9782a6a0 Mon Sep 17 00:00:00 2001 From: Alex Cunningham Date: Sat, 4 Feb 2012 21:43:18 +0000 Subject: [PATCH 05/18] testSerialization flag now back in effect, testSerialization will not be compiled by default --- tests/Makefile.am | 9 ++++----- 1 file changed, 4 insertions(+), 5 deletions(-) diff --git a/tests/Makefile.am b/tests/Makefile.am index 19378a83f..cc1b34162 100644 --- a/tests/Makefile.am +++ b/tests/Makefile.am @@ -24,10 +24,9 @@ check_PROGRAMS += testGaussianISAM2 check_PROGRAMS += testExtendedKalmanFilter check_PROGRAMS += testRot3Optimization -## flag disabled to force this test to get updated properly -#if ENABLE_SERIALIZATION +if ENABLE_SERIALIZATION check_PROGRAMS += testSerialization -#endif +endif # Timing tests noinst_PROGRAMS = timeGaussianFactorGraph timeSequentialOnDataset timeMultifrontalOnDataset @@ -40,9 +39,9 @@ AM_LDFLAGS = $(BOOST_LDFLAGS) AM_CPPFLAGS = $(BOOST_CPPFLAGS) -I$(top_srcdir) # link to serialization library for test -#if ENABLE_SERIALIZATION +if ENABLE_SERIALIZATION AM_LDFLAGS += -lboost_serialization -#endif +endif LDADD = ../gtsam/libgtsam.la ../CppUnitLite/libCppUnitLite.a AM_DEFAULT_SOURCE_EXT = .cpp From fab5717917e9be52da2f8d7b48e7253c41bb8c6b Mon Sep 17 00:00:00 2001 From: Alex Cunningham Date: Mon, 6 Feb 2012 01:59:45 +0000 Subject: [PATCH 06/18] Fixed namespace return type bug with pointers in wrap. Matlab tests now pass. --- tests/matlab/testJacobianFactor.m | 11 ++++++----- tests/matlab/testKalmanFilter.m | 6 +++--- wrap/ReturnValue.cpp | 6 +++--- 3 files changed, 12 insertions(+), 11 deletions(-) diff --git a/tests/matlab/testJacobianFactor.m b/tests/matlab/testJacobianFactor.m index ef7ed71f3..2209b36a6 100644 --- a/tests/matlab/testJacobianFactor.m +++ b/tests/matlab/testJacobianFactor.m @@ -29,8 +29,9 @@ x1 = 3; % the RHS b2=[-1;1.5;2;-1]; -model4 = SharedDiagonal([1;1;1;1]); -combined = JacobianFactor(x2, Ax2, l1, Al1, x1, Ax1, b2, model4); +sigmas = [1;1;1;1]; +model4 = gtsamSharedDiagonal(sigmas); +combined = gtsamJacobianFactor(x2, Ax2, l1, Al1, x1, Ax1, b2, model4); % eliminate the first variable (x2) in the combined factor, destructive ! actualCG = combined.eliminateFirst(); @@ -49,7 +50,7 @@ S13 = [ +0.00,-8.94427 ]; d=[2.23607;-1.56525]; -expectedCG = GaussianConditional(x2,d,R11,l1,S12,x1,S13,[1;1]); +expectedCG = gtsamGaussianConditional(x2,d,R11,l1,S12,x1,S13,[1;1]); % check if the result matches CHECK('actualCG.equals(expectedCG,1e-5)',actualCG.equals(expectedCG,1e-4)); @@ -68,8 +69,8 @@ Bx1 = [ % the RHS b1= [0.0;0.894427]; -model2 = SharedDiagonal([1;1]); -expectedLF = JacobianFactor(l1, Bl1, x1, Bx1, b1, model2); +model2 = gtsamSharedDiagonal([1;1]); +expectedLF = gtsamJacobianFactor(l1, Bl1, x1, Bx1, b1, model2); % check if the result matches the combined (reduced) factor % FIXME: JacobianFactor/GaussianFactor mismatch diff --git a/tests/matlab/testKalmanFilter.m b/tests/matlab/testKalmanFilter.m index a074c75d3..e9c1b7149 100644 --- a/tests/matlab/testKalmanFilter.m +++ b/tests/matlab/testKalmanFilter.m @@ -22,13 +22,13 @@ F = eye(2,2); B = eye(2,2); u = [1.0; 0.0]; -modelQ = SharedDiagonal([0.1;0.1]); +modelQ = gtsamSharedDiagonal([0.1;0.1]); Q = 0.01*eye(2,2); H = eye(2,2); z1 = [1.0, 0.0]'; z2 = [2.0, 0.0]'; z3 = [3.0, 0.0]'; -modelR = SharedDiagonal([0.1;0.1]); +modelR = gtsamSharedDiagonal([0.1;0.1]); R = 0.01*eye(2,2); %% Create the set of expected output TestValues @@ -48,7 +48,7 @@ P23 = inv(I22) + Q; I33 = inv(P23) + inv(R); %% Create an KalmanFilter object -KF = KalmanFilter(2); +KF = gtsamKalmanFilter(2); %% Create the Kalman Filter initialization point x_initial = [0.0;0.0]; diff --git a/wrap/ReturnValue.cpp b/wrap/ReturnValue.cpp index 1aad0a08a..2095abc5e 100644 --- a/wrap/ReturnValue.cpp +++ b/wrap/ReturnValue.cpp @@ -59,17 +59,17 @@ void ReturnValue::wrap_result(FileWriter& file) const { // second return value in pair if (isPtr2) // if we already have a pointer - file.oss << " out[1] = wrap_shared_ptr(result.second,\"" << type2 << "\");\n"; + file.oss << " out[1] = wrap_shared_ptr(result.second,\"" << matlabType2 << "\");\n"; else if (category2 == ReturnValue::CLASS) // if we are going to make one file.oss << " out[1] = wrap_shared_ptr(make_shared< " << cppType2 << " >(result.second),\"" << matlabType2 << "\");\n"; else file.oss << " out[1] = wrap< " << return_type(true,arg2) << " >(result.second);\n"; } else if (isPtr1) - file.oss << " out[0] = wrap_shared_ptr(result,\"" << type1 << "\");\n"; + file.oss << " out[0] = wrap_shared_ptr(result,\"" << matlabType1 << "\");\n"; else if (category1 == ReturnValue::CLASS) file.oss << " out[0] = wrap_shared_ptr(make_shared< " << cppType1 << " >(result),\"" << matlabType1 << "\");\n"; - else if (type1!="void") + else if (matlabType1!="void") file.oss << " out[0] = wrap< " << return_type(true,arg1) << " >(result);\n"; } From 9f66fa20becfb4048bb10dbb3b086e5fddc16da2 Mon Sep 17 00:00:00 2001 From: Andrew Melim Date: Mon, 6 Feb 2012 14:05:59 +0000 Subject: [PATCH 07/18] Added CalibratedCamera to gtsam.h --- gtsam.h | 22 ++++++++++++++++++++++ 1 file changed, 22 insertions(+) diff --git a/gtsam.h b/gtsam.h index d73fd563b..c17906df1 100644 --- a/gtsam.h +++ b/gtsam.h @@ -207,6 +207,28 @@ class Pose3 { gtsam::Rot3 rotation() const; }; +class CalibratedCamera { + + CalibratedCamera(); + CalibratedCamera(const gtsam::Pose3& pose); + CalibratedCamera(const Vector& v); + + void print(string s) const; + bool equals(const gtsam::Pose3& pose, double tol) const; + + gtsam::Pose3 pose() const; + + gtsam::CalibratedCamera compose(const gtsam::CalibratedCamera& c) const; + gtsam::CalibratedCamera inverse() const; + gtsam::CalibratedCamera level(const gtsam::Pose2& pose2, double height); + gtsam::CalibratedCamera retract(const Vector& d) const; + Vector localCoordinates(const gtsam::CalibratedCamera& T2) const; + + gtsam::Point2 project(const gtsam::Point3& point) const; + static gtsam::Point2 project_to_camera(const gtsam::Point3& cameraPoint); +}; + + //************************************************************************* // inference //************************************************************************* From 819d3273f42a33c9b9f3702045f464e61d4572bf Mon Sep 17 00:00:00 2001 From: Vadim Indelman Date: Mon, 6 Feb 2012 15:15:01 +0000 Subject: [PATCH 08/18] Added Jacobians' calculation in compose and inverse functions. --- gtsam/base/LieVector.h | 11 +++++++++-- 1 file changed, 9 insertions(+), 2 deletions(-) diff --git a/gtsam/base/LieVector.h b/gtsam/base/LieVector.h index 5a1b3d580..5db89fc49 100644 --- a/gtsam/base/LieVector.h +++ b/gtsam/base/LieVector.h @@ -77,7 +77,12 @@ struct LieVector : public Vector { } /** compose with another object */ - inline LieVector compose(const LieVector& p) const { + inline LieVector compose(const LieVector& p, + boost::optional H1=boost::none, + boost::optional H2=boost::none) const { + if(H1) *H1 = eye(dim()); + if(H2) *H2 = eye(p.dim()); + return LieVector(vector() + p); } @@ -91,7 +96,9 @@ struct LieVector : public Vector { } /** invert the object and yield a new one */ - inline LieVector inverse() const { + inline LieVector inverse(boost::optional H=boost::none) const { + if(H) *H = -eye(dim()); + return LieVector(-1.0 * vector()); } From c2e14b9f0665266c80e6bcbcaa470eef20b52575 Mon Sep 17 00:00:00 2001 From: Frank Dellaert Date: Mon, 6 Feb 2012 17:18:25 +0000 Subject: [PATCH 09/18] No more date to avoid triggering svn changes --- wrap/FileWriter.cpp | 10 +++------- 1 file changed, 3 insertions(+), 7 deletions(-) diff --git a/wrap/FileWriter.cpp b/wrap/FileWriter.cpp index 3ced1ec44..ae474be0a 100644 --- a/wrap/FileWriter.cpp +++ b/wrap/FileWriter.cpp @@ -8,12 +8,10 @@ #include "FileWriter.h" #include "utilities.h" -#include - #include +#include using namespace std; -using namespace boost::gregorian; using namespace wrap; /* ************************************************************************* */ @@ -41,10 +39,8 @@ void FileWriter::emit(bool add_header, bool force_overwrite) const { if (!ofs) throw CantOpenFile(filename_); // header - if (add_header) { - date today = day_clock::local_day(); - ofs << comment_str_ << " automatically generated by wrap on " << today << endl; - } + if (add_header) + ofs << comment_str_ << " automatically generated by wrap" << endl; // dump in stringstream ofs << new_contents; From 345580c7f8e86b6ab16a9819f5f95b83eb77f075 Mon Sep 17 00:00:00 2001 From: Stephen Williams Date: Mon, 6 Feb 2012 18:47:25 +0000 Subject: [PATCH 10/18] Fixed bug in optional jacobians using g++ 4.6.1. Compiler finds the incorrect version of the Matrix class. --- gtsam/base/LieVector.h | 14 +++++++++----- 1 file changed, 9 insertions(+), 5 deletions(-) diff --git a/gtsam/base/LieVector.h b/gtsam/base/LieVector.h index 5db89fc49..30c007349 100644 --- a/gtsam/base/LieVector.h +++ b/gtsam/base/LieVector.h @@ -76,10 +76,14 @@ struct LieVector : public Vector { return LieVector(); } + // Note: Manually specifying the 'gtsam' namespace for the optional Matrix arguments + // This is a work-around for linux g++ 4.6.1 that incorrectly selects the Eigen::Matrix class + // instead of the gtsam::Matrix class. This is related to deriving this class from an Eigen Vector + // as the other geometry objects (Point3, Rot3, etc.) have this problem /** compose with another object */ inline LieVector compose(const LieVector& p, - boost::optional H1=boost::none, - boost::optional H2=boost::none) const { + boost::optional H1=boost::none, + boost::optional H2=boost::none) const { if(H1) *H1 = eye(dim()); if(H2) *H2 = eye(p.dim()); @@ -88,15 +92,15 @@ struct LieVector : public Vector { /** between operation */ inline LieVector between(const LieVector& l2, - boost::optional H1=boost::none, - boost::optional H2=boost::none) const { + boost::optional H1=boost::none, + boost::optional H2=boost::none) const { if(H1) *H1 = -eye(dim()); if(H2) *H2 = eye(l2.dim()); return LieVector(l2.vector() - vector()); } /** invert the object and yield a new one */ - inline LieVector inverse(boost::optional H=boost::none) const { + inline LieVector inverse(boost::optional H=boost::none) const { if(H) *H = -eye(dim()); return LieVector(-1.0 * vector()); From ded872af5fcb0c5bc759a4ad0645ce1dceb79fab Mon Sep 17 00:00:00 2001 From: Alex Cunningham Date: Mon, 6 Feb 2012 19:45:40 +0000 Subject: [PATCH 11/18] Forced wrap to always add a "generated by" header, updated expected test code --- wrap/Class.cpp | 2 +- wrap/Method.cpp | 2 +- wrap/StaticMethod.cpp | 2 +- wrap/tests/expected/@Point2/Point2.m | 1 + wrap/tests/expected/@Point2/argChar.cpp | 11 +++++++++++ wrap/tests/expected/@Point2/argChar.m | 5 +++++ wrap/tests/expected/@Point2/dim.cpp | 2 +- wrap/tests/expected/@Point2/dim.m | 1 + wrap/tests/expected/@Point2/returnChar.cpp | 11 +++++++++++ wrap/tests/expected/@Point2/returnChar.m | 5 +++++ wrap/tests/expected/@Point2/vectorConfusion.cpp | 2 +- wrap/tests/expected/@Point2/vectorConfusion.m | 1 + wrap/tests/expected/@Point2/x.cpp | 2 +- wrap/tests/expected/@Point2/x.m | 1 + wrap/tests/expected/@Point2/y.cpp | 2 +- wrap/tests/expected/@Point2/y.m | 1 + wrap/tests/expected/@Point3/Point3.m | 1 + wrap/tests/expected/@Point3/norm.cpp | 2 +- wrap/tests/expected/@Point3/norm.m | 1 + wrap/tests/expected/@Test/Test.m | 1 + wrap/tests/expected/@Test/arg_EigenConstRef.cpp | 2 +- wrap/tests/expected/@Test/arg_EigenConstRef.m | 1 + wrap/tests/expected/@Test/create_MixedPtrs.cpp | 2 +- wrap/tests/expected/@Test/create_MixedPtrs.m | 1 + wrap/tests/expected/@Test/create_ptrs.cpp | 2 +- wrap/tests/expected/@Test/create_ptrs.m | 1 + wrap/tests/expected/@Test/print.cpp | 2 +- wrap/tests/expected/@Test/print.m | 1 + wrap/tests/expected/@Test/return_Point2Ptr.cpp | 2 +- wrap/tests/expected/@Test/return_Point2Ptr.m | 1 + wrap/tests/expected/@Test/return_Test.cpp | 2 +- wrap/tests/expected/@Test/return_Test.m | 1 + wrap/tests/expected/@Test/return_TestPtr.cpp | 2 +- wrap/tests/expected/@Test/return_TestPtr.m | 1 + wrap/tests/expected/@Test/return_bool.cpp | 2 +- wrap/tests/expected/@Test/return_bool.m | 1 + wrap/tests/expected/@Test/return_double.cpp | 2 +- wrap/tests/expected/@Test/return_double.m | 1 + wrap/tests/expected/@Test/return_field.cpp | 2 +- wrap/tests/expected/@Test/return_field.m | 1 + wrap/tests/expected/@Test/return_int.cpp | 2 +- wrap/tests/expected/@Test/return_int.m | 1 + wrap/tests/expected/@Test/return_matrix1.cpp | 2 +- wrap/tests/expected/@Test/return_matrix1.m | 1 + wrap/tests/expected/@Test/return_matrix2.cpp | 2 +- wrap/tests/expected/@Test/return_matrix2.m | 1 + wrap/tests/expected/@Test/return_pair.cpp | 2 +- wrap/tests/expected/@Test/return_pair.m | 1 + wrap/tests/expected/@Test/return_ptrs.cpp | 2 +- wrap/tests/expected/@Test/return_ptrs.m | 1 + wrap/tests/expected/@Test/return_size_t.cpp | 2 +- wrap/tests/expected/@Test/return_size_t.m | 1 + wrap/tests/expected/@Test/return_string.cpp | 2 +- wrap/tests/expected/@Test/return_string.m | 1 + wrap/tests/expected/@Test/return_vector1.cpp | 2 +- wrap/tests/expected/@Test/return_vector1.m | 1 + wrap/tests/expected/@Test/return_vector2.cpp | 2 +- wrap/tests/expected/@Test/return_vector2.m | 1 + wrap/tests/expected/Makefile | 2 +- wrap/tests/expected/Point3_StaticFunctionRet.cpp | 2 +- wrap/tests/expected/Point3_StaticFunctionRet.m | 1 + wrap/tests/expected/Point3_staticFunction.cpp | 2 +- wrap/tests/expected/Point3_staticFunction.m | 1 + wrap/tests/expected/make_geometry.m | 2 +- wrap/tests/expected/new_Point2_.cpp | 2 +- wrap/tests/expected/new_Point2_.m | 2 +- wrap/tests/expected/new_Point2_dd.cpp | 2 +- wrap/tests/expected/new_Point2_dd.m | 2 +- wrap/tests/expected/new_Point3_ddd.cpp | 2 +- wrap/tests/expected/new_Point3_ddd.m | 2 +- wrap/tests/expected/new_Test_.cpp | 2 +- wrap/tests/expected/new_Test_.m | 2 +- wrap/tests/expected/new_Test_b.cpp | 10 ---------- wrap/tests/expected/new_Test_b.m | 4 ---- wrap/tests/expected/new_Test_dM.cpp | 2 +- wrap/tests/expected/new_Test_dM.m | 2 +- wrap/tests/expected_namespaces/@ClassD/ClassD.m | 3 ++- wrap/tests/expected_namespaces/@ns1ClassA/ns1ClassA.m | 1 + wrap/tests/expected_namespaces/@ns1ClassB/ns1ClassB.m | 1 + .../expected_namespaces/@ns2ClassA/memberFunction.cpp | 2 +- .../expected_namespaces/@ns2ClassA/memberFunction.m | 1 + wrap/tests/expected_namespaces/@ns2ClassA/ns2ClassA.m | 1 + wrap/tests/expected_namespaces/@ns2ClassA/nsArg.cpp | 2 +- wrap/tests/expected_namespaces/@ns2ClassA/nsArg.m | 1 + .../tests/expected_namespaces/@ns2ClassA/nsReturn.cpp | 2 +- wrap/tests/expected_namespaces/@ns2ClassA/nsReturn.m | 1 + wrap/tests/expected_namespaces/@ns2ClassC/ns2ClassC.m | 1 + .../expected_namespaces/@ns2ns3ClassB/ns2ns3ClassB.m | 1 + wrap/tests/expected_namespaces/Makefile | 2 +- wrap/tests/expected_namespaces/make_testNamespaces.m | 2 +- wrap/tests/expected_namespaces/new_ClassD_.cpp | 2 +- wrap/tests/expected_namespaces/new_ClassD_.m | 2 +- wrap/tests/expected_namespaces/new_ns1ClassA_.cpp | 2 +- wrap/tests/expected_namespaces/new_ns1ClassA_.m | 2 +- wrap/tests/expected_namespaces/new_ns1ClassB_.cpp | 2 +- wrap/tests/expected_namespaces/new_ns1ClassB_.m | 2 +- wrap/tests/expected_namespaces/new_ns2ClassA_.cpp | 2 +- wrap/tests/expected_namespaces/new_ns2ClassA_.m | 2 +- wrap/tests/expected_namespaces/new_ns2ClassC_.cpp | 2 +- wrap/tests/expected_namespaces/new_ns2ClassC_.m | 2 +- wrap/tests/expected_namespaces/new_ns2ns3ClassB_.cpp | 2 +- wrap/tests/expected_namespaces/new_ns2ns3ClassB_.m | 2 +- .../tests/expected_namespaces/ns2ClassA_afunction.cpp | 2 +- wrap/tests/expected_namespaces/ns2ClassA_afunction.m | 1 + wrap/utilities.h | 2 +- 105 files changed, 132 insertions(+), 75 deletions(-) create mode 100644 wrap/tests/expected/@Point2/argChar.cpp create mode 100644 wrap/tests/expected/@Point2/argChar.m create mode 100644 wrap/tests/expected/@Point2/returnChar.cpp create mode 100644 wrap/tests/expected/@Point2/returnChar.m delete mode 100644 wrap/tests/expected/new_Test_b.cpp delete mode 100644 wrap/tests/expected/new_Test_b.m diff --git a/wrap/Class.cpp b/wrap/Class.cpp index 8c86ccc58..f6763ac31 100644 --- a/wrap/Class.cpp +++ b/wrap/Class.cpp @@ -51,7 +51,7 @@ void Class::matlab_proxy(const string& classFile) const { file.oss << "end" << endl; // close file - file.emit(false); + file.emit(true); } /* ************************************************************************* */ diff --git a/wrap/Method.cpp b/wrap/Method.cpp index cf280c1d1..3d53956f1 100644 --- a/wrap/Method.cpp +++ b/wrap/Method.cpp @@ -42,7 +42,7 @@ void Method::matlab_mfile(const string& classPath) const { file.oss << "end" << endl; // close file - file.emit(false); + file.emit(true); } /* ************************************************************************* */ diff --git a/wrap/StaticMethod.cpp b/wrap/StaticMethod.cpp index e066d41d8..3dd9e7c8b 100644 --- a/wrap/StaticMethod.cpp +++ b/wrap/StaticMethod.cpp @@ -43,7 +43,7 @@ void StaticMethod::matlab_mfile(const string& toolboxPath, const string& classNa file.oss << "end" << endl; // close file - file.emit(false); + file.emit(true); } /* ************************************************************************* */ diff --git a/wrap/tests/expected/@Point2/Point2.m b/wrap/tests/expected/@Point2/Point2.m index b8cb9a12a..b5545f915 100644 --- a/wrap/tests/expected/@Point2/Point2.m +++ b/wrap/tests/expected/@Point2/Point2.m @@ -1,3 +1,4 @@ +% automatically generated by wrap classdef Point2 properties self = 0 diff --git a/wrap/tests/expected/@Point2/argChar.cpp b/wrap/tests/expected/@Point2/argChar.cpp new file mode 100644 index 000000000..16187cfec --- /dev/null +++ b/wrap/tests/expected/@Point2/argChar.cpp @@ -0,0 +1,11 @@ +// automatically generated by wrap +#include +#include +using namespace geometry; +void mexFunction(int nargout, mxArray *out[], int nargin, const mxArray *in[]) +{ + checkArguments("argChar",nargout,nargin-1,1); + shared_ptr self = unwrap_shared_ptr< Point2 >(in[0],"Point2"); + char a = unwrap< char >(in[1]); + self->argChar(a); +} diff --git a/wrap/tests/expected/@Point2/argChar.m b/wrap/tests/expected/@Point2/argChar.m new file mode 100644 index 000000000..3eccf4b76 --- /dev/null +++ b/wrap/tests/expected/@Point2/argChar.m @@ -0,0 +1,5 @@ + automatically generated by wrap +function result = argChar(obj,a) +% usage: obj.argChar(a) + error('need to compile argChar.cpp'); +end diff --git a/wrap/tests/expected/@Point2/dim.cpp b/wrap/tests/expected/@Point2/dim.cpp index 47a7172f5..f4fa9be65 100644 --- a/wrap/tests/expected/@Point2/dim.cpp +++ b/wrap/tests/expected/@Point2/dim.cpp @@ -1,4 +1,4 @@ -// automatically generated by wrap on 2012-Jan-15 +// automatically generated by wrap #include #include using namespace geometry; diff --git a/wrap/tests/expected/@Point2/dim.m b/wrap/tests/expected/@Point2/dim.m index 40715292e..011eb28a7 100644 --- a/wrap/tests/expected/@Point2/dim.m +++ b/wrap/tests/expected/@Point2/dim.m @@ -1,3 +1,4 @@ + automatically generated by wrap function result = dim(obj) % usage: obj.dim() error('need to compile dim.cpp'); diff --git a/wrap/tests/expected/@Point2/returnChar.cpp b/wrap/tests/expected/@Point2/returnChar.cpp new file mode 100644 index 000000000..8ec723283 --- /dev/null +++ b/wrap/tests/expected/@Point2/returnChar.cpp @@ -0,0 +1,11 @@ +// automatically generated by wrap +#include +#include +using namespace geometry; +void mexFunction(int nargout, mxArray *out[], int nargin, const mxArray *in[]) +{ + checkArguments("returnChar",nargout,nargin-1,0); + shared_ptr self = unwrap_shared_ptr< Point2 >(in[0],"Point2"); + char result = self->returnChar(); + out[0] = wrap< char >(result); +} diff --git a/wrap/tests/expected/@Point2/returnChar.m b/wrap/tests/expected/@Point2/returnChar.m new file mode 100644 index 000000000..c9334a503 --- /dev/null +++ b/wrap/tests/expected/@Point2/returnChar.m @@ -0,0 +1,5 @@ + automatically generated by wrap +function result = returnChar(obj) +% usage: obj.returnChar() + error('need to compile returnChar.cpp'); +end diff --git a/wrap/tests/expected/@Point2/vectorConfusion.cpp b/wrap/tests/expected/@Point2/vectorConfusion.cpp index 2a2234529..cd8be15d2 100644 --- a/wrap/tests/expected/@Point2/vectorConfusion.cpp +++ b/wrap/tests/expected/@Point2/vectorConfusion.cpp @@ -1,4 +1,4 @@ -// automatically generated by wrap on 2012-Jan-15 +// automatically generated by wrap #include #include using namespace geometry; diff --git a/wrap/tests/expected/@Point2/vectorConfusion.m b/wrap/tests/expected/@Point2/vectorConfusion.m index d141e8085..0db1db291 100644 --- a/wrap/tests/expected/@Point2/vectorConfusion.m +++ b/wrap/tests/expected/@Point2/vectorConfusion.m @@ -1,3 +1,4 @@ + automatically generated by wrap function result = vectorConfusion(obj) % usage: obj.vectorConfusion() error('need to compile vectorConfusion.cpp'); diff --git a/wrap/tests/expected/@Point2/x.cpp b/wrap/tests/expected/@Point2/x.cpp index f53befc28..2c994c8e2 100644 --- a/wrap/tests/expected/@Point2/x.cpp +++ b/wrap/tests/expected/@Point2/x.cpp @@ -1,4 +1,4 @@ -// automatically generated by wrap on 2012-Jan-15 +// automatically generated by wrap #include #include using namespace geometry; diff --git a/wrap/tests/expected/@Point2/x.m b/wrap/tests/expected/@Point2/x.m index f91039ab7..0a6e99d16 100644 --- a/wrap/tests/expected/@Point2/x.m +++ b/wrap/tests/expected/@Point2/x.m @@ -1,3 +1,4 @@ + automatically generated by wrap function result = x(obj) % usage: obj.x() error('need to compile x.cpp'); diff --git a/wrap/tests/expected/@Point2/y.cpp b/wrap/tests/expected/@Point2/y.cpp index 5933a554b..d0b007125 100644 --- a/wrap/tests/expected/@Point2/y.cpp +++ b/wrap/tests/expected/@Point2/y.cpp @@ -1,4 +1,4 @@ -// automatically generated by wrap on 2012-Jan-15 +// automatically generated by wrap #include #include using namespace geometry; diff --git a/wrap/tests/expected/@Point2/y.m b/wrap/tests/expected/@Point2/y.m index f9f36ae90..ee5a55e1d 100644 --- a/wrap/tests/expected/@Point2/y.m +++ b/wrap/tests/expected/@Point2/y.m @@ -1,3 +1,4 @@ + automatically generated by wrap function result = y(obj) % usage: obj.y() error('need to compile y.cpp'); diff --git a/wrap/tests/expected/@Point3/Point3.m b/wrap/tests/expected/@Point3/Point3.m index aba7ffedd..a83c13792 100644 --- a/wrap/tests/expected/@Point3/Point3.m +++ b/wrap/tests/expected/@Point3/Point3.m @@ -1,3 +1,4 @@ +% automatically generated by wrap classdef Point3 properties self = 0 diff --git a/wrap/tests/expected/@Point3/norm.cpp b/wrap/tests/expected/@Point3/norm.cpp index f8f1318f9..9936958d7 100644 --- a/wrap/tests/expected/@Point3/norm.cpp +++ b/wrap/tests/expected/@Point3/norm.cpp @@ -1,4 +1,4 @@ -// automatically generated by wrap on 2012-Jan-15 +// automatically generated by wrap #include #include using namespace geometry; diff --git a/wrap/tests/expected/@Point3/norm.m b/wrap/tests/expected/@Point3/norm.m index dc4e62597..bb6482df4 100644 --- a/wrap/tests/expected/@Point3/norm.m +++ b/wrap/tests/expected/@Point3/norm.m @@ -1,3 +1,4 @@ + automatically generated by wrap function result = norm(obj) % usage: obj.norm() error('need to compile norm.cpp'); diff --git a/wrap/tests/expected/@Test/Test.m b/wrap/tests/expected/@Test/Test.m index 7c46da816..66a110f2f 100644 --- a/wrap/tests/expected/@Test/Test.m +++ b/wrap/tests/expected/@Test/Test.m @@ -1,3 +1,4 @@ +% automatically generated by wrap classdef Test properties self = 0 diff --git a/wrap/tests/expected/@Test/arg_EigenConstRef.cpp b/wrap/tests/expected/@Test/arg_EigenConstRef.cpp index 15819d68b..487741c07 100644 --- a/wrap/tests/expected/@Test/arg_EigenConstRef.cpp +++ b/wrap/tests/expected/@Test/arg_EigenConstRef.cpp @@ -1,4 +1,4 @@ -// automatically generated by wrap on 2012-Jan-15 +// automatically generated by wrap #include #include using namespace geometry; diff --git a/wrap/tests/expected/@Test/arg_EigenConstRef.m b/wrap/tests/expected/@Test/arg_EigenConstRef.m index e353faa29..76f190d99 100644 --- a/wrap/tests/expected/@Test/arg_EigenConstRef.m +++ b/wrap/tests/expected/@Test/arg_EigenConstRef.m @@ -1,3 +1,4 @@ + automatically generated by wrap function result = arg_EigenConstRef(obj,value) % usage: obj.arg_EigenConstRef(value) error('need to compile arg_EigenConstRef.cpp'); diff --git a/wrap/tests/expected/@Test/create_MixedPtrs.cpp b/wrap/tests/expected/@Test/create_MixedPtrs.cpp index 27a663d81..269bb990c 100644 --- a/wrap/tests/expected/@Test/create_MixedPtrs.cpp +++ b/wrap/tests/expected/@Test/create_MixedPtrs.cpp @@ -1,4 +1,4 @@ -// automatically generated by wrap on 2012-Jan-15 +// automatically generated by wrap #include #include using namespace geometry; diff --git a/wrap/tests/expected/@Test/create_MixedPtrs.m b/wrap/tests/expected/@Test/create_MixedPtrs.m index 9062cabcb..764ce822c 100644 --- a/wrap/tests/expected/@Test/create_MixedPtrs.m +++ b/wrap/tests/expected/@Test/create_MixedPtrs.m @@ -1,3 +1,4 @@ + automatically generated by wrap function [first,second] = create_MixedPtrs(obj) % usage: obj.create_MixedPtrs() error('need to compile create_MixedPtrs.cpp'); diff --git a/wrap/tests/expected/@Test/create_ptrs.cpp b/wrap/tests/expected/@Test/create_ptrs.cpp index 48a9e4645..bfd9f39bf 100644 --- a/wrap/tests/expected/@Test/create_ptrs.cpp +++ b/wrap/tests/expected/@Test/create_ptrs.cpp @@ -1,4 +1,4 @@ -// automatically generated by wrap on 2012-Jan-15 +// automatically generated by wrap #include #include using namespace geometry; diff --git a/wrap/tests/expected/@Test/create_ptrs.m b/wrap/tests/expected/@Test/create_ptrs.m index 11af0ac5b..b1623b5bc 100644 --- a/wrap/tests/expected/@Test/create_ptrs.m +++ b/wrap/tests/expected/@Test/create_ptrs.m @@ -1,3 +1,4 @@ + automatically generated by wrap function [first,second] = create_ptrs(obj) % usage: obj.create_ptrs() error('need to compile create_ptrs.cpp'); diff --git a/wrap/tests/expected/@Test/print.cpp b/wrap/tests/expected/@Test/print.cpp index e945988b5..e93f5f09a 100644 --- a/wrap/tests/expected/@Test/print.cpp +++ b/wrap/tests/expected/@Test/print.cpp @@ -1,4 +1,4 @@ -// automatically generated by wrap on 2012-Jan-15 +// automatically generated by wrap #include #include using namespace geometry; diff --git a/wrap/tests/expected/@Test/print.m b/wrap/tests/expected/@Test/print.m index cf181c3cf..2adca017d 100644 --- a/wrap/tests/expected/@Test/print.m +++ b/wrap/tests/expected/@Test/print.m @@ -1,3 +1,4 @@ + automatically generated by wrap function result = print(obj) % usage: obj.print() error('need to compile print.cpp'); diff --git a/wrap/tests/expected/@Test/return_Point2Ptr.cpp b/wrap/tests/expected/@Test/return_Point2Ptr.cpp index f6f366f8d..9ad2a4360 100644 --- a/wrap/tests/expected/@Test/return_Point2Ptr.cpp +++ b/wrap/tests/expected/@Test/return_Point2Ptr.cpp @@ -1,4 +1,4 @@ -// automatically generated by wrap on 2012-Jan-15 +// automatically generated by wrap #include #include using namespace geometry; diff --git a/wrap/tests/expected/@Test/return_Point2Ptr.m b/wrap/tests/expected/@Test/return_Point2Ptr.m index 2da8b3710..410081dcb 100644 --- a/wrap/tests/expected/@Test/return_Point2Ptr.m +++ b/wrap/tests/expected/@Test/return_Point2Ptr.m @@ -1,3 +1,4 @@ + automatically generated by wrap function result = return_Point2Ptr(obj,value) % usage: obj.return_Point2Ptr(value) error('need to compile return_Point2Ptr.cpp'); diff --git a/wrap/tests/expected/@Test/return_Test.cpp b/wrap/tests/expected/@Test/return_Test.cpp index 0ead17cb2..73c63a899 100644 --- a/wrap/tests/expected/@Test/return_Test.cpp +++ b/wrap/tests/expected/@Test/return_Test.cpp @@ -1,4 +1,4 @@ -// automatically generated by wrap on 2012-Jan-15 +// automatically generated by wrap #include #include using namespace geometry; diff --git a/wrap/tests/expected/@Test/return_Test.m b/wrap/tests/expected/@Test/return_Test.m index 01f4ec61b..2faa73be3 100644 --- a/wrap/tests/expected/@Test/return_Test.m +++ b/wrap/tests/expected/@Test/return_Test.m @@ -1,3 +1,4 @@ + automatically generated by wrap function result = return_Test(obj,value) % usage: obj.return_Test(value) error('need to compile return_Test.cpp'); diff --git a/wrap/tests/expected/@Test/return_TestPtr.cpp b/wrap/tests/expected/@Test/return_TestPtr.cpp index 3aae3fdb9..607e48cfd 100644 --- a/wrap/tests/expected/@Test/return_TestPtr.cpp +++ b/wrap/tests/expected/@Test/return_TestPtr.cpp @@ -1,4 +1,4 @@ -// automatically generated by wrap on 2012-Jan-15 +// automatically generated by wrap #include #include using namespace geometry; diff --git a/wrap/tests/expected/@Test/return_TestPtr.m b/wrap/tests/expected/@Test/return_TestPtr.m index e1d0c90f5..7c40e76c6 100644 --- a/wrap/tests/expected/@Test/return_TestPtr.m +++ b/wrap/tests/expected/@Test/return_TestPtr.m @@ -1,3 +1,4 @@ + automatically generated by wrap function result = return_TestPtr(obj,value) % usage: obj.return_TestPtr(value) error('need to compile return_TestPtr.cpp'); diff --git a/wrap/tests/expected/@Test/return_bool.cpp b/wrap/tests/expected/@Test/return_bool.cpp index 3581777ed..d700ead2b 100644 --- a/wrap/tests/expected/@Test/return_bool.cpp +++ b/wrap/tests/expected/@Test/return_bool.cpp @@ -1,4 +1,4 @@ -// automatically generated by wrap on 2012-Jan-15 +// automatically generated by wrap #include #include using namespace geometry; diff --git a/wrap/tests/expected/@Test/return_bool.m b/wrap/tests/expected/@Test/return_bool.m index 185ab992d..76fc4363b 100644 --- a/wrap/tests/expected/@Test/return_bool.m +++ b/wrap/tests/expected/@Test/return_bool.m @@ -1,3 +1,4 @@ + automatically generated by wrap function result = return_bool(obj,value) % usage: obj.return_bool(value) error('need to compile return_bool.cpp'); diff --git a/wrap/tests/expected/@Test/return_double.cpp b/wrap/tests/expected/@Test/return_double.cpp index d2f08c939..38770e1cd 100644 --- a/wrap/tests/expected/@Test/return_double.cpp +++ b/wrap/tests/expected/@Test/return_double.cpp @@ -1,4 +1,4 @@ -// automatically generated by wrap on 2012-Jan-15 +// automatically generated by wrap #include #include using namespace geometry; diff --git a/wrap/tests/expected/@Test/return_double.m b/wrap/tests/expected/@Test/return_double.m index a6ba733cf..daed1d34b 100644 --- a/wrap/tests/expected/@Test/return_double.m +++ b/wrap/tests/expected/@Test/return_double.m @@ -1,3 +1,4 @@ + automatically generated by wrap function result = return_double(obj,value) % usage: obj.return_double(value) error('need to compile return_double.cpp'); diff --git a/wrap/tests/expected/@Test/return_field.cpp b/wrap/tests/expected/@Test/return_field.cpp index 9de7a9ed6..b5e067801 100644 --- a/wrap/tests/expected/@Test/return_field.cpp +++ b/wrap/tests/expected/@Test/return_field.cpp @@ -1,4 +1,4 @@ -// automatically generated by wrap on 2012-Jan-15 +// automatically generated by wrap #include #include using namespace geometry; diff --git a/wrap/tests/expected/@Test/return_field.m b/wrap/tests/expected/@Test/return_field.m index 278ffa411..11b5ebe07 100644 --- a/wrap/tests/expected/@Test/return_field.m +++ b/wrap/tests/expected/@Test/return_field.m @@ -1,3 +1,4 @@ + automatically generated by wrap function result = return_field(obj,t) % usage: obj.return_field(t) error('need to compile return_field.cpp'); diff --git a/wrap/tests/expected/@Test/return_int.cpp b/wrap/tests/expected/@Test/return_int.cpp index f94551f03..e2dfd25e8 100644 --- a/wrap/tests/expected/@Test/return_int.cpp +++ b/wrap/tests/expected/@Test/return_int.cpp @@ -1,4 +1,4 @@ -// automatically generated by wrap on 2012-Jan-15 +// automatically generated by wrap #include #include using namespace geometry; diff --git a/wrap/tests/expected/@Test/return_int.m b/wrap/tests/expected/@Test/return_int.m index 8b613285c..a6783acdf 100644 --- a/wrap/tests/expected/@Test/return_int.m +++ b/wrap/tests/expected/@Test/return_int.m @@ -1,3 +1,4 @@ + automatically generated by wrap function result = return_int(obj,value) % usage: obj.return_int(value) error('need to compile return_int.cpp'); diff --git a/wrap/tests/expected/@Test/return_matrix1.cpp b/wrap/tests/expected/@Test/return_matrix1.cpp index 2e726f572..8bb9acff8 100644 --- a/wrap/tests/expected/@Test/return_matrix1.cpp +++ b/wrap/tests/expected/@Test/return_matrix1.cpp @@ -1,4 +1,4 @@ -// automatically generated by wrap on 2012-Jan-15 +// automatically generated by wrap #include #include using namespace geometry; diff --git a/wrap/tests/expected/@Test/return_matrix1.m b/wrap/tests/expected/@Test/return_matrix1.m index 29743158c..302f15372 100644 --- a/wrap/tests/expected/@Test/return_matrix1.m +++ b/wrap/tests/expected/@Test/return_matrix1.m @@ -1,3 +1,4 @@ + automatically generated by wrap function result = return_matrix1(obj,value) % usage: obj.return_matrix1(value) error('need to compile return_matrix1.cpp'); diff --git a/wrap/tests/expected/@Test/return_matrix2.cpp b/wrap/tests/expected/@Test/return_matrix2.cpp index 1e18e3aba..f1a22da47 100644 --- a/wrap/tests/expected/@Test/return_matrix2.cpp +++ b/wrap/tests/expected/@Test/return_matrix2.cpp @@ -1,4 +1,4 @@ -// automatically generated by wrap on 2012-Jan-15 +// automatically generated by wrap #include #include using namespace geometry; diff --git a/wrap/tests/expected/@Test/return_matrix2.m b/wrap/tests/expected/@Test/return_matrix2.m index e9ec91678..3ed4d0ec7 100644 --- a/wrap/tests/expected/@Test/return_matrix2.m +++ b/wrap/tests/expected/@Test/return_matrix2.m @@ -1,3 +1,4 @@ + automatically generated by wrap function result = return_matrix2(obj,value) % usage: obj.return_matrix2(value) error('need to compile return_matrix2.cpp'); diff --git a/wrap/tests/expected/@Test/return_pair.cpp b/wrap/tests/expected/@Test/return_pair.cpp index 81802130a..8f6949d7c 100644 --- a/wrap/tests/expected/@Test/return_pair.cpp +++ b/wrap/tests/expected/@Test/return_pair.cpp @@ -1,4 +1,4 @@ -// automatically generated by wrap on 2012-Jan-15 +// automatically generated by wrap #include #include using namespace geometry; diff --git a/wrap/tests/expected/@Test/return_pair.m b/wrap/tests/expected/@Test/return_pair.m index a97f7c46e..abb97336c 100644 --- a/wrap/tests/expected/@Test/return_pair.m +++ b/wrap/tests/expected/@Test/return_pair.m @@ -1,3 +1,4 @@ + automatically generated by wrap function [first,second] = return_pair(obj,v,A) % usage: obj.return_pair(v,A) error('need to compile return_pair.cpp'); diff --git a/wrap/tests/expected/@Test/return_ptrs.cpp b/wrap/tests/expected/@Test/return_ptrs.cpp index 27085fcc6..20d6c57fe 100644 --- a/wrap/tests/expected/@Test/return_ptrs.cpp +++ b/wrap/tests/expected/@Test/return_ptrs.cpp @@ -1,4 +1,4 @@ -// automatically generated by wrap on 2012-Jan-15 +// automatically generated by wrap #include #include using namespace geometry; diff --git a/wrap/tests/expected/@Test/return_ptrs.m b/wrap/tests/expected/@Test/return_ptrs.m index ef7f8e5fc..bed198563 100644 --- a/wrap/tests/expected/@Test/return_ptrs.m +++ b/wrap/tests/expected/@Test/return_ptrs.m @@ -1,3 +1,4 @@ + automatically generated by wrap function [first,second] = return_ptrs(obj,p1,p2) % usage: obj.return_ptrs(p1,p2) error('need to compile return_ptrs.cpp'); diff --git a/wrap/tests/expected/@Test/return_size_t.cpp b/wrap/tests/expected/@Test/return_size_t.cpp index 94b7d7b6c..6b12a167b 100644 --- a/wrap/tests/expected/@Test/return_size_t.cpp +++ b/wrap/tests/expected/@Test/return_size_t.cpp @@ -1,4 +1,4 @@ -// automatically generated by wrap on 2012-Jan-15 +// automatically generated by wrap #include #include using namespace geometry; diff --git a/wrap/tests/expected/@Test/return_size_t.m b/wrap/tests/expected/@Test/return_size_t.m index bc2734410..7cb2c6f0f 100644 --- a/wrap/tests/expected/@Test/return_size_t.m +++ b/wrap/tests/expected/@Test/return_size_t.m @@ -1,3 +1,4 @@ + automatically generated by wrap function result = return_size_t(obj,value) % usage: obj.return_size_t(value) error('need to compile return_size_t.cpp'); diff --git a/wrap/tests/expected/@Test/return_string.cpp b/wrap/tests/expected/@Test/return_string.cpp index 786d98955..c05a57fba 100644 --- a/wrap/tests/expected/@Test/return_string.cpp +++ b/wrap/tests/expected/@Test/return_string.cpp @@ -1,4 +1,4 @@ -// automatically generated by wrap on 2012-Jan-15 +// automatically generated by wrap #include #include using namespace geometry; diff --git a/wrap/tests/expected/@Test/return_string.m b/wrap/tests/expected/@Test/return_string.m index 3f2304a65..5661df443 100644 --- a/wrap/tests/expected/@Test/return_string.m +++ b/wrap/tests/expected/@Test/return_string.m @@ -1,3 +1,4 @@ + automatically generated by wrap function result = return_string(obj,value) % usage: obj.return_string(value) error('need to compile return_string.cpp'); diff --git a/wrap/tests/expected/@Test/return_vector1.cpp b/wrap/tests/expected/@Test/return_vector1.cpp index a2e5108bd..3710e5d48 100644 --- a/wrap/tests/expected/@Test/return_vector1.cpp +++ b/wrap/tests/expected/@Test/return_vector1.cpp @@ -1,4 +1,4 @@ -// automatically generated by wrap on 2012-Jan-15 +// automatically generated by wrap #include #include using namespace geometry; diff --git a/wrap/tests/expected/@Test/return_vector1.m b/wrap/tests/expected/@Test/return_vector1.m index f67382978..3746c4c20 100644 --- a/wrap/tests/expected/@Test/return_vector1.m +++ b/wrap/tests/expected/@Test/return_vector1.m @@ -1,3 +1,4 @@ + automatically generated by wrap function result = return_vector1(obj,value) % usage: obj.return_vector1(value) error('need to compile return_vector1.cpp'); diff --git a/wrap/tests/expected/@Test/return_vector2.cpp b/wrap/tests/expected/@Test/return_vector2.cpp index 03d584d06..72564f05c 100644 --- a/wrap/tests/expected/@Test/return_vector2.cpp +++ b/wrap/tests/expected/@Test/return_vector2.cpp @@ -1,4 +1,4 @@ -// automatically generated by wrap on 2012-Jan-15 +// automatically generated by wrap #include #include using namespace geometry; diff --git a/wrap/tests/expected/@Test/return_vector2.m b/wrap/tests/expected/@Test/return_vector2.m index 95b6bcfd6..426c63457 100644 --- a/wrap/tests/expected/@Test/return_vector2.m +++ b/wrap/tests/expected/@Test/return_vector2.m @@ -1,3 +1,4 @@ + automatically generated by wrap function result = return_vector2(obj,value) % usage: obj.return_vector2(value) error('need to compile return_vector2.cpp'); diff --git a/wrap/tests/expected/Makefile b/wrap/tests/expected/Makefile index 662e1586b..cc5f06578 100644 --- a/wrap/tests/expected/Makefile +++ b/wrap/tests/expected/Makefile @@ -1,4 +1,4 @@ -# automatically generated by wrap on 2012-Jan-23 +# automatically generated by wrap MEX = mex MEXENDING = mexa64 diff --git a/wrap/tests/expected/Point3_StaticFunctionRet.cpp b/wrap/tests/expected/Point3_StaticFunctionRet.cpp index 4be4329ed..062194bd5 100644 --- a/wrap/tests/expected/Point3_StaticFunctionRet.cpp +++ b/wrap/tests/expected/Point3_StaticFunctionRet.cpp @@ -1,4 +1,4 @@ -// automatically generated by wrap on 2012-Jan-15 +// automatically generated by wrap #include #include using namespace geometry; diff --git a/wrap/tests/expected/Point3_StaticFunctionRet.m b/wrap/tests/expected/Point3_StaticFunctionRet.m index 25a9d6ff2..433d3c00d 100644 --- a/wrap/tests/expected/Point3_StaticFunctionRet.m +++ b/wrap/tests/expected/Point3_StaticFunctionRet.m @@ -1,3 +1,4 @@ + automatically generated by wrap function result = Point3_StaticFunctionRet(z) % usage: x = Point3_StaticFunctionRet(z) error('need to compile Point3_StaticFunctionRet.cpp'); diff --git a/wrap/tests/expected/Point3_staticFunction.cpp b/wrap/tests/expected/Point3_staticFunction.cpp index 7024cb9d7..6adfdbe5a 100644 --- a/wrap/tests/expected/Point3_staticFunction.cpp +++ b/wrap/tests/expected/Point3_staticFunction.cpp @@ -1,4 +1,4 @@ -// automatically generated by wrap on 2012-Jan-15 +// automatically generated by wrap #include #include using namespace geometry; diff --git a/wrap/tests/expected/Point3_staticFunction.m b/wrap/tests/expected/Point3_staticFunction.m index 441bb5bc6..ccf9b85bd 100644 --- a/wrap/tests/expected/Point3_staticFunction.m +++ b/wrap/tests/expected/Point3_staticFunction.m @@ -1,3 +1,4 @@ + automatically generated by wrap function result = Point3_staticFunction() % usage: x = Point3_staticFunction() error('need to compile Point3_staticFunction.cpp'); diff --git a/wrap/tests/expected/make_geometry.m b/wrap/tests/expected/make_geometry.m index 1824d8b74..ce2208e7e 100644 --- a/wrap/tests/expected/make_geometry.m +++ b/wrap/tests/expected/make_geometry.m @@ -1,4 +1,4 @@ -% automatically generated by wrap on 2012-Jan-23 +% automatically generated by wrap echo on toolboxpath = mfilename('fullpath'); diff --git a/wrap/tests/expected/new_Point2_.cpp b/wrap/tests/expected/new_Point2_.cpp index 9b3aa2fa5..661307b60 100644 --- a/wrap/tests/expected/new_Point2_.cpp +++ b/wrap/tests/expected/new_Point2_.cpp @@ -1,4 +1,4 @@ -// automatically generated by wrap on 2012-Jan-15 +// automatically generated by wrap #include #include using namespace geometry; diff --git a/wrap/tests/expected/new_Point2_.m b/wrap/tests/expected/new_Point2_.m index e2215bfec..b0b655b5e 100644 --- a/wrap/tests/expected/new_Point2_.m +++ b/wrap/tests/expected/new_Point2_.m @@ -1,4 +1,4 @@ -% automatically generated by wrap on 2012-Jan-15 +% automatically generated by wrap function result = new_Point2_(obj) error('need to compile new_Point2_.cpp'); end diff --git a/wrap/tests/expected/new_Point2_dd.cpp b/wrap/tests/expected/new_Point2_dd.cpp index 496e22239..2c6e743ca 100644 --- a/wrap/tests/expected/new_Point2_dd.cpp +++ b/wrap/tests/expected/new_Point2_dd.cpp @@ -1,4 +1,4 @@ -// automatically generated by wrap on 2012-Jan-15 +// automatically generated by wrap #include #include using namespace geometry; diff --git a/wrap/tests/expected/new_Point2_dd.m b/wrap/tests/expected/new_Point2_dd.m index 947e9477d..4a769ce30 100644 --- a/wrap/tests/expected/new_Point2_dd.m +++ b/wrap/tests/expected/new_Point2_dd.m @@ -1,4 +1,4 @@ -% automatically generated by wrap on 2012-Jan-15 +% automatically generated by wrap function result = new_Point2_dd(obj,x,y) error('need to compile new_Point2_dd.cpp'); end diff --git a/wrap/tests/expected/new_Point3_ddd.cpp b/wrap/tests/expected/new_Point3_ddd.cpp index b3b410443..aa45dc71c 100644 --- a/wrap/tests/expected/new_Point3_ddd.cpp +++ b/wrap/tests/expected/new_Point3_ddd.cpp @@ -1,4 +1,4 @@ -// automatically generated by wrap on 2012-Jan-15 +// automatically generated by wrap #include #include using namespace geometry; diff --git a/wrap/tests/expected/new_Point3_ddd.m b/wrap/tests/expected/new_Point3_ddd.m index 089268cc1..154dda1d0 100644 --- a/wrap/tests/expected/new_Point3_ddd.m +++ b/wrap/tests/expected/new_Point3_ddd.m @@ -1,4 +1,4 @@ -% automatically generated by wrap on 2012-Jan-15 +% automatically generated by wrap function result = new_Point3_ddd(obj,x,y,z) error('need to compile new_Point3_ddd.cpp'); end diff --git a/wrap/tests/expected/new_Test_.cpp b/wrap/tests/expected/new_Test_.cpp index 0080e3b21..9c66706ae 100644 --- a/wrap/tests/expected/new_Test_.cpp +++ b/wrap/tests/expected/new_Test_.cpp @@ -1,4 +1,4 @@ -// automatically generated by wrap on 2012-Jan-15 +// automatically generated by wrap #include #include using namespace geometry; diff --git a/wrap/tests/expected/new_Test_.m b/wrap/tests/expected/new_Test_.m index b1b04f083..33c465f8b 100644 --- a/wrap/tests/expected/new_Test_.m +++ b/wrap/tests/expected/new_Test_.m @@ -1,4 +1,4 @@ -% automatically generated by wrap on 2012-Jan-15 +% automatically generated by wrap function result = new_Test_(obj) error('need to compile new_Test_.cpp'); end diff --git a/wrap/tests/expected/new_Test_b.cpp b/wrap/tests/expected/new_Test_b.cpp deleted file mode 100644 index 921c692af..000000000 --- a/wrap/tests/expected/new_Test_b.cpp +++ /dev/null @@ -1,10 +0,0 @@ -// automatically generated by wrap on 2011-Dec-01 -#include -#include -void mexFunction(int nargout, mxArray *out[], int nargin, const mxArray *in[]) -{ - checkArguments("new_Test_b",nargout,nargin,1); - bool value = unwrap< bool >(in[0]); - Test* self = new Test(value); - out[0] = wrap_constructed(self,"Test"); -} diff --git a/wrap/tests/expected/new_Test_b.m b/wrap/tests/expected/new_Test_b.m deleted file mode 100644 index a07945d9f..000000000 --- a/wrap/tests/expected/new_Test_b.m +++ /dev/null @@ -1,4 +0,0 @@ -% automatically generated by wrap on 2011-Dec-01 -function result = new_Test_b(obj,value) - error('need to compile new_Test_b.cpp'); -end diff --git a/wrap/tests/expected/new_Test_dM.cpp b/wrap/tests/expected/new_Test_dM.cpp index 5a4ad0bd8..e8a7c8de1 100644 --- a/wrap/tests/expected/new_Test_dM.cpp +++ b/wrap/tests/expected/new_Test_dM.cpp @@ -1,4 +1,4 @@ -// automatically generated by wrap on 2012-Jan-15 +// automatically generated by wrap #include #include using namespace geometry; diff --git a/wrap/tests/expected/new_Test_dM.m b/wrap/tests/expected/new_Test_dM.m index 826432b9f..c7009d6a9 100644 --- a/wrap/tests/expected/new_Test_dM.m +++ b/wrap/tests/expected/new_Test_dM.m @@ -1,4 +1,4 @@ -% automatically generated by wrap on 2012-Jan-15 +% automatically generated by wrap function result = new_Test_dM(obj,a,b) error('need to compile new_Test_dM.cpp'); end diff --git a/wrap/tests/expected_namespaces/@ClassD/ClassD.m b/wrap/tests/expected_namespaces/@ClassD/ClassD.m index d6b5b452a..52fbab1e7 100644 --- a/wrap/tests/expected_namespaces/@ClassD/ClassD.m +++ b/wrap/tests/expected_namespaces/@ClassD/ClassD.m @@ -1,10 +1,11 @@ +% automatically generated by wrap classdef ClassD properties self = 0 end methods function obj = ClassD(varargin) - if nargin == 0, obj.self = new_ClassD_(); end + if (nargin == 0), obj.self = new_ClassD_(); end if nargin ~= 13 && obj.self == 0, error('ClassD constructor failed'); end end function display(obj), obj.print(''); end diff --git a/wrap/tests/expected_namespaces/@ns1ClassA/ns1ClassA.m b/wrap/tests/expected_namespaces/@ns1ClassA/ns1ClassA.m index 1b05165b5..8d26fd069 100644 --- a/wrap/tests/expected_namespaces/@ns1ClassA/ns1ClassA.m +++ b/wrap/tests/expected_namespaces/@ns1ClassA/ns1ClassA.m @@ -1,3 +1,4 @@ +% automatically generated by wrap classdef ns1ClassA properties self = 0 diff --git a/wrap/tests/expected_namespaces/@ns1ClassB/ns1ClassB.m b/wrap/tests/expected_namespaces/@ns1ClassB/ns1ClassB.m index 78313677b..9a307e5d3 100644 --- a/wrap/tests/expected_namespaces/@ns1ClassB/ns1ClassB.m +++ b/wrap/tests/expected_namespaces/@ns1ClassB/ns1ClassB.m @@ -1,3 +1,4 @@ +% automatically generated by wrap classdef ns1ClassB properties self = 0 diff --git a/wrap/tests/expected_namespaces/@ns2ClassA/memberFunction.cpp b/wrap/tests/expected_namespaces/@ns2ClassA/memberFunction.cpp index 8a8112f99..8e5bc3960 100644 --- a/wrap/tests/expected_namespaces/@ns2ClassA/memberFunction.cpp +++ b/wrap/tests/expected_namespaces/@ns2ClassA/memberFunction.cpp @@ -1,4 +1,4 @@ -// automatically generated by wrap on 2011-Dec-15 +// automatically generated by wrap #include #include #include diff --git a/wrap/tests/expected_namespaces/@ns2ClassA/memberFunction.m b/wrap/tests/expected_namespaces/@ns2ClassA/memberFunction.m index 8e8d24bd7..4523cba56 100644 --- a/wrap/tests/expected_namespaces/@ns2ClassA/memberFunction.m +++ b/wrap/tests/expected_namespaces/@ns2ClassA/memberFunction.m @@ -1,3 +1,4 @@ + automatically generated by wrap function result = memberFunction(obj) % usage: obj.memberFunction() error('need to compile memberFunction.cpp'); diff --git a/wrap/tests/expected_namespaces/@ns2ClassA/ns2ClassA.m b/wrap/tests/expected_namespaces/@ns2ClassA/ns2ClassA.m index 2718d4cf1..1d3bc7577 100644 --- a/wrap/tests/expected_namespaces/@ns2ClassA/ns2ClassA.m +++ b/wrap/tests/expected_namespaces/@ns2ClassA/ns2ClassA.m @@ -1,3 +1,4 @@ +% automatically generated by wrap classdef ns2ClassA properties self = 0 diff --git a/wrap/tests/expected_namespaces/@ns2ClassA/nsArg.cpp b/wrap/tests/expected_namespaces/@ns2ClassA/nsArg.cpp index 9e9edcf78..7c06bcfdc 100644 --- a/wrap/tests/expected_namespaces/@ns2ClassA/nsArg.cpp +++ b/wrap/tests/expected_namespaces/@ns2ClassA/nsArg.cpp @@ -1,4 +1,4 @@ -// automatically generated by wrap on 2011-Dec-15 +// automatically generated by wrap #include #include #include diff --git a/wrap/tests/expected_namespaces/@ns2ClassA/nsArg.m b/wrap/tests/expected_namespaces/@ns2ClassA/nsArg.m index bdd4b387f..4893ece7f 100644 --- a/wrap/tests/expected_namespaces/@ns2ClassA/nsArg.m +++ b/wrap/tests/expected_namespaces/@ns2ClassA/nsArg.m @@ -1,3 +1,4 @@ + automatically generated by wrap function result = nsArg(obj,arg) % usage: obj.nsArg(arg) error('need to compile nsArg.cpp'); diff --git a/wrap/tests/expected_namespaces/@ns2ClassA/nsReturn.cpp b/wrap/tests/expected_namespaces/@ns2ClassA/nsReturn.cpp index b7a967e2c..c6714ee9f 100644 --- a/wrap/tests/expected_namespaces/@ns2ClassA/nsReturn.cpp +++ b/wrap/tests/expected_namespaces/@ns2ClassA/nsReturn.cpp @@ -1,4 +1,4 @@ -// automatically generated by wrap on 2011-Dec-15 +// automatically generated by wrap #include #include #include diff --git a/wrap/tests/expected_namespaces/@ns2ClassA/nsReturn.m b/wrap/tests/expected_namespaces/@ns2ClassA/nsReturn.m index d0d093a37..2c900bc30 100644 --- a/wrap/tests/expected_namespaces/@ns2ClassA/nsReturn.m +++ b/wrap/tests/expected_namespaces/@ns2ClassA/nsReturn.m @@ -1,3 +1,4 @@ + automatically generated by wrap function result = nsReturn(obj,q) % usage: obj.nsReturn(q) error('need to compile nsReturn.cpp'); diff --git a/wrap/tests/expected_namespaces/@ns2ClassC/ns2ClassC.m b/wrap/tests/expected_namespaces/@ns2ClassC/ns2ClassC.m index 039f5add3..be0d267e7 100644 --- a/wrap/tests/expected_namespaces/@ns2ClassC/ns2ClassC.m +++ b/wrap/tests/expected_namespaces/@ns2ClassC/ns2ClassC.m @@ -1,3 +1,4 @@ +% automatically generated by wrap classdef ns2ClassC properties self = 0 diff --git a/wrap/tests/expected_namespaces/@ns2ns3ClassB/ns2ns3ClassB.m b/wrap/tests/expected_namespaces/@ns2ns3ClassB/ns2ns3ClassB.m index 154c89d48..647a70772 100644 --- a/wrap/tests/expected_namespaces/@ns2ns3ClassB/ns2ns3ClassB.m +++ b/wrap/tests/expected_namespaces/@ns2ns3ClassB/ns2ns3ClassB.m @@ -1,3 +1,4 @@ +% automatically generated by wrap classdef ns2ns3ClassB properties self = 0 diff --git a/wrap/tests/expected_namespaces/Makefile b/wrap/tests/expected_namespaces/Makefile index 8a6bc3af7..dcc3b1dbd 100644 --- a/wrap/tests/expected_namespaces/Makefile +++ b/wrap/tests/expected_namespaces/Makefile @@ -1,4 +1,4 @@ -# automatically generated by wrap on 2011-Dec-15 +# automatically generated by wrap MEX = mex MEXENDING = mexa64 diff --git a/wrap/tests/expected_namespaces/make_testNamespaces.m b/wrap/tests/expected_namespaces/make_testNamespaces.m index 9a3ee5b6c..1dd743ffe 100644 --- a/wrap/tests/expected_namespaces/make_testNamespaces.m +++ b/wrap/tests/expected_namespaces/make_testNamespaces.m @@ -1,4 +1,4 @@ -% automatically generated by wrap on 2011-Dec-15 +% automatically generated by wrap echo on toolboxpath = mfilename('fullpath'); diff --git a/wrap/tests/expected_namespaces/new_ClassD_.cpp b/wrap/tests/expected_namespaces/new_ClassD_.cpp index c39f7c3fe..59ea4398b 100644 --- a/wrap/tests/expected_namespaces/new_ClassD_.cpp +++ b/wrap/tests/expected_namespaces/new_ClassD_.cpp @@ -1,4 +1,4 @@ -// automatically generated by wrap on 2011-Dec-15 +// automatically generated by wrap #include #include void mexFunction(int nargout, mxArray *out[], int nargin, const mxArray *in[]) diff --git a/wrap/tests/expected_namespaces/new_ClassD_.m b/wrap/tests/expected_namespaces/new_ClassD_.m index 99f139acf..abfd419f6 100644 --- a/wrap/tests/expected_namespaces/new_ClassD_.m +++ b/wrap/tests/expected_namespaces/new_ClassD_.m @@ -1,4 +1,4 @@ -% automatically generated by wrap on 2011-Dec-15 +% automatically generated by wrap function result = new_ClassD_(obj) error('need to compile new_ClassD_.cpp'); end diff --git a/wrap/tests/expected_namespaces/new_ns1ClassA_.cpp b/wrap/tests/expected_namespaces/new_ns1ClassA_.cpp index 84fbe45bf..cbb82eb70 100644 --- a/wrap/tests/expected_namespaces/new_ns1ClassA_.cpp +++ b/wrap/tests/expected_namespaces/new_ns1ClassA_.cpp @@ -1,4 +1,4 @@ -// automatically generated by wrap on 2011-Dec-15 +// automatically generated by wrap #include #include void mexFunction(int nargout, mxArray *out[], int nargin, const mxArray *in[]) diff --git a/wrap/tests/expected_namespaces/new_ns1ClassA_.m b/wrap/tests/expected_namespaces/new_ns1ClassA_.m index ab53c21a2..054aba2f0 100644 --- a/wrap/tests/expected_namespaces/new_ns1ClassA_.m +++ b/wrap/tests/expected_namespaces/new_ns1ClassA_.m @@ -1,4 +1,4 @@ -% automatically generated by wrap on 2011-Dec-15 +% automatically generated by wrap function result = new_ns1ClassA_(obj) error('need to compile new_ns1ClassA_.cpp'); end diff --git a/wrap/tests/expected_namespaces/new_ns1ClassB_.cpp b/wrap/tests/expected_namespaces/new_ns1ClassB_.cpp index 84670f1f1..d50cede19 100644 --- a/wrap/tests/expected_namespaces/new_ns1ClassB_.cpp +++ b/wrap/tests/expected_namespaces/new_ns1ClassB_.cpp @@ -1,4 +1,4 @@ -// automatically generated by wrap on 2011-Dec-15 +// automatically generated by wrap #include #include #include diff --git a/wrap/tests/expected_namespaces/new_ns1ClassB_.m b/wrap/tests/expected_namespaces/new_ns1ClassB_.m index 83f5daa6a..b92398a17 100644 --- a/wrap/tests/expected_namespaces/new_ns1ClassB_.m +++ b/wrap/tests/expected_namespaces/new_ns1ClassB_.m @@ -1,4 +1,4 @@ -% automatically generated by wrap on 2011-Dec-15 +% automatically generated by wrap function result = new_ns1ClassB_(obj) error('need to compile new_ns1ClassB_.cpp'); end diff --git a/wrap/tests/expected_namespaces/new_ns2ClassA_.cpp b/wrap/tests/expected_namespaces/new_ns2ClassA_.cpp index a70341f17..81bae3198 100644 --- a/wrap/tests/expected_namespaces/new_ns2ClassA_.cpp +++ b/wrap/tests/expected_namespaces/new_ns2ClassA_.cpp @@ -1,4 +1,4 @@ -// automatically generated by wrap on 2011-Dec-15 +// automatically generated by wrap #include #include #include diff --git a/wrap/tests/expected_namespaces/new_ns2ClassA_.m b/wrap/tests/expected_namespaces/new_ns2ClassA_.m index 171b839b9..88dedf719 100644 --- a/wrap/tests/expected_namespaces/new_ns2ClassA_.m +++ b/wrap/tests/expected_namespaces/new_ns2ClassA_.m @@ -1,4 +1,4 @@ -% automatically generated by wrap on 2011-Dec-15 +% automatically generated by wrap function result = new_ns2ClassA_(obj) error('need to compile new_ns2ClassA_.cpp'); end diff --git a/wrap/tests/expected_namespaces/new_ns2ClassC_.cpp b/wrap/tests/expected_namespaces/new_ns2ClassC_.cpp index 04d58a187..fbee07926 100644 --- a/wrap/tests/expected_namespaces/new_ns2ClassC_.cpp +++ b/wrap/tests/expected_namespaces/new_ns2ClassC_.cpp @@ -1,4 +1,4 @@ -// automatically generated by wrap on 2011-Dec-15 +// automatically generated by wrap #include #include void mexFunction(int nargout, mxArray *out[], int nargin, const mxArray *in[]) diff --git a/wrap/tests/expected_namespaces/new_ns2ClassC_.m b/wrap/tests/expected_namespaces/new_ns2ClassC_.m index 1858c3ada..b3f711e16 100644 --- a/wrap/tests/expected_namespaces/new_ns2ClassC_.m +++ b/wrap/tests/expected_namespaces/new_ns2ClassC_.m @@ -1,4 +1,4 @@ -% automatically generated by wrap on 2011-Dec-15 +% automatically generated by wrap function result = new_ns2ClassC_(obj) error('need to compile new_ns2ClassC_.cpp'); end diff --git a/wrap/tests/expected_namespaces/new_ns2ns3ClassB_.cpp b/wrap/tests/expected_namespaces/new_ns2ns3ClassB_.cpp index 38970edf9..ca9d02df3 100644 --- a/wrap/tests/expected_namespaces/new_ns2ns3ClassB_.cpp +++ b/wrap/tests/expected_namespaces/new_ns2ns3ClassB_.cpp @@ -1,4 +1,4 @@ -// automatically generated by wrap on 2011-Dec-15 +// automatically generated by wrap #include #include #include diff --git a/wrap/tests/expected_namespaces/new_ns2ns3ClassB_.m b/wrap/tests/expected_namespaces/new_ns2ns3ClassB_.m index 9842b55e8..2696c2498 100644 --- a/wrap/tests/expected_namespaces/new_ns2ns3ClassB_.m +++ b/wrap/tests/expected_namespaces/new_ns2ns3ClassB_.m @@ -1,4 +1,4 @@ -% automatically generated by wrap on 2011-Dec-15 +% automatically generated by wrap function result = new_ns2ns3ClassB_(obj) error('need to compile new_ns2ns3ClassB_.cpp'); end diff --git a/wrap/tests/expected_namespaces/ns2ClassA_afunction.cpp b/wrap/tests/expected_namespaces/ns2ClassA_afunction.cpp index 4ef71fcf4..72559acf8 100644 --- a/wrap/tests/expected_namespaces/ns2ClassA_afunction.cpp +++ b/wrap/tests/expected_namespaces/ns2ClassA_afunction.cpp @@ -1,4 +1,4 @@ -// automatically generated by wrap on 2011-Dec-15 +// automatically generated by wrap #include #include #include diff --git a/wrap/tests/expected_namespaces/ns2ClassA_afunction.m b/wrap/tests/expected_namespaces/ns2ClassA_afunction.m index 0482d1548..3a1101918 100644 --- a/wrap/tests/expected_namespaces/ns2ClassA_afunction.m +++ b/wrap/tests/expected_namespaces/ns2ClassA_afunction.m @@ -1,3 +1,4 @@ + automatically generated by wrap function result = ns2ClassA_afunction() % usage: x = ns2ClassA_afunction() error('need to compile ns2ClassA_afunction.cpp'); diff --git a/wrap/utilities.h b/wrap/utilities.h index ee7997645..384ff3749 100644 --- a/wrap/utilities.h +++ b/wrap/utilities.h @@ -75,7 +75,7 @@ std::string file_contents(const std::string& filename, bool skipheader=false); * Check whether two files are equal * By default, skips the first line of actual so header is not generated */ -bool files_equal(const std::string& expected, const std::string& actual, bool skipheader=true); +bool files_equal(const std::string& expected, const std::string& actual, bool skipheader=false); /** * Compare strings for unit tests From c323a052d5aec921e52ca349f7677e4ddf51e71c Mon Sep 17 00:00:00 2001 From: Chris Beall Date: Mon, 6 Feb 2012 23:57:07 +0000 Subject: [PATCH 12/18] doc typo --- gtsam/linear/JacobianFactor.h | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/gtsam/linear/JacobianFactor.h b/gtsam/linear/JacobianFactor.h index 079cb9292..ec661066d 100644 --- a/gtsam/linear/JacobianFactor.h +++ b/gtsam/linear/JacobianFactor.h @@ -289,7 +289,7 @@ namespace gtsam { private: - // Friend HessianFactor to facilitate convertion constructors + // Friend HessianFactor to facilitate conversion constructors friend class HessianFactor; // Friend unit tests (see also forward declarations above) From 282ac6484d535384bde91b5c29972c1b8d40de93 Mon Sep 17 00:00:00 2001 From: Frank Dellaert Date: Wed, 8 Feb 2012 15:23:11 +0000 Subject: [PATCH 13/18] "outputMetisFormat" outputs index in hmetis hypergraph format --- gtsam/inference/VariableIndex.cpp | 34 ++++++++++++++++++++++--------- gtsam/inference/VariableIndex.h | 6 ++++++ 2 files changed, 30 insertions(+), 10 deletions(-) diff --git a/gtsam/inference/VariableIndex.cpp b/gtsam/inference/VariableIndex.cpp index b44fa7f9a..32780c220 100644 --- a/gtsam/inference/VariableIndex.cpp +++ b/gtsam/inference/VariableIndex.cpp @@ -21,6 +21,8 @@ namespace gtsam { +using namespace std; + /* ************************************************************************* */ void VariableIndex::permute(const Permutation& permutation) { #ifndef NDEBUG @@ -36,7 +38,7 @@ void VariableIndex::permute(const Permutation& permutation) { /* ************************************************************************* */ bool VariableIndex::equals(const VariableIndex& other, double tol) const { if(this->nEntries_ == other.nEntries_ && this->nFactors_ == other.nFactors_) { - for(size_t var=0; var < std::max(this->index_.size(), other.index_.size()); ++var) + for(size_t var=0; var < max(this->index_.size(), other.index_.size()); ++var) if(var >= this->index_.size() || var >= other.index_.size()) { if(!((var >= this->index_.size() && other.index_[var].empty()) || (var >= other.index_.size() && this->index_[var].empty()))) @@ -49,21 +51,33 @@ bool VariableIndex::equals(const VariableIndex& other, double tol) const { } /* ************************************************************************* */ -void VariableIndex::print(const std::string& str) const { - std::cout << str << "\n"; - std::cout << "nEntries = " << this->nEntries_ << ", nFactors = " << this->nFactors_ << "\n"; +void VariableIndex::print(const string& str) const { + cout << str << "\n"; + cout << "nEntries = " << nEntries() << ", nFactors = " << nFactors() << "\n"; Index var = 0; BOOST_FOREACH(const Factors& variable, index_.container()) { Permutation::const_iterator rvar = find(index_.permutation().begin(), index_.permutation().end(), var); assert(rvar != index_.permutation().end()); - std::cout << "var " << (rvar-index_.permutation().begin()) << ":"; - BOOST_FOREACH(const size_t factor, variable) { - std::cout << " " << factor; - } - std::cout << "\n"; + cout << "var " << (rvar-index_.permutation().begin()) << ":"; + BOOST_FOREACH(const size_t factor, variable) + cout << " " << factor; + cout << "\n"; ++ var; } - std::cout << std::flush; + cout << flush; +} + +/* ************************************************************************* */ +void VariableIndex::outputMetisFormat(ostream& os) const { + os << size() << " " << nFactors() << "\n"; + // run over variables, which will be hyper-edges. + BOOST_FOREACH(const Factors& variable, index_.container()) { + // every variable is a hyper-edge covering its factors + BOOST_FOREACH(const size_t factor, variable) + os << (factor+1) << " "; // base 1 + os << "\n"; + } + os << flush; } } diff --git a/gtsam/inference/VariableIndex.h b/gtsam/inference/VariableIndex.h index 982bff247..fc4fde620 100644 --- a/gtsam/inference/VariableIndex.h +++ b/gtsam/inference/VariableIndex.h @@ -101,6 +101,12 @@ public: /** Print the variable index (for unit tests and debugging). */ void print(const std::string& str = "VariableIndex: ") const; + /** + * Output dual hypergraph to Metis file format for use with hmetis + * In the dual graph, variables are hyperedges, factors are nodes. + */ + void outputMetisFormat(std::ostream& os) const; + /// @} /// @name Advanced Interface From 2573383eca713cf4f918ea7500fbbc89fc978c90 Mon Sep 17 00:00:00 2001 From: Yong-Dian Jian Date: Tue, 14 Feb 2012 02:03:19 +0000 Subject: [PATCH 14/18] minor interface change --- gtsam/linear/IterativeSolver.h | 12 +++++------- 1 file changed, 5 insertions(+), 7 deletions(-) diff --git a/gtsam/linear/IterativeSolver.h b/gtsam/linear/IterativeSolver.h index 600c267ac..ec259b03c 100644 --- a/gtsam/linear/IterativeSolver.h +++ b/gtsam/linear/IterativeSolver.h @@ -30,7 +30,6 @@ class IterativeSolver { public: typedef IterativeOptimizationParameters Parameters; - typedef Parameters::shared_ptr sharedParameters; protected: @@ -40,21 +39,20 @@ public: IterativeSolver(): parameters_(new Parameters()) {} - IterativeSolver(const Parameters::shared_ptr& parameters) - : parameters_(parameters) {} - IterativeSolver(const IterativeSolver &solver) : parameters_(solver.parameters_) {} + IterativeSolver(const Parameters::shared_ptr& parameters) + : parameters_(parameters) {} + IterativeSolver(const Parameters ¶meters) : parameters_(new Parameters(parameters)) {} - IterativeSolver(const sharedParameters parameters) - : parameters_(parameters) {} - virtual ~IterativeSolver() {} virtual VectorValues::shared_ptr optimize () = 0; + + Parameters::shared_ptr parameters() { return parameters_ ; } }; } From 8b05fdb14fa12b196b331102d0b688c346891cc6 Mon Sep 17 00:00:00 2001 From: Yong-Dian Jian Date: Tue, 14 Feb 2012 04:08:43 +0000 Subject: [PATCH 15/18] minor update --- .../linear/IterativeOptimizationParameters.h | 112 +++++++----------- 1 file changed, 45 insertions(+), 67 deletions(-) diff --git a/gtsam/linear/IterativeOptimizationParameters.h b/gtsam/linear/IterativeOptimizationParameters.h index e779b7519..98b26e603 100644 --- a/gtsam/linear/IterativeOptimizationParameters.h +++ b/gtsam/linear/IterativeOptimizationParameters.h @@ -27,83 +27,61 @@ public: } verbosityLevel; public: - int maxIterations_; - int reset_; // number of iterations before reset, for cg and gmres - double epsilon_; // relative error + size_t minIterations_; + size_t maxIterations_; + size_t reset_; // number of iterations before reset, for cg and gmres + double epsilon_rel_; // relative error double epsilon_abs_; // absolute error verbosityLevel verbosity_; - size_t nReduce_ ; - boost::shared_ptr skeleton_spec_; bool est_cond_ ; public: - IterativeOptimizationParameters() : - maxIterations_(500), reset_(501), epsilon_(1e-3), epsilon_abs_(1e-3), - verbosity_(SILENT), nReduce_(0), skeleton_spec_(), est_cond_(false) { - } + IterativeOptimizationParameters() + : minIterations_(1), maxIterations_(500), reset_(501), + epsilon_rel_(1e-3), epsilon_abs_(1e-3), verbosity_(SILENT), est_cond_(false) {} IterativeOptimizationParameters( - const IterativeOptimizationParameters ¶meters) : - maxIterations_(parameters.maxIterations_), reset_(parameters.reset_), - epsilon_(parameters.epsilon_), epsilon_abs_(parameters.epsilon_abs_), - verbosity_(parameters.verbosity_), - nReduce_(parameters.nReduce_), - skeleton_spec_(parameters.skeleton_spec_), - est_cond_(parameters.est_cond_){ - } + const IterativeOptimizationParameters &p) : + minIterations_(p.minIterations_), maxIterations_(p.maxIterations_), reset_(p.reset_), + epsilon_rel_(p.epsilon_rel_), epsilon_abs_(p.epsilon_abs_), verbosity_(p.verbosity_), + est_cond_(p.est_cond_){ } - IterativeOptimizationParameters(int maxIterations, double epsilon, - double epsilon_abs, verbosityLevel verbosity = ERROR, int reset = -1, bool est_cond=false) : - maxIterations_(maxIterations), reset_(reset), epsilon_(epsilon), - epsilon_abs_(epsilon_abs), verbosity_(verbosity), - nReduce_(0), - skeleton_spec_(), - est_cond_(est_cond) { - if (reset_ == -1) - reset_ = maxIterations_ + 1; - } + IterativeOptimizationParameters(size_t minIterations, size_t maxIterations, size_t reset, + double epsilon, double epsilon_abs, verbosityLevel verbosity = ERROR, bool est_cond = false) : + minIterations_(minIterations), maxIterations_(maxIterations), reset_(reset), + epsilon_rel_(epsilon), epsilon_abs_(epsilon_abs), verbosity_(verbosity), est_cond_(est_cond) {} - int maxIterations() const { - return maxIterations_; - } - int reset() const { - return reset_; - } - double epsilon() const { - return epsilon_; - } - double epsilon_abs() const { - return epsilon_abs_; - } - verbosityLevel verbosity() const { - return verbosity_; - } - bool est_cond() const { - return est_cond_ ; - } + size_t minIterations() const { return minIterations_; } + size_t maxIterations() const { return maxIterations_; } + size_t reset() const { return reset_; } + double epsilon() const { return epsilon_rel_; } + double epsilon_rel() const { return epsilon_rel_; } + double epsilon_abs() const { return epsilon_abs_; } + verbosityLevel verbosity() const { return verbosity_; } + bool est_cond() const { return est_cond_ ; } }; -struct DimSpec: public std::vector { - - typedef std::vector Base; - typedef boost::shared_ptr shared_ptr; - - DimSpec() : - Base() { - } - DimSpec(size_t n) : - Base(n) { - } - DimSpec(size_t n, size_t init) : - Base(n, init) { - } - DimSpec(const VectorValues &V) : - Base(V.size()) { - const size_t n = V.size(); - for (size_t i = 0; i < n; ++i) { - (*this)[i] = V[i].rows(); - } - } -}; +//struct DimSpec: public std::vector { +// +// typedef std::vector Base; +// typedef boost::shared_ptr shared_ptr; +// +// DimSpec() : +// Base() { +// } +// DimSpec(size_t n) : +// Base(n) { +// } +// DimSpec(size_t n, size_t init) : +// Base(n, init) { +// } +// DimSpec(const VectorValues &V) : +// Base(V.size()) { +// const size_t n = V.size(); +// for (size_t i = 0; i < n; ++i) { +// (*this)[i] = V[i].rows(); +// } +// } +//}; } From 5d3e11e0c92cb6b05ac0ae0076c529d487af2a44 Mon Sep 17 00:00:00 2001 From: Yong-Dian Jian Date: Tue, 14 Feb 2012 18:18:28 +0000 Subject: [PATCH 16/18] in progress -- separate files to speed up compilation time... --- .../linear/IterativeOptimizationParameters.h | 30 ++----------------- 1 file changed, 3 insertions(+), 27 deletions(-) diff --git a/gtsam/linear/IterativeOptimizationParameters.h b/gtsam/linear/IterativeOptimizationParameters.h index 98b26e603..fa5c3a6ee 100644 --- a/gtsam/linear/IterativeOptimizationParameters.h +++ b/gtsam/linear/IterativeOptimizationParameters.h @@ -6,14 +6,12 @@ #pragma once -#include +#include +#include #include -#include namespace gtsam { -struct DimSpec; - // a container for all related parameters struct IterativeOptimizationParameters { @@ -34,6 +32,7 @@ public: double epsilon_abs_; // absolute error verbosityLevel verbosity_; bool est_cond_ ; + std::map sandbox_; public: IterativeOptimizationParameters() @@ -61,27 +60,4 @@ public: bool est_cond() const { return est_cond_ ; } }; -//struct DimSpec: public std::vector { -// -// typedef std::vector Base; -// typedef boost::shared_ptr shared_ptr; -// -// DimSpec() : -// Base() { -// } -// DimSpec(size_t n) : -// Base(n) { -// } -// DimSpec(size_t n, size_t init) : -// Base(n, init) { -// } -// DimSpec(const VectorValues &V) : -// Base(V.size()) { -// const size_t n = V.size(); -// for (size_t i = 0; i < n; ++i) { -// (*this)[i] = V[i].rows(); -// } -// } -//}; - } From d34375ab80d7b57f56db7c52bef9500756c4270a Mon Sep 17 00:00:00 2001 From: Yong-Dian Jian Date: Tue, 14 Feb 2012 23:22:21 +0000 Subject: [PATCH 17/18] remove all templates in CGSolvers to speedup compilation --- gtsam/linear/IterativeSolver.h | 2 ++ 1 file changed, 2 insertions(+) diff --git a/gtsam/linear/IterativeSolver.h b/gtsam/linear/IterativeSolver.h index ec259b03c..8de70bfdf 100644 --- a/gtsam/linear/IterativeSolver.h +++ b/gtsam/linear/IterativeSolver.h @@ -18,6 +18,7 @@ #pragma once +#include #include #include #include @@ -29,6 +30,7 @@ class IterativeSolver { public: + typedef boost::shared_ptr shared_ptr; typedef IterativeOptimizationParameters Parameters; protected: From b96b03a7331dc6756b3e6a26f5cb2dfd1c049515 Mon Sep 17 00:00:00 2001 From: Yong-Dian Jian Date: Wed, 15 Feb 2012 02:12:36 +0000 Subject: [PATCH 18/18] alternative timing report --- gtsam/base/timing.cpp | 41 +++++++++++++++++++++++++++++++++++++++++ gtsam/base/timing.h | 9 +++++++++ 2 files changed, 50 insertions(+) diff --git a/gtsam/base/timing.cpp b/gtsam/base/timing.cpp index 0942735ad..9e0bfdc28 100644 --- a/gtsam/base/timing.cpp +++ b/gtsam/base/timing.cpp @@ -16,8 +16,10 @@ * @date Oct 5, 2010 */ +#include #include #include +#include #include #include #include @@ -41,6 +43,7 @@ void TimingOutline::add(size_t usecs) { t_ += usecs; tIt_ += usecs; ++ n_; + history_.push_back(usecs); } /* ************************************************************************* */ @@ -83,6 +86,44 @@ void TimingOutline::print(const std::string& outline) const { } } +void TimingOutline::print2(const std::string& outline) const { + + const int w1 = 24, w2 = 3, w3 = 6, precision = 3; + const double selfTotal = double(t_)/(1000000.0), + selfMean = selfTotal/double(n_); + // const double childMean = double(time())/(1000000.0*n_); + + // compute standard deviation + double acc = 0.0; + BOOST_FOREACH(const size_t &t, history_) { + const double tmp = double(t)/1000000.0 - selfMean ; + acc += (tmp*tmp); + } + const double selfStd = sqrt(acc); + const std::string label = label_ + ": " ; + + if ( n_ == 0 ) { + std::cout << label << std::fixed << std::setprecision(precision) << double(time())/(1000000.0) << " seconds" << std::endl; + } + else { + std::cout << std::setw(w1) << label ; + std::cout << std::setiosflags(std::ios::right) << std::setw(w2) << n_ << " (times), " + << std::setiosflags(std::ios::right) << std::fixed << std::setw(w3) << std::setprecision(precision) << selfMean << " (mean), " + << std::setiosflags(std::ios::right) << std::fixed << std::setw(w3) << std::setprecision(precision) << selfStd << " (std)," + << std::setiosflags(std::ios::right) << std::fixed << std::setw(w3) << std::setprecision(precision) << selfTotal << " (total)" + //<< std::setprecision(precision) << std::setw(w3) << std::fixed << childMean << " (child-mean)" + << std::endl; + } + + for(size_t i=0; iprint2(childOutline); + } + } +} + /* ************************************************************************* */ const boost::shared_ptr& TimingOutline::child(size_t child, const std::string& label, const boost::weak_ptr& thisPtr) { assert(thisPtr.lock().get() == this); diff --git a/gtsam/base/timing.h b/gtsam/base/timing.h index baefae8e4..cd6624980 100644 --- a/gtsam/base/timing.h +++ b/gtsam/base/timing.h @@ -35,6 +35,7 @@ protected: size_t tMin_; size_t n_; std::string label_; + std::vector history_; boost::weak_ptr parent_; std::vector > children_; struct timeval t0_; @@ -50,6 +51,8 @@ public: void print(const std::string& outline = "") const; + void print2(const std::string& outline = "") const; + const boost::shared_ptr& child(size_t child, const std::string& label, const boost::weak_ptr& thisPtr); void tic(); @@ -168,11 +171,17 @@ inline void ticPush_(const std::string& prefix, const std::string& id) { tic_(id); } void ticPop_(const std::string& prefix, const std::string& id); + inline void tictoc_print_() { timing.print(); timingRoot->print(); } +/* print mean and standard deviation */ +inline void tictoc_print2_() { + timingRoot->print2(); +} + #ifdef ENABLE_TIMING inline double _tic() { return _tic_(); } inline double _toc(double t) { return _toc_(t); }