Merge commit '69c480490e0bc18ea897f1c96d8dd0bdc9b50fd5' into 2.0_prep (trunk r9251)

Conflicts:
	gtsam/linear/SubgraphSolver.h
	tests/Makefile.am
release/4.3a0
Richard Roberts 2012-02-15 23:43:25 +00:00
commit 5939ec2371
120 changed files with 709 additions and 609 deletions

24
gtsam.h
View File

@ -187,7 +187,6 @@ class Pose2 {
class Pose3 { class Pose3 {
Pose3(); Pose3();
Pose3(const gtsam::Rot3& r, const gtsam::Point3& t); Pose3(const gtsam::Rot3& r, const gtsam::Point3& t);
Pose3(Vector v);
Pose3(Matrix t); Pose3(Matrix t);
Pose3(const gtsam::Pose2& pose2); Pose3(const gtsam::Pose2& pose2);
static gtsam::Pose3 Expmap(Vector v); static gtsam::Pose3 Expmap(Vector v);
@ -203,10 +202,33 @@ class Pose3 {
gtsam::Pose3 between(const gtsam::Pose3& p2); gtsam::Pose3 between(const gtsam::Pose3& p2);
gtsam::Pose3 retract(Vector v); gtsam::Pose3 retract(Vector v);
gtsam::Pose3 retractFirstOrder(Vector v); gtsam::Pose3 retractFirstOrder(Vector v);
Vector localCoordinates(const gtsam::Pose3& T2) const;
gtsam::Point3 translation() const; gtsam::Point3 translation() const;
gtsam::Rot3 rotation() const; 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 // inference
//************************************************************************* //*************************************************************************

View File

@ -77,22 +77,33 @@ struct LieVector : public Vector, public DerivedValue<LieVector> {
return LieVector(); 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 */ /** compose with another object */
inline LieVector compose(const LieVector& p) const { inline LieVector compose(const LieVector& p,
boost::optional<gtsam::Matrix&> H1=boost::none,
boost::optional<gtsam::Matrix&> H2=boost::none) const {
if(H1) *H1 = eye(dim());
if(H2) *H2 = eye(p.dim());
return LieVector(vector() + p); return LieVector(vector() + p);
} }
/** between operation */ /** between operation */
inline LieVector between(const LieVector& l2, inline LieVector between(const LieVector& l2,
boost::optional<Matrix&> H1=boost::none, boost::optional<gtsam::Matrix&> H1=boost::none,
boost::optional<Matrix&> H2=boost::none) const { boost::optional<gtsam::Matrix&> H2=boost::none) const {
if(H1) *H1 = -eye(dim()); if(H1) *H1 = -eye(dim());
if(H2) *H2 = eye(l2.dim()); if(H2) *H2 = eye(l2.dim());
return LieVector(l2.vector() - vector()); return LieVector(l2.vector() - vector());
} }
/** invert the object and yield a new one */ /** invert the object and yield a new one */
inline LieVector inverse() const { inline LieVector inverse(boost::optional<gtsam::Matrix&> H=boost::none) const {
if(H) *H = -eye(dim());
return LieVector(-1.0 * vector()); return LieVector(-1.0 * vector());
} }

View File

@ -16,8 +16,10 @@
* @date Oct 5, 2010 * @date Oct 5, 2010
*/ */
#include <math.h>
#include <stdio.h> #include <stdio.h>
#include <iostream> #include <iostream>
#include <iomanip>
#include <sys/time.h> #include <sys/time.h>
#include <stdlib.h> #include <stdlib.h>
#include <boost/foreach.hpp> #include <boost/foreach.hpp>
@ -41,6 +43,7 @@ void TimingOutline::add(size_t usecs) {
t_ += usecs; t_ += usecs;
tIt_ += usecs; tIt_ += usecs;
++ n_; ++ 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; i<children_.size(); ++i) {
if(children_[i]) {
std::string childOutline(outline);
childOutline += " ";
children_[i]->print2(childOutline);
}
}
}
/* ************************************************************************* */ /* ************************************************************************* */
const boost::shared_ptr<TimingOutline>& TimingOutline::child(size_t child, const std::string& label, const boost::weak_ptr<TimingOutline>& thisPtr) { const boost::shared_ptr<TimingOutline>& TimingOutline::child(size_t child, const std::string& label, const boost::weak_ptr<TimingOutline>& thisPtr) {
assert(thisPtr.lock().get() == this); assert(thisPtr.lock().get() == this);

View File

@ -35,6 +35,7 @@ protected:
size_t tMin_; size_t tMin_;
size_t n_; size_t n_;
std::string label_; std::string label_;
std::vector<size_t> history_;
boost::weak_ptr<TimingOutline> parent_; boost::weak_ptr<TimingOutline> parent_;
std::vector<boost::shared_ptr<TimingOutline> > children_; std::vector<boost::shared_ptr<TimingOutline> > children_;
struct timeval t0_; struct timeval t0_;
@ -50,6 +51,8 @@ public:
void print(const std::string& outline = "") const; void print(const std::string& outline = "") const;
void print2(const std::string& outline = "") const;
const boost::shared_ptr<TimingOutline>& child(size_t child, const std::string& label, const boost::weak_ptr<TimingOutline>& thisPtr); const boost::shared_ptr<TimingOutline>& child(size_t child, const std::string& label, const boost::weak_ptr<TimingOutline>& thisPtr);
void tic(); void tic();
@ -168,11 +171,17 @@ inline void ticPush_(const std::string& prefix, const std::string& id) {
tic_(id); tic_(id);
} }
void ticPop_(const std::string& prefix, const std::string& id); void ticPop_(const std::string& prefix, const std::string& id);
inline void tictoc_print_() { inline void tictoc_print_() {
timing.print(); timing.print();
timingRoot->print(); timingRoot->print();
} }
/* print mean and standard deviation */
inline void tictoc_print2_() {
timingRoot->print2();
}
#ifdef ENABLE_TIMING #ifdef ENABLE_TIMING
inline double _tic() { return _tic_(); } inline double _tic() { return _tic_(); }
inline double _toc(double t) { return _toc_(t); } inline double _toc(double t) { return _toc_(t); }

View File

@ -138,6 +138,9 @@ template<class CONDITIONAL, class CLIQUE> class BayesTree;
/** return the number of factors and NULLS */ /** return the number of factors and NULLS */
size_t size() const { return factors_.size();} 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 */ /** const cast to the underlying vector of factors */
operator const std::vector<sharedFactor>&() const { return factors_; } operator const std::vector<sharedFactor>&() const { return factors_; }

View File

@ -21,6 +21,8 @@
namespace gtsam { namespace gtsam {
using namespace std;
/* ************************************************************************* */ /* ************************************************************************* */
void VariableIndex::permute(const Permutation& permutation) { void VariableIndex::permute(const Permutation& permutation) {
#ifndef NDEBUG #ifndef NDEBUG
@ -36,7 +38,7 @@ void VariableIndex::permute(const Permutation& permutation) {
/* ************************************************************************* */ /* ************************************************************************* */
bool VariableIndex::equals(const VariableIndex& other, double tol) const { bool VariableIndex::equals(const VariableIndex& other, double tol) const {
if(this->nEntries_ == other.nEntries_ && this->nFactors_ == other.nFactors_) { 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() || var >= other.index_.size()) {
if(!((var >= this->index_.size() && other.index_[var].empty()) || if(!((var >= this->index_.size() && other.index_[var].empty()) ||
(var >= other.index_.size() && this->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 { void VariableIndex::print(const string& str) const {
std::cout << str << "\n"; cout << str << "\n";
std::cout << "nEntries = " << this->nEntries_ << ", nFactors = " << this->nFactors_ << "\n"; cout << "nEntries = " << nEntries() << ", nFactors = " << nFactors() << "\n";
Index var = 0; Index var = 0;
BOOST_FOREACH(const Factors& variable, index_.container()) { BOOST_FOREACH(const Factors& variable, index_.container()) {
Permutation::const_iterator rvar = find(index_.permutation().begin(), index_.permutation().end(), var); Permutation::const_iterator rvar = find(index_.permutation().begin(), index_.permutation().end(), var);
assert(rvar != index_.permutation().end()); assert(rvar != index_.permutation().end());
std::cout << "var " << (rvar-index_.permutation().begin()) << ":"; cout << "var " << (rvar-index_.permutation().begin()) << ":";
BOOST_FOREACH(const size_t factor, variable) { BOOST_FOREACH(const size_t factor, variable)
std::cout << " " << factor; cout << " " << factor;
} cout << "\n";
std::cout << "\n";
++ var; ++ 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;
} }
} }

View File

@ -101,6 +101,12 @@ public:
/** Print the variable index (for unit tests and debugging). */ /** Print the variable index (for unit tests and debugging). */
void print(const std::string& str = "VariableIndex: ") const; 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 /// @name Advanced Interface

View File

@ -6,14 +6,12 @@
#pragma once #pragma once
#include <vector> #include <string>
#include <map>
#include <boost/shared_ptr.hpp> #include <boost/shared_ptr.hpp>
#include <gtsam/linear/VectorValues.h>
namespace gtsam { namespace gtsam {
struct DimSpec;
// a container for all related parameters // a container for all related parameters
struct IterativeOptimizationParameters { struct IterativeOptimizationParameters {
@ -27,83 +25,39 @@ public:
} verbosityLevel; } verbosityLevel;
public: public:
int maxIterations_; size_t minIterations_;
int reset_; // number of iterations before reset, for cg and gmres size_t maxIterations_;
double epsilon_; // relative error size_t reset_; // number of iterations before reset, for cg and gmres
double epsilon_rel_; // relative error
double epsilon_abs_; // absolute error double epsilon_abs_; // absolute error
verbosityLevel verbosity_; verbosityLevel verbosity_;
size_t nReduce_ ;
boost::shared_ptr<DimSpec> skeleton_spec_;
bool est_cond_ ; bool est_cond_ ;
std::map<std::string, std::string> sandbox_;
public: public:
IterativeOptimizationParameters() : IterativeOptimizationParameters()
maxIterations_(100), reset_(101), epsilon_(1e-5), epsilon_abs_(1e-5), : minIterations_(1), maxIterations_(500), reset_(501),
verbosity_(SILENT), nReduce_(0), skeleton_spec_(), est_cond_(false) { epsilon_rel_(1e-3), epsilon_abs_(1e-3), verbosity_(SILENT), est_cond_(false) {}
}
IterativeOptimizationParameters( IterativeOptimizationParameters(
const IterativeOptimizationParameters &parameters) : const IterativeOptimizationParameters &p) :
maxIterations_(parameters.maxIterations_), reset_(parameters.reset_), minIterations_(p.minIterations_), maxIterations_(p.maxIterations_), reset_(p.reset_),
epsilon_(parameters.epsilon_), epsilon_abs_(parameters.epsilon_abs_), epsilon_rel_(p.epsilon_rel_), epsilon_abs_(p.epsilon_abs_), verbosity_(p.verbosity_),
verbosity_(parameters.verbosity_), est_cond_(p.est_cond_){ }
nReduce_(parameters.nReduce_),
skeleton_spec_(parameters.skeleton_spec_),
est_cond_(parameters.est_cond_){
}
IterativeOptimizationParameters(int maxIterations, double epsilon, IterativeOptimizationParameters(size_t minIterations, size_t maxIterations, size_t reset,
double epsilon_abs, verbosityLevel verbosity = ERROR, int reset = -1, bool est_cond=false) : double epsilon, double epsilon_abs, verbosityLevel verbosity = ERROR, bool est_cond = false) :
maxIterations_(maxIterations), reset_(reset), epsilon_(epsilon), minIterations_(minIterations), maxIterations_(maxIterations), reset_(reset),
epsilon_abs_(epsilon_abs), verbosity_(verbosity), epsilon_rel_(epsilon), epsilon_abs_(epsilon_abs), verbosity_(verbosity), est_cond_(est_cond) {}
nReduce_(0),
skeleton_spec_(),
est_cond_(est_cond) {
if (reset_ == -1)
reset_ = maxIterations_ + 1;
}
int maxIterations() const { size_t minIterations() const { return minIterations_; }
return maxIterations_; size_t maxIterations() const { return maxIterations_; }
} size_t reset() const { return reset_; }
int reset() const { double epsilon() const { return epsilon_rel_; }
return reset_; double epsilon_rel() const { return epsilon_rel_; }
} double epsilon_abs() const { return epsilon_abs_; }
double epsilon() const { verbosityLevel verbosity() const { return verbosity_; }
return epsilon_; bool est_cond() const { return est_cond_ ; }
}
double epsilon_abs() const {
return epsilon_abs_;
}
verbosityLevel verbosity() const {
return verbosity_;
}
bool est_cond() const {
return est_cond_ ;
}
};
struct DimSpec: public std::vector<size_t> {
typedef std::vector<size_t> Base;
typedef boost::shared_ptr<DimSpec> 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();
}
}
}; };
} }

View File

@ -18,6 +18,7 @@
#pragma once #pragma once
#include <boost/shared_ptr.hpp>
#include <gtsam/linear/GaussianFactorGraph.h> #include <gtsam/linear/GaussianFactorGraph.h>
#include <gtsam/inference/VariableIndex.h> #include <gtsam/inference/VariableIndex.h>
#include <gtsam/linear/VectorValues.h> #include <gtsam/linear/VectorValues.h>
@ -29,44 +30,31 @@ class IterativeSolver {
public: public:
typedef boost::shared_ptr<IterativeSolver> shared_ptr;
typedef IterativeOptimizationParameters Parameters; typedef IterativeOptimizationParameters Parameters;
typedef Parameters::shared_ptr sharedParameters;
protected: protected:
GaussianFactorGraph::shared_ptr graph_;
VariableIndex::shared_ptr variableIndex_;
Parameters::shared_ptr parameters_ ; Parameters::shared_ptr parameters_ ;
public: public:
IterativeSolver( IterativeSolver(): parameters_(new Parameters()) {}
const GaussianFactorGraph::shared_ptr& factorGraph,
const VariableIndex::shared_ptr& variableIndex):
graph_(factorGraph), variableIndex_(variableIndex),
parameters_(new Parameters()) { }
IterativeSolver( IterativeSolver(const IterativeSolver &solver)
const GaussianFactorGraph::shared_ptr& factorGraph, : parameters_(solver.parameters_) {}
const VariableIndex::shared_ptr& variableIndex,
const Parameters::shared_ptr& parameters):
graph_(factorGraph), variableIndex_(variableIndex), parameters_(parameters) { }
IterativeSolver(): IterativeSolver(const Parameters::shared_ptr& parameters)
parameters_(new IterativeOptimizationParameters()) {} : parameters_(parameters) {}
IterativeSolver(const IterativeSolver &solver): IterativeSolver(const Parameters &parameters)
parameters_(solver.parameters_) {} : parameters_(new Parameters(parameters)) {}
IterativeSolver(const IterativeOptimizationParameters &parameters):
parameters_(new IterativeOptimizationParameters(parameters)) {}
IterativeSolver(const sharedParameters parameters):
parameters_(parameters) {}
virtual ~IterativeSolver() {} virtual ~IterativeSolver() {}
virtual VectorValues::shared_ptr optimize () = 0; virtual VectorValues::shared_ptr optimize () = 0;
Parameters::shared_ptr parameters() { return parameters_ ; }
}; };
} }

View File

@ -289,7 +289,7 @@ namespace gtsam {
private: private:
// Friend HessianFactor to facilitate convertion constructors // Friend HessianFactor to facilitate conversion constructors
friend class HessianFactor; friend class HessianFactor;
// Friend unit tests (see also forward declarations above) // Friend unit tests (see also forward declarations above)

View File

@ -1,150 +1,150 @@
/* ---------------------------------------------------------------------------- ///* ----------------------------------------------------------------------------
//
* GTSAM Copyright 2010, Georgia Tech Research Corporation, // * GTSAM Copyright 2010, Georgia Tech Research Corporation,
* Atlanta, Georgia 30332-0415 // * Atlanta, Georgia 30332-0415
* All Rights Reserved // * All Rights Reserved
* Authors: Frank Dellaert, et al. (see THANKS for the full author list) // * Authors: Frank Dellaert, et al. (see THANKS for the full author list)
//
* See LICENSE for the license information // * See LICENSE for the license information
//
* -------------------------------------------------------------------------- */ // * -------------------------------------------------------------------------- */
//
/** ///**
* @file SubgraphPreconditioner.cpp // * @file SubgraphPreconditioner.cpp
* @date Dec 31, 2009 // * @date Dec 31, 2009
* @author: Frank Dellaert // * @author: Frank Dellaert
*/ // */
//
#include <boost/foreach.hpp> //#include <boost/foreach.hpp>
#include <gtsam/linear/SubgraphPreconditioner.h> //#include <gtsam/linear/SubgraphPreconditioner.h>
#include <gtsam/linear/JacobianFactor.h> //#include <gtsam/linear/JacobianFactor.h>
#include <gtsam/linear/GaussianFactorGraph.h> //#include <gtsam/linear/GaussianFactorGraph.h>
//
using namespace std; //using namespace std;
//
namespace gtsam { //namespace gtsam {
//
/* ************************************************************************* */ // /* ************************************************************************* */
SubgraphPreconditioner::SubgraphPreconditioner(const sharedFG& Ab1, const sharedFG& Ab2, // SubgraphPreconditioner::SubgraphPreconditioner(const sharedFG& Ab1, const sharedFG& Ab2,
const sharedBayesNet& Rc1, const sharedValues& xbar) : // const sharedBayesNet& Rc1, const sharedValues& xbar) :
Ab1_(Ab1), Ab2_(Ab2), Rc1_(Rc1), xbar_(xbar), b2bar_(gaussianErrors_(*Ab2_,*xbar)) { // Ab1_(Ab1), Ab2_(Ab2), Rc1_(Rc1), xbar_(xbar), b2bar_(gaussianErrors_(*Ab2_,*xbar)) {
} // }
//
/* ************************************************************************* */ // /* ************************************************************************* */
// x = xbar + inv(R1)*y // // x = xbar + inv(R1)*y
VectorValues SubgraphPreconditioner::x(const VectorValues& y) const { // VectorValues SubgraphPreconditioner::x(const VectorValues& y) const {
#ifdef VECTORBTREE //#ifdef VECTORBTREE
if (!y.cloned(*xbar_)) throw // if (!y.cloned(*xbar_)) throw
invalid_argument("SubgraphPreconditioner::x: y needs to be cloned from xbar"); // invalid_argument("SubgraphPreconditioner::x: y needs to be cloned from xbar");
#endif //#endif
VectorValues x = y; // VectorValues x = y;
backSubstituteInPlace(*Rc1_,x); // backSubstituteInPlace(*Rc1_,x);
x += *xbar_; // x += *xbar_;
return x; // return x;
} // }
//
// SubgraphPreconditioner SubgraphPreconditioner::add_priors(double sigma) const { //// SubgraphPreconditioner SubgraphPreconditioner::add_priors(double sigma) const {
// SubgraphPreconditioner result = *this ; //// SubgraphPreconditioner result = *this ;
// result.Ab2_ = sharedFG(new GaussianFactorGraph(Ab2_->add_priors(sigma))) ; //// result.Ab2_ = sharedFG(new GaussianFactorGraph(Ab2_->add_priors(sigma))) ;
// return result ; //// return result ;
// } //// }
//
/* ************************************************************************* */ // /* ************************************************************************* */
double error(const SubgraphPreconditioner& sp, const VectorValues& y) { // double error(const SubgraphPreconditioner& sp, const VectorValues& y) {
//
Errors e(y); // Errors e(y);
VectorValues x = sp.x(y); // VectorValues x = sp.x(y);
Errors e2 = gaussianErrors(*sp.Ab2(),x); // Errors e2 = gaussianErrors(*sp.Ab2(),x);
return 0.5 * (dot(e, e) + dot(e2,e2)); // return 0.5 * (dot(e, e) + dot(e2,e2));
} // }
//
/* ************************************************************************* */ // /* ************************************************************************* */
// gradient is y + inv(R1')*A2'*(A2*inv(R1)*y-b2bar), // // gradient is y + inv(R1')*A2'*(A2*inv(R1)*y-b2bar),
VectorValues gradient(const SubgraphPreconditioner& sp, const VectorValues& y) { // VectorValues gradient(const SubgraphPreconditioner& sp, const VectorValues& y) {
VectorValues x = sp.x(y); // x = inv(R1)*y // VectorValues x = sp.x(y); // x = inv(R1)*y
Errors e2 = gaussianErrors(*sp.Ab2(),x); // Errors e2 = gaussianErrors(*sp.Ab2(),x);
VectorValues gx2 = VectorValues::Zero(y); // VectorValues gx2 = VectorValues::Zero(y);
gtsam::transposeMultiplyAdd(*sp.Ab2(),1.0,e2,gx2); // A2'*e2; // gtsam::transposeMultiplyAdd(*sp.Ab2(),1.0,e2,gx2); // A2'*e2;
VectorValues gy2 = gtsam::backSubstituteTranspose(*sp.Rc1(), gx2); // inv(R1')*gx2 // VectorValues gy2 = gtsam::backSubstituteTranspose(*sp.Rc1(), gx2); // inv(R1')*gx2
return y + gy2; // return y + gy2;
} // }
//
/* ************************************************************************* */ // /* ************************************************************************* */
// Apply operator A, A*y = [I;A2*inv(R1)]*y = [y; A2*inv(R1)*y] // // Apply operator A, A*y = [I;A2*inv(R1)]*y = [y; A2*inv(R1)*y]
Errors operator*(const SubgraphPreconditioner& sp, const VectorValues& y) { // Errors operator*(const SubgraphPreconditioner& sp, const VectorValues& y) {
//
Errors e(y); // Errors e(y);
//
// Add A2 contribution // // Add A2 contribution
VectorValues x = y; // TODO avoid ? // VectorValues x = y; // TODO avoid ?
gtsam::backSubstituteInPlace(*sp.Rc1(), x); // x=inv(R1)*y // gtsam::backSubstituteInPlace(*sp.Rc1(), x); // x=inv(R1)*y
Errors e2 = *sp.Ab2() * x; // A2*x // Errors e2 = *sp.Ab2() * x; // A2*x
e.splice(e.end(), e2); // e.splice(e.end(), e2);
//
return e; // return e;
} // }
//
/* ************************************************************************* */ // /* ************************************************************************* */
// In-place version that overwrites e // // In-place version that overwrites e
void multiplyInPlace(const SubgraphPreconditioner& sp, const VectorValues& y, Errors& e) { // void multiplyInPlace(const SubgraphPreconditioner& sp, const VectorValues& y, Errors& e) {
//
//
Errors::iterator ei = e.begin(); // Errors::iterator ei = e.begin();
for ( Index i = 0 ; i < y.size() ; ++i, ++ei ) { // for ( Index i = 0 ; i < y.size() ; ++i, ++ei ) {
*ei = y[i]; // *ei = y[i];
} // }
//
// Add A2 contribution // // Add A2 contribution
VectorValues x = y; // TODO avoid ? // VectorValues x = y; // TODO avoid ?
gtsam::backSubstituteInPlace(*sp.Rc1(), x); // x=inv(R1)*y // gtsam::backSubstituteInPlace(*sp.Rc1(), x); // x=inv(R1)*y
gtsam::multiplyInPlace(*sp.Ab2(),x,ei); // use iterator version // gtsam::multiplyInPlace(*sp.Ab2(),x,ei); // use iterator version
} // }
//
/* ************************************************************************* */ // /* ************************************************************************* */
// Apply operator A', A'*e = [I inv(R1')*A2']*e = e1 + inv(R1')*A2'*e2 // // Apply operator A', A'*e = [I inv(R1')*A2']*e = e1 + inv(R1')*A2'*e2
VectorValues operator^(const SubgraphPreconditioner& sp, const Errors& e) { // VectorValues operator^(const SubgraphPreconditioner& sp, const Errors& e) {
//
Errors::const_iterator it = e.begin(); // Errors::const_iterator it = e.begin();
VectorValues y = sp.zero(); // VectorValues y = sp.zero();
for ( Index i = 0 ; i < y.size() ; ++i, ++it ) // for ( Index i = 0 ; i < y.size() ; ++i, ++it )
y[i] = *it ; // y[i] = *it ;
sp.transposeMultiplyAdd2(1.0,it,e.end(),y); // sp.transposeMultiplyAdd2(1.0,it,e.end(),y);
return y; // return y;
} // }
//
/* ************************************************************************* */ // /* ************************************************************************* */
// y += alpha*A'*e // // y += alpha*A'*e
void transposeMultiplyAdd // void transposeMultiplyAdd
(const SubgraphPreconditioner& sp, double alpha, const Errors& e, VectorValues& y) { // (const SubgraphPreconditioner& sp, double alpha, const Errors& e, VectorValues& y) {
//
//
Errors::const_iterator it = e.begin(); // Errors::const_iterator it = e.begin();
for ( Index i = 0 ; i < y.size() ; ++i, ++it ) { // for ( Index i = 0 ; i < y.size() ; ++i, ++it ) {
const Vector& ei = *it; // const Vector& ei = *it;
axpy(alpha,ei,y[i]); // axpy(alpha,ei,y[i]);
} // }
sp.transposeMultiplyAdd2(alpha,it,e.end(),y); // sp.transposeMultiplyAdd2(alpha,it,e.end(),y);
} // }
//
/* ************************************************************************* */ // /* ************************************************************************* */
// y += alpha*inv(R1')*A2'*e2 // // y += alpha*inv(R1')*A2'*e2
void SubgraphPreconditioner::transposeMultiplyAdd2 (double alpha, // void SubgraphPreconditioner::transposeMultiplyAdd2 (double alpha,
Errors::const_iterator it, Errors::const_iterator end, VectorValues& y) const { // Errors::const_iterator it, Errors::const_iterator end, VectorValues& y) const {
//
// create e2 with what's left of e // // create e2 with what's left of e
// TODO can we avoid creating e2 by passing iterator to transposeMultiplyAdd ? // // TODO can we avoid creating e2 by passing iterator to transposeMultiplyAdd ?
Errors e2; // Errors e2;
while (it != end) // while (it != end)
e2.push_back(*(it++)); // e2.push_back(*(it++));
//
VectorValues x = VectorValues::Zero(y); // x = 0 // VectorValues x = VectorValues::Zero(y); // x = 0
gtsam::transposeMultiplyAdd(*Ab2_,1.0,e2,x); // x += A2'*e2 // gtsam::transposeMultiplyAdd(*Ab2_,1.0,e2,x); // x += A2'*e2
axpy(alpha, gtsam::backSubstituteTranspose(*Rc1_, x), y); // y += alpha*inv(R1')*x // axpy(alpha, gtsam::backSubstituteTranspose(*Rc1_, x), y); // y += alpha*inv(R1')*x
} // }
//
/* ************************************************************************* */ // /* ************************************************************************* */
void SubgraphPreconditioner::print(const std::string& s) const { // void SubgraphPreconditioner::print(const std::string& s) const {
cout << s << endl; // cout << s << endl;
Ab2_->print(); // Ab2_->print();
} // }
} // nsamespace gtsam //} // nsamespace gtsam

View File

@ -1,116 +1,116 @@
/* ---------------------------------------------------------------------------- ///* ----------------------------------------------------------------------------
//
* GTSAM Copyright 2010, Georgia Tech Research Corporation, // * GTSAM Copyright 2010, Georgia Tech Research Corporation,
* Atlanta, Georgia 30332-0415 // * Atlanta, Georgia 30332-0415
* All Rights Reserved // * All Rights Reserved
* Authors: Frank Dellaert, et al. (see THANKS for the full author list) // * Authors: Frank Dellaert, et al. (see THANKS for the full author list)
//
* See LICENSE for the license information // * See LICENSE for the license information
//
* -------------------------------------------------------------------------- */ // * -------------------------------------------------------------------------- */
//
/** ///**
* @file SubgraphPreconditioner.h // * @file SubgraphPreconditioner.h
* @date Dec 31, 2009 // * @date Dec 31, 2009
* @author Frank Dellaert // * @author Frank Dellaert
*/ // */
//
#pragma once //#pragma once
//
#include <gtsam/linear/JacobianFactor.h> //#include <gtsam/linear/JacobianFactor.h>
#include <gtsam/linear/GaussianBayesNet.h> //#include <gtsam/linear/GaussianBayesNet.h>
#include <gtsam/nonlinear/Ordering.h> // FIXME shouldn't have nonlinear things in linear //#include <gtsam/nonlinear/Ordering.h> // FIXME shouldn't have nonlinear things in linear
//
namespace gtsam { //namespace gtsam {
//
/** // /**
* Subgraph conditioner class, as explained in the RSS 2010 submission. // * 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 // * 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. // * 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. // * 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). // * Then solve for yhat using CG, and solve for xhat = system.x(yhat).
*/ // */
class SubgraphPreconditioner { // class SubgraphPreconditioner {
//
public: // public:
typedef boost::shared_ptr<const GaussianBayesNet> sharedBayesNet; // typedef boost::shared_ptr<const GaussianBayesNet> sharedBayesNet;
typedef boost::shared_ptr<const FactorGraph<JacobianFactor> > sharedFG; // typedef boost::shared_ptr<const FactorGraph<JacobianFactor> > sharedFG;
typedef boost::shared_ptr<const VectorValues> sharedValues; // typedef boost::shared_ptr<const VectorValues> sharedValues;
typedef boost::shared_ptr<const Errors> sharedErrors; // typedef boost::shared_ptr<const Errors> sharedErrors;
//
private: // private:
sharedFG Ab1_, Ab2_; // sharedFG Ab1_, Ab2_;
sharedBayesNet Rc1_; // sharedBayesNet Rc1_;
sharedValues xbar_; // sharedValues xbar_;
sharedErrors b2bar_; /** b2 - A2*xbar */ // sharedErrors b2bar_; /** b2 - A2*xbar */
//
public: // public:
//
SubgraphPreconditioner(); // SubgraphPreconditioner();
/** // /**
* Constructor // * Constructor
* @param Ab1: the Graph A1*x=b1 // * @param Ab1: the Graph A1*x=b1
* @param Ab2: the Graph A2*x=b2 // * @param Ab2: the Graph A2*x=b2
* @param Rc1: the Bayes Net R1*x=c1 // * @param Rc1: the Bayes Net R1*x=c1
* @param xbar: the solution to R1*x=c1 // * @param xbar: the solution to R1*x=c1
*/ // */
SubgraphPreconditioner(const sharedFG& Ab1, const sharedFG& Ab2, const sharedBayesNet& Rc1, const sharedValues& xbar); // SubgraphPreconditioner(const sharedFG& Ab1, const sharedFG& Ab2, const sharedBayesNet& Rc1, const sharedValues& xbar);
//
/** Access Ab1 */ // /** Access Ab1 */
const sharedFG& Ab1() const { return Ab1_; } // const sharedFG& Ab1() const { return Ab1_; }
//
/** Access Ab2 */ // /** Access Ab2 */
const sharedFG& Ab2() const { return Ab2_; } // const sharedFG& Ab2() const { return Ab2_; }
//
/** Access Rc1 */ // /** Access Rc1 */
const sharedBayesNet& Rc1() const { return Rc1_; } // const sharedBayesNet& Rc1() const { return Rc1_; }
//
/** // /**
* Add zero-mean i.i.d. Gaussian prior terms to each variable // * Add zero-mean i.i.d. Gaussian prior terms to each variable
* @param sigma Standard deviation of Gaussian // * @param sigma Standard deviation of Gaussian
*/ // */
// SubgraphPreconditioner add_priors(double sigma) const; //// SubgraphPreconditioner add_priors(double sigma) const;
//
/* x = xbar + inv(R1)*y */ // /* x = xbar + inv(R1)*y */
VectorValues x(const VectorValues& y) const; // VectorValues x(const VectorValues& y) const;
//
/* A zero VectorValues with the structure of xbar */ // /* A zero VectorValues with the structure of xbar */
VectorValues zero() const { // VectorValues zero() const {
VectorValues V(VectorValues::Zero(*xbar_)) ; // VectorValues V(VectorValues::Zero(*xbar_)) ;
return V ; // return V ;
} // }
//
/** // /**
* Add constraint part of the error only, used in both calls above // * Add constraint part of the error only, used in both calls above
* y += alpha*inv(R1')*A2'*e2 // * y += alpha*inv(R1')*A2'*e2
* Takes a range indicating e2 !!!! // * Takes a range indicating e2 !!!!
*/ // */
void transposeMultiplyAdd2(double alpha, Errors::const_iterator begin, // void transposeMultiplyAdd2(double alpha, Errors::const_iterator begin,
Errors::const_iterator end, VectorValues& y) const; // Errors::const_iterator end, VectorValues& y) const;
//
/** print the object */ // /** print the object */
void print(const std::string& s = "SubgraphPreconditioner") const; // void print(const std::string& s = "SubgraphPreconditioner") const;
}; // };
//
/* error, given y */ // /* error, given y */
double error(const SubgraphPreconditioner& sp, const VectorValues& y); // double error(const SubgraphPreconditioner& sp, const VectorValues& y);
//
/** gradient = y + inv(R1')*A2'*(A2*inv(R1)*y-b2bar) */ // /** gradient = y + inv(R1')*A2'*(A2*inv(R1)*y-b2bar) */
VectorValues gradient(const SubgraphPreconditioner& sp, const VectorValues& y); // VectorValues gradient(const SubgraphPreconditioner& sp, const VectorValues& y);
//
/** Apply operator A */ // /** Apply operator A */
Errors operator*(const SubgraphPreconditioner& sp, const VectorValues& y); // Errors operator*(const SubgraphPreconditioner& sp, const VectorValues& y);
//
/** Apply operator A in place: needs e allocated already */ // /** Apply operator A in place: needs e allocated already */
void multiplyInPlace(const SubgraphPreconditioner& sp, const VectorValues& y, Errors& e); // void multiplyInPlace(const SubgraphPreconditioner& sp, const VectorValues& y, Errors& e);
//
/** Apply operator A' */ // /** Apply operator A' */
VectorValues operator^(const SubgraphPreconditioner& sp, const Errors& e); // VectorValues operator^(const SubgraphPreconditioner& sp, const Errors& e);
//
/** // /**
* Add A'*e to y // * Add A'*e to y
* y += alpha*A'*[e1;e2] = [alpha*e1; alpha*inv(R1')*A2'*e2] // * y += alpha*A'*[e1;e2] = [alpha*e1; alpha*inv(R1')*A2'*e2]
*/ // */
void transposeMultiplyAdd(const SubgraphPreconditioner& sp, double alpha, const Errors& e, VectorValues& y); // void transposeMultiplyAdd(const SubgraphPreconditioner& sp, double alpha, const Errors& e, VectorValues& y);
//
} // namespace gtsam //} // namespace gtsam

View File

@ -1,50 +1,50 @@
/* ---------------------------------------------------------------------------- ///* ----------------------------------------------------------------------------
//
* GTSAM Copyright 2010, Georgia Tech Research Corporation, // * GTSAM Copyright 2010, Georgia Tech Research Corporation,
* Atlanta, Georgia 30332-0415 // * Atlanta, Georgia 30332-0415
* All Rights Reserved // * All Rights Reserved
* Authors: Frank Dellaert, et al. (see THANKS for the full author list) // * Authors: Frank Dellaert, et al. (see THANKS for the full author list)
//
* See LICENSE for the license information // * See LICENSE for the license information
//
* -------------------------------------------------------------------------- */ // * -------------------------------------------------------------------------- */
//
#include <gtsam/linear/SubgraphSolver.h> //#include <gtsam/linear/SubgraphSolver.h>
//
using namespace std; //using namespace std;
//
namespace gtsam { //namespace gtsam {
//
/* split the gaussian factor graph Ab into Ab1 and Ab2 according to the map */ ///* split the gaussian factor graph Ab into Ab1 and Ab2 according to the map */
bool split(const std::map<Index, Index> &M, //bool split(const std::map<Index, Index> &M,
const GaussianFactorGraph &Ab, // const GaussianFactorGraph &Ab,
GaussianFactorGraph &Ab1, // GaussianFactorGraph &Ab1,
GaussianFactorGraph &Ab2) { // GaussianFactorGraph &Ab2) {
//
Ab1 = GaussianFactorGraph(); // Ab1 = GaussianFactorGraph();
Ab2 = GaussianFactorGraph(); // Ab2 = GaussianFactorGraph();
//
for ( size_t i = 0 ; i < Ab.size() ; ++i ) { // for ( size_t i = 0 ; i < Ab.size() ; ++i ) {
//
boost::shared_ptr<GaussianFactor> factor = Ab[i] ; // boost::shared_ptr<GaussianFactor> factor = Ab[i] ;
//
if (factor->keys().size() > 2) // if (factor->keys().size() > 2)
throw(invalid_argument("split: only support factors with at most two keys")); // throw(invalid_argument("split: only support factors with at most two keys"));
if (factor->keys().size() == 1) { // if (factor->keys().size() == 1) {
Ab1.push_back(factor); // Ab1.push_back(factor);
Ab2.push_back(factor); // Ab2.push_back(factor);
continue; // continue;
} // }
Index key1 = factor->keys()[0]; // Index key1 = factor->keys()[0];
Index key2 = factor->keys()[1]; // Index key2 = factor->keys()[1];
//
if ((M.find(key1) != M.end() && M.find(key1)->second == key2) || // if ((M.find(key1) != M.end() && M.find(key1)->second == key2) ||
(M.find(key2) != M.end() && M.find(key2)->second == key1)) // (M.find(key2) != M.end() && M.find(key2)->second == key1))
Ab1.push_back(factor); // Ab1.push_back(factor);
else // else
Ab2.push_back(factor); // Ab2.push_back(factor);
} // }
return true ; // return true ;
} //}
//
} // \namespace gtsam //} // \namespace gtsam

View File

@ -1,101 +1,100 @@
/* ---------------------------------------------------------------------------- ///* ----------------------------------------------------------------------------
//
* GTSAM Copyright 2010, Georgia Tech Research Corporation, // * GTSAM Copyright 2010, Georgia Tech Research Corporation,
* Atlanta, Georgia 30332-0415 // * Atlanta, Georgia 30332-0415
* All Rights Reserved // * All Rights Reserved
* Authors: Frank Dellaert, et al. (see THANKS for the full author list) // * Authors: Frank Dellaert, et al. (see THANKS for the full author list)
//
* See LICENSE for the license information // * See LICENSE for the license information
//
* -------------------------------------------------------------------------- */ // * -------------------------------------------------------------------------- */
//
#pragma once //#pragma once
//
#include <boost/make_shared.hpp> //#include <boost/make_shared.hpp>
//
#include <gtsam/linear/GaussianFactorGraph.h> //#include <gtsam/linear/GaussianFactorGraph.h>
#include <gtsam/linear/IterativeSolver.h> //#include <gtsam/linear/IterativeSolver.h>
#include <gtsam/linear/SubgraphPreconditioner.h> //#include <gtsam/linear/SubgraphPreconditioner.h>
#include <gtsam/nonlinear/Values.h> //
//namespace gtsam {
namespace gtsam { //
///* split the gaussian factor graph Ab into Ab1 and Ab2 according to the map */
/* split the gaussian factor graph Ab into Ab1 and Ab2 according to the map */ //bool split(const std::map<Index, Index> &M,
bool split(const std::map<Index, Index> &M, // const GaussianFactorGraph &Ab,
const GaussianFactorGraph &Ab, // GaussianFactorGraph &Ab1,
GaussianFactorGraph &Ab1, // GaussianFactorGraph &Ab2);
GaussianFactorGraph &Ab2); //
///**
/** // * A nonlinear system solver using subgraph preconditioning conjugate gradient
* A nonlinear system solver using subgraph preconditioning conjugate gradient // * Concept NonLinearSolver<G,T,L> implements
* Concept NonLinearSolver<G,T,L> implements // * linearize: G * T -> L
* linearize: G * T -> L // * solve : L -> VectorValues
* solve : L -> VectorValues // */
*/ //template<class GRAPH, class LINEAR, class VALUES>
template<class GRAPH, class LINEAR, class KEY> //class SubgraphSolver : public IterativeSolver {
class SubgraphSolver : public IterativeSolver { //
//private:
private:
// typedef typename VALUES::Key Key; // typedef typename VALUES::Key Key;
typedef typename GRAPH::Pose Pose; // typedef typename GRAPH::Pose Pose;
typedef typename GRAPH::Constraint Constraint; // typedef typename GRAPH::Constraint Constraint;
//
typedef boost::shared_ptr<const SubgraphSolver> shared_ptr ; // typedef boost::shared_ptr<const SubgraphSolver> shared_ptr ;
typedef boost::shared_ptr<Ordering> shared_ordering ; // typedef boost::shared_ptr<Ordering> shared_ordering ;
typedef boost::shared_ptr<GRAPH> shared_graph ; // typedef boost::shared_ptr<GRAPH> shared_graph ;
typedef boost::shared_ptr<LINEAR> shared_linear ; // typedef boost::shared_ptr<LINEAR> shared_linear ;
typedef boost::shared_ptr<Values> shared_values ; // typedef boost::shared_ptr<VALUES> shared_values ;
typedef boost::shared_ptr<SubgraphPreconditioner> shared_preconditioner ; // typedef boost::shared_ptr<SubgraphPreconditioner> shared_preconditioner ;
typedef std::map<Index,Index> mapPairIndex ; // typedef std::map<Index,Index> mapPairIndex ;
//
/* the ordering derived from the spanning tree */ // /* the ordering derived from the spanning tree */
shared_ordering ordering_; // shared_ordering ordering_;
//
/* the indice of two vertices in the gaussian factor graph */ // /* the indice of two vertices in the gaussian factor graph */
mapPairIndex pairs_; // mapPairIndex pairs_;
//
/* preconditioner */ // /* preconditioner */
shared_preconditioner pc_; // shared_preconditioner pc_;
//
/* flag for direct solver - either QR or LDL */ // /* flag for direct solver - either QR or LDL */
bool useQR_; // bool useQR_;
//
public: //public:
//
SubgraphSolver(const GRAPH& G, const Values& theta0, const Parameters &parameters = Parameters(), bool useQR = false): // SubgraphSolver(const GRAPH& G, const VALUES& theta0, const Parameters &parameters = Parameters(), bool useQR = false):
IterativeSolver(parameters), useQR_(useQR) { initialize(G,theta0); } // IterativeSolver(parameters), useQR_(useQR) { initialize(G,theta0); }
//
SubgraphSolver(const LINEAR& GFG) { // SubgraphSolver(const LINEAR& GFG) {
std::cout << "[SubgraphSolver] Unexpected usage.." << std::endl; // std::cout << "[SubgraphSolver] Unexpected usage.." << std::endl;
throw std::runtime_error("SubgraphSolver: gaussian factor graph initialization not supported"); // throw std::runtime_error("SubgraphSolver: gaussian factor graph initialization not supported");
} // }
//
SubgraphSolver(const shared_linear& GFG, const boost::shared_ptr<VariableIndex>& structure, bool useQR = false) { // SubgraphSolver(const shared_linear& GFG, const boost::shared_ptr<VariableIndex>& structure, bool useQR = false) {
std::cout << "[SubgraphSolver] Unexpected usage.." << std::endl; // std::cout << "[SubgraphSolver] Unexpected usage.." << std::endl;
throw std::runtime_error("SubgraphSolver: gaussian factor graph and variable index initialization not supported"); // throw std::runtime_error("SubgraphSolver: gaussian factor graph and variable index initialization not supported");
} // }
//
SubgraphSolver(const SubgraphSolver& solver) : // SubgraphSolver(const SubgraphSolver& solver) :
IterativeSolver(solver), ordering_(solver.ordering_), pairs_(solver.pairs_), pc_(solver.pc_), useQR_(solver.useQR_) {} // IterativeSolver(solver), ordering_(solver.ordering_), pairs_(solver.pairs_), pc_(solver.pc_), useQR_(solver.useQR_) {}
//
SubgraphSolver(shared_ordering ordering, // SubgraphSolver(shared_ordering ordering,
mapPairIndex pairs, // mapPairIndex pairs,
shared_preconditioner pc, // shared_preconditioner pc,
sharedParameters parameters = boost::make_shared<Parameters>(), // sharedParameters parameters = boost::make_shared<Parameters>(),
bool useQR = true) : // bool useQR = true) :
IterativeSolver(parameters), ordering_(ordering), pairs_(pairs), pc_(pc), useQR_(useQR) {} // IterativeSolver(parameters), ordering_(ordering), pairs_(pairs), pc_(pc), useQR_(useQR) {}
//
void replaceFactors(const typename LINEAR::shared_ptr &graph); // void replaceFactors(const typename LINEAR::shared_ptr &graph);
VectorValues::shared_ptr optimize() const; // VectorValues::shared_ptr optimize() ;
shared_ordering ordering() const { return ordering_; } // shared_ordering ordering() const { return ordering_; }
//
protected: //protected:
void initialize(const GRAPH& G, const Values& theta0); // void initialize(const GRAPH& G, const VALUES& theta0);
//
private: //private:
SubgraphSolver():IterativeSolver(){} // SubgraphSolver():IterativeSolver(){}
}; //};
//
} // namespace gtsam //} // namespace gtsam
//
#include <gtsam/linear/SubgraphSolver-inl.h> //#include <gtsam/linear/SubgraphSolver-inl.h>

View File

@ -51,7 +51,7 @@ void Class::matlab_proxy(const string& classFile) const {
file.oss << "end" << endl; file.oss << "end" << endl;
// close file // close file
file.emit(false); file.emit(true);
} }
/* ************************************************************************* */ /* ************************************************************************* */

View File

@ -8,12 +8,10 @@
#include "FileWriter.h" #include "FileWriter.h"
#include "utilities.h" #include "utilities.h"
#include <boost/date_time/gregorian/gregorian.hpp>
#include <fstream> #include <fstream>
#include <iostream>
using namespace std; using namespace std;
using namespace boost::gregorian;
using namespace wrap; using namespace wrap;
/* ************************************************************************* */ /* ************************************************************************* */
@ -41,10 +39,8 @@ void FileWriter::emit(bool add_header, bool force_overwrite) const {
if (!ofs) throw CantOpenFile(filename_); if (!ofs) throw CantOpenFile(filename_);
// header // header
if (add_header) { if (add_header)
date today = day_clock::local_day(); ofs << comment_str_ << " automatically generated by wrap" << endl;
ofs << comment_str_ << " automatically generated by wrap on " << today << endl;
}
// dump in stringstream // dump in stringstream
ofs << new_contents; ofs << new_contents;

View File

@ -42,7 +42,7 @@ void Method::matlab_mfile(const string& classPath) const {
file.oss << "end" << endl; file.oss << "end" << endl;
// close file // close file
file.emit(false); file.emit(true);
} }
/* ************************************************************************* */ /* ************************************************************************* */

View File

@ -43,7 +43,7 @@ void StaticMethod::matlab_mfile(const string& toolboxPath, const string& classNa
file.oss << "end" << endl; file.oss << "end" << endl;
// close file // close file
file.emit(false); file.emit(true);
} }
/* ************************************************************************* */ /* ************************************************************************* */

View File

@ -1,3 +1,4 @@
% automatically generated by wrap
classdef Point2 classdef Point2
properties properties
self = 0 self = 0

View File

@ -0,0 +1,11 @@
// automatically generated by wrap
#include <wrap/matlab.h>
#include <Point2.h>
using namespace geometry;
void mexFunction(int nargout, mxArray *out[], int nargin, const mxArray *in[])
{
checkArguments("argChar",nargout,nargin-1,1);
shared_ptr<Point2> self = unwrap_shared_ptr< Point2 >(in[0],"Point2");
char a = unwrap< char >(in[1]);
self->argChar(a);
}

View File

@ -0,0 +1,5 @@
automatically generated by wrap
function result = argChar(obj,a)
% usage: obj.argChar(a)
error('need to compile argChar.cpp');
end

View File

@ -1,4 +1,4 @@
// automatically generated by wrap on 2012-Jan-15 // automatically generated by wrap
#include <wrap/matlab.h> #include <wrap/matlab.h>
#include <Point2.h> #include <Point2.h>
using namespace geometry; using namespace geometry;

View File

@ -1,3 +1,4 @@
automatically generated by wrap
function result = dim(obj) function result = dim(obj)
% usage: obj.dim() % usage: obj.dim()
error('need to compile dim.cpp'); error('need to compile dim.cpp');

View File

@ -0,0 +1,11 @@
// automatically generated by wrap
#include <wrap/matlab.h>
#include <Point2.h>
using namespace geometry;
void mexFunction(int nargout, mxArray *out[], int nargin, const mxArray *in[])
{
checkArguments("returnChar",nargout,nargin-1,0);
shared_ptr<Point2> self = unwrap_shared_ptr< Point2 >(in[0],"Point2");
char result = self->returnChar();
out[0] = wrap< char >(result);
}

View File

@ -0,0 +1,5 @@
automatically generated by wrap
function result = returnChar(obj)
% usage: obj.returnChar()
error('need to compile returnChar.cpp');
end

View File

@ -1,4 +1,4 @@
// automatically generated by wrap on 2012-Jan-15 // automatically generated by wrap
#include <wrap/matlab.h> #include <wrap/matlab.h>
#include <Point2.h> #include <Point2.h>
using namespace geometry; using namespace geometry;

View File

@ -1,3 +1,4 @@
automatically generated by wrap
function result = vectorConfusion(obj) function result = vectorConfusion(obj)
% usage: obj.vectorConfusion() % usage: obj.vectorConfusion()
error('need to compile vectorConfusion.cpp'); error('need to compile vectorConfusion.cpp');

View File

@ -1,4 +1,4 @@
// automatically generated by wrap on 2012-Jan-15 // automatically generated by wrap
#include <wrap/matlab.h> #include <wrap/matlab.h>
#include <Point2.h> #include <Point2.h>
using namespace geometry; using namespace geometry;

View File

@ -1,3 +1,4 @@
automatically generated by wrap
function result = x(obj) function result = x(obj)
% usage: obj.x() % usage: obj.x()
error('need to compile x.cpp'); error('need to compile x.cpp');

View File

@ -1,4 +1,4 @@
// automatically generated by wrap on 2012-Jan-15 // automatically generated by wrap
#include <wrap/matlab.h> #include <wrap/matlab.h>
#include <Point2.h> #include <Point2.h>
using namespace geometry; using namespace geometry;

View File

@ -1,3 +1,4 @@
automatically generated by wrap
function result = y(obj) function result = y(obj)
% usage: obj.y() % usage: obj.y()
error('need to compile y.cpp'); error('need to compile y.cpp');

View File

@ -1,3 +1,4 @@
% automatically generated by wrap
classdef Point3 classdef Point3
properties properties
self = 0 self = 0

View File

@ -1,4 +1,4 @@
// automatically generated by wrap on 2012-Jan-15 // automatically generated by wrap
#include <wrap/matlab.h> #include <wrap/matlab.h>
#include <Point3.h> #include <Point3.h>
using namespace geometry; using namespace geometry;

View File

@ -1,3 +1,4 @@
automatically generated by wrap
function result = norm(obj) function result = norm(obj)
% usage: obj.norm() % usage: obj.norm()
error('need to compile norm.cpp'); error('need to compile norm.cpp');

View File

@ -1,3 +1,4 @@
% automatically generated by wrap
classdef Test classdef Test
properties properties
self = 0 self = 0

View File

@ -1,4 +1,4 @@
// automatically generated by wrap on 2012-Jan-15 // automatically generated by wrap
#include <wrap/matlab.h> #include <wrap/matlab.h>
#include <folder/path/to/Test.h> #include <folder/path/to/Test.h>
using namespace geometry; using namespace geometry;

View File

@ -1,3 +1,4 @@
automatically generated by wrap
function result = arg_EigenConstRef(obj,value) function result = arg_EigenConstRef(obj,value)
% usage: obj.arg_EigenConstRef(value) % usage: obj.arg_EigenConstRef(value)
error('need to compile arg_EigenConstRef.cpp'); error('need to compile arg_EigenConstRef.cpp');

View File

@ -1,4 +1,4 @@
// automatically generated by wrap on 2012-Jan-15 // automatically generated by wrap
#include <wrap/matlab.h> #include <wrap/matlab.h>
#include <folder/path/to/Test.h> #include <folder/path/to/Test.h>
using namespace geometry; using namespace geometry;

View File

@ -1,3 +1,4 @@
automatically generated by wrap
function [first,second] = create_MixedPtrs(obj) function [first,second] = create_MixedPtrs(obj)
% usage: obj.create_MixedPtrs() % usage: obj.create_MixedPtrs()
error('need to compile create_MixedPtrs.cpp'); error('need to compile create_MixedPtrs.cpp');

View File

@ -1,4 +1,4 @@
// automatically generated by wrap on 2012-Jan-15 // automatically generated by wrap
#include <wrap/matlab.h> #include <wrap/matlab.h>
#include <folder/path/to/Test.h> #include <folder/path/to/Test.h>
using namespace geometry; using namespace geometry;

View File

@ -1,3 +1,4 @@
automatically generated by wrap
function [first,second] = create_ptrs(obj) function [first,second] = create_ptrs(obj)
% usage: obj.create_ptrs() % usage: obj.create_ptrs()
error('need to compile create_ptrs.cpp'); error('need to compile create_ptrs.cpp');

View File

@ -1,4 +1,4 @@
// automatically generated by wrap on 2012-Jan-15 // automatically generated by wrap
#include <wrap/matlab.h> #include <wrap/matlab.h>
#include <folder/path/to/Test.h> #include <folder/path/to/Test.h>
using namespace geometry; using namespace geometry;

View File

@ -1,3 +1,4 @@
automatically generated by wrap
function result = print(obj) function result = print(obj)
% usage: obj.print() % usage: obj.print()
error('need to compile print.cpp'); error('need to compile print.cpp');

View File

@ -1,4 +1,4 @@
// automatically generated by wrap on 2012-Jan-15 // automatically generated by wrap
#include <wrap/matlab.h> #include <wrap/matlab.h>
#include <folder/path/to/Test.h> #include <folder/path/to/Test.h>
using namespace geometry; using namespace geometry;

View File

@ -1,3 +1,4 @@
automatically generated by wrap
function result = return_Point2Ptr(obj,value) function result = return_Point2Ptr(obj,value)
% usage: obj.return_Point2Ptr(value) % usage: obj.return_Point2Ptr(value)
error('need to compile return_Point2Ptr.cpp'); error('need to compile return_Point2Ptr.cpp');

View File

@ -1,4 +1,4 @@
// automatically generated by wrap on 2012-Jan-15 // automatically generated by wrap
#include <wrap/matlab.h> #include <wrap/matlab.h>
#include <folder/path/to/Test.h> #include <folder/path/to/Test.h>
using namespace geometry; using namespace geometry;

View File

@ -1,3 +1,4 @@
automatically generated by wrap
function result = return_Test(obj,value) function result = return_Test(obj,value)
% usage: obj.return_Test(value) % usage: obj.return_Test(value)
error('need to compile return_Test.cpp'); error('need to compile return_Test.cpp');

View File

@ -1,4 +1,4 @@
// automatically generated by wrap on 2012-Jan-15 // automatically generated by wrap
#include <wrap/matlab.h> #include <wrap/matlab.h>
#include <folder/path/to/Test.h> #include <folder/path/to/Test.h>
using namespace geometry; using namespace geometry;

View File

@ -1,3 +1,4 @@
automatically generated by wrap
function result = return_TestPtr(obj,value) function result = return_TestPtr(obj,value)
% usage: obj.return_TestPtr(value) % usage: obj.return_TestPtr(value)
error('need to compile return_TestPtr.cpp'); error('need to compile return_TestPtr.cpp');

View File

@ -1,4 +1,4 @@
// automatically generated by wrap on 2012-Jan-15 // automatically generated by wrap
#include <wrap/matlab.h> #include <wrap/matlab.h>
#include <folder/path/to/Test.h> #include <folder/path/to/Test.h>
using namespace geometry; using namespace geometry;

View File

@ -1,3 +1,4 @@
automatically generated by wrap
function result = return_bool(obj,value) function result = return_bool(obj,value)
% usage: obj.return_bool(value) % usage: obj.return_bool(value)
error('need to compile return_bool.cpp'); error('need to compile return_bool.cpp');

View File

@ -1,4 +1,4 @@
// automatically generated by wrap on 2012-Jan-15 // automatically generated by wrap
#include <wrap/matlab.h> #include <wrap/matlab.h>
#include <folder/path/to/Test.h> #include <folder/path/to/Test.h>
using namespace geometry; using namespace geometry;

View File

@ -1,3 +1,4 @@
automatically generated by wrap
function result = return_double(obj,value) function result = return_double(obj,value)
% usage: obj.return_double(value) % usage: obj.return_double(value)
error('need to compile return_double.cpp'); error('need to compile return_double.cpp');

View File

@ -1,4 +1,4 @@
// automatically generated by wrap on 2012-Jan-15 // automatically generated by wrap
#include <wrap/matlab.h> #include <wrap/matlab.h>
#include <folder/path/to/Test.h> #include <folder/path/to/Test.h>
using namespace geometry; using namespace geometry;

View File

@ -1,3 +1,4 @@
automatically generated by wrap
function result = return_field(obj,t) function result = return_field(obj,t)
% usage: obj.return_field(t) % usage: obj.return_field(t)
error('need to compile return_field.cpp'); error('need to compile return_field.cpp');

View File

@ -1,4 +1,4 @@
// automatically generated by wrap on 2012-Jan-15 // automatically generated by wrap
#include <wrap/matlab.h> #include <wrap/matlab.h>
#include <folder/path/to/Test.h> #include <folder/path/to/Test.h>
using namespace geometry; using namespace geometry;

View File

@ -1,3 +1,4 @@
automatically generated by wrap
function result = return_int(obj,value) function result = return_int(obj,value)
% usage: obj.return_int(value) % usage: obj.return_int(value)
error('need to compile return_int.cpp'); error('need to compile return_int.cpp');

View File

@ -1,4 +1,4 @@
// automatically generated by wrap on 2012-Jan-15 // automatically generated by wrap
#include <wrap/matlab.h> #include <wrap/matlab.h>
#include <folder/path/to/Test.h> #include <folder/path/to/Test.h>
using namespace geometry; using namespace geometry;

View File

@ -1,3 +1,4 @@
automatically generated by wrap
function result = return_matrix1(obj,value) function result = return_matrix1(obj,value)
% usage: obj.return_matrix1(value) % usage: obj.return_matrix1(value)
error('need to compile return_matrix1.cpp'); error('need to compile return_matrix1.cpp');

View File

@ -1,4 +1,4 @@
// automatically generated by wrap on 2012-Jan-15 // automatically generated by wrap
#include <wrap/matlab.h> #include <wrap/matlab.h>
#include <folder/path/to/Test.h> #include <folder/path/to/Test.h>
using namespace geometry; using namespace geometry;

View File

@ -1,3 +1,4 @@
automatically generated by wrap
function result = return_matrix2(obj,value) function result = return_matrix2(obj,value)
% usage: obj.return_matrix2(value) % usage: obj.return_matrix2(value)
error('need to compile return_matrix2.cpp'); error('need to compile return_matrix2.cpp');

View File

@ -1,4 +1,4 @@
// automatically generated by wrap on 2012-Jan-15 // automatically generated by wrap
#include <wrap/matlab.h> #include <wrap/matlab.h>
#include <folder/path/to/Test.h> #include <folder/path/to/Test.h>
using namespace geometry; using namespace geometry;

View File

@ -1,3 +1,4 @@
automatically generated by wrap
function [first,second] = return_pair(obj,v,A) function [first,second] = return_pair(obj,v,A)
% usage: obj.return_pair(v,A) % usage: obj.return_pair(v,A)
error('need to compile return_pair.cpp'); error('need to compile return_pair.cpp');

View File

@ -1,4 +1,4 @@
// automatically generated by wrap on 2012-Jan-15 // automatically generated by wrap
#include <wrap/matlab.h> #include <wrap/matlab.h>
#include <folder/path/to/Test.h> #include <folder/path/to/Test.h>
using namespace geometry; using namespace geometry;

View File

@ -1,3 +1,4 @@
automatically generated by wrap
function [first,second] = return_ptrs(obj,p1,p2) function [first,second] = return_ptrs(obj,p1,p2)
% usage: obj.return_ptrs(p1,p2) % usage: obj.return_ptrs(p1,p2)
error('need to compile return_ptrs.cpp'); error('need to compile return_ptrs.cpp');

View File

@ -1,4 +1,4 @@
// automatically generated by wrap on 2012-Jan-15 // automatically generated by wrap
#include <wrap/matlab.h> #include <wrap/matlab.h>
#include <folder/path/to/Test.h> #include <folder/path/to/Test.h>
using namespace geometry; using namespace geometry;

View File

@ -1,3 +1,4 @@
automatically generated by wrap
function result = return_size_t(obj,value) function result = return_size_t(obj,value)
% usage: obj.return_size_t(value) % usage: obj.return_size_t(value)
error('need to compile return_size_t.cpp'); error('need to compile return_size_t.cpp');

View File

@ -1,4 +1,4 @@
// automatically generated by wrap on 2012-Jan-15 // automatically generated by wrap
#include <wrap/matlab.h> #include <wrap/matlab.h>
#include <folder/path/to/Test.h> #include <folder/path/to/Test.h>
using namespace geometry; using namespace geometry;

View File

@ -1,3 +1,4 @@
automatically generated by wrap
function result = return_string(obj,value) function result = return_string(obj,value)
% usage: obj.return_string(value) % usage: obj.return_string(value)
error('need to compile return_string.cpp'); error('need to compile return_string.cpp');

View File

@ -1,4 +1,4 @@
// automatically generated by wrap on 2012-Jan-15 // automatically generated by wrap
#include <wrap/matlab.h> #include <wrap/matlab.h>
#include <folder/path/to/Test.h> #include <folder/path/to/Test.h>
using namespace geometry; using namespace geometry;

View File

@ -1,3 +1,4 @@
automatically generated by wrap
function result = return_vector1(obj,value) function result = return_vector1(obj,value)
% usage: obj.return_vector1(value) % usage: obj.return_vector1(value)
error('need to compile return_vector1.cpp'); error('need to compile return_vector1.cpp');

View File

@ -1,4 +1,4 @@
// automatically generated by wrap on 2012-Jan-15 // automatically generated by wrap
#include <wrap/matlab.h> #include <wrap/matlab.h>
#include <folder/path/to/Test.h> #include <folder/path/to/Test.h>
using namespace geometry; using namespace geometry;

View File

@ -1,3 +1,4 @@
automatically generated by wrap
function result = return_vector2(obj,value) function result = return_vector2(obj,value)
% usage: obj.return_vector2(value) % usage: obj.return_vector2(value)
error('need to compile return_vector2.cpp'); error('need to compile return_vector2.cpp');

View File

@ -1,4 +1,4 @@
# automatically generated by wrap on 2012-Jan-23 # automatically generated by wrap
MEX = mex MEX = mex
MEXENDING = mexa64 MEXENDING = mexa64

View File

@ -1,4 +1,4 @@
// automatically generated by wrap on 2012-Jan-15 // automatically generated by wrap
#include <wrap/matlab.h> #include <wrap/matlab.h>
#include <Point3.h> #include <Point3.h>
using namespace geometry; using namespace geometry;

View File

@ -1,3 +1,4 @@
automatically generated by wrap
function result = Point3_StaticFunctionRet(z) function result = Point3_StaticFunctionRet(z)
% usage: x = Point3_StaticFunctionRet(z) % usage: x = Point3_StaticFunctionRet(z)
error('need to compile Point3_StaticFunctionRet.cpp'); error('need to compile Point3_StaticFunctionRet.cpp');

View File

@ -1,4 +1,4 @@
// automatically generated by wrap on 2012-Jan-15 // automatically generated by wrap
#include <wrap/matlab.h> #include <wrap/matlab.h>
#include <Point3.h> #include <Point3.h>
using namespace geometry; using namespace geometry;

View File

@ -1,3 +1,4 @@
automatically generated by wrap
function result = Point3_staticFunction() function result = Point3_staticFunction()
% usage: x = Point3_staticFunction() % usage: x = Point3_staticFunction()
error('need to compile Point3_staticFunction.cpp'); error('need to compile Point3_staticFunction.cpp');

View File

@ -1,4 +1,4 @@
% automatically generated by wrap on 2012-Jan-23 % automatically generated by wrap
echo on echo on
toolboxpath = mfilename('fullpath'); toolboxpath = mfilename('fullpath');

View File

@ -1,4 +1,4 @@
// automatically generated by wrap on 2012-Jan-15 // automatically generated by wrap
#include <wrap/matlab.h> #include <wrap/matlab.h>
#include <Point2.h> #include <Point2.h>
using namespace geometry; using namespace geometry;

View File

@ -1,4 +1,4 @@
% automatically generated by wrap on 2012-Jan-15 % automatically generated by wrap
function result = new_Point2_(obj) function result = new_Point2_(obj)
error('need to compile new_Point2_.cpp'); error('need to compile new_Point2_.cpp');
end end

View File

@ -1,4 +1,4 @@
// automatically generated by wrap on 2012-Jan-15 // automatically generated by wrap
#include <wrap/matlab.h> #include <wrap/matlab.h>
#include <Point2.h> #include <Point2.h>
using namespace geometry; using namespace geometry;

View File

@ -1,4 +1,4 @@
% automatically generated by wrap on 2012-Jan-15 % automatically generated by wrap
function result = new_Point2_dd(obj,x,y) function result = new_Point2_dd(obj,x,y)
error('need to compile new_Point2_dd.cpp'); error('need to compile new_Point2_dd.cpp');
end end

View File

@ -1,4 +1,4 @@
// automatically generated by wrap on 2012-Jan-15 // automatically generated by wrap
#include <wrap/matlab.h> #include <wrap/matlab.h>
#include <Point3.h> #include <Point3.h>
using namespace geometry; using namespace geometry;

View File

@ -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) function result = new_Point3_ddd(obj,x,y,z)
error('need to compile new_Point3_ddd.cpp'); error('need to compile new_Point3_ddd.cpp');
end end

View File

@ -1,4 +1,4 @@
// automatically generated by wrap on 2012-Jan-15 // automatically generated by wrap
#include <wrap/matlab.h> #include <wrap/matlab.h>
#include <folder/path/to/Test.h> #include <folder/path/to/Test.h>
using namespace geometry; using namespace geometry;

View File

@ -1,4 +1,4 @@
% automatically generated by wrap on 2012-Jan-15 % automatically generated by wrap
function result = new_Test_(obj) function result = new_Test_(obj)
error('need to compile new_Test_.cpp'); error('need to compile new_Test_.cpp');
end end

View File

@ -1,10 +0,0 @@
// automatically generated by wrap on 2011-Dec-01
#include <wrap/matlab.h>
#include <Test.h>
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");
}

View File

@ -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

View File

@ -1,4 +1,4 @@
// automatically generated by wrap on 2012-Jan-15 // automatically generated by wrap
#include <wrap/matlab.h> #include <wrap/matlab.h>
#include <folder/path/to/Test.h> #include <folder/path/to/Test.h>
using namespace geometry; using namespace geometry;

View File

@ -1,4 +1,4 @@
% automatically generated by wrap on 2012-Jan-15 % automatically generated by wrap
function result = new_Test_dM(obj,a,b) function result = new_Test_dM(obj,a,b)
error('need to compile new_Test_dM.cpp'); error('need to compile new_Test_dM.cpp');
end end

View File

@ -1,10 +1,11 @@
% automatically generated by wrap
classdef ClassD classdef ClassD
properties properties
self = 0 self = 0
end end
methods methods
function obj = ClassD(varargin) 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 if nargin ~= 13 && obj.self == 0, error('ClassD constructor failed'); end
end end
function display(obj), obj.print(''); end function display(obj), obj.print(''); end

View File

@ -1,3 +1,4 @@
% automatically generated by wrap
classdef ns1ClassA classdef ns1ClassA
properties properties
self = 0 self = 0

View File

@ -1,3 +1,4 @@
% automatically generated by wrap
classdef ns1ClassB classdef ns1ClassB
properties properties
self = 0 self = 0

View File

@ -1,4 +1,4 @@
// automatically generated by wrap on 2011-Dec-15 // automatically generated by wrap
#include <wrap/matlab.h> #include <wrap/matlab.h>
#include <path/to/ns2.h> #include <path/to/ns2.h>
#include <path/to/ns2/ClassA.h> #include <path/to/ns2/ClassA.h>

View File

@ -1,3 +1,4 @@
automatically generated by wrap
function result = memberFunction(obj) function result = memberFunction(obj)
% usage: obj.memberFunction() % usage: obj.memberFunction()
error('need to compile memberFunction.cpp'); error('need to compile memberFunction.cpp');

View File

@ -1,3 +1,4 @@
% automatically generated by wrap
classdef ns2ClassA classdef ns2ClassA
properties properties
self = 0 self = 0

View File

@ -1,4 +1,4 @@
// automatically generated by wrap on 2011-Dec-15 // automatically generated by wrap
#include <wrap/matlab.h> #include <wrap/matlab.h>
#include <path/to/ns2.h> #include <path/to/ns2.h>
#include <path/to/ns2/ClassA.h> #include <path/to/ns2/ClassA.h>

View File

@ -1,3 +1,4 @@
automatically generated by wrap
function result = nsArg(obj,arg) function result = nsArg(obj,arg)
% usage: obj.nsArg(arg) % usage: obj.nsArg(arg)
error('need to compile nsArg.cpp'); error('need to compile nsArg.cpp');

View File

@ -1,4 +1,4 @@
// automatically generated by wrap on 2011-Dec-15 // automatically generated by wrap
#include <wrap/matlab.h> #include <wrap/matlab.h>
#include <path/to/ns2.h> #include <path/to/ns2.h>
#include <path/to/ns2/ClassA.h> #include <path/to/ns2/ClassA.h>

Some files were not shown because too many files have changed in this diff Show More