config() changed to values() for consistency

release/4.3a0
Chris Beall 2010-10-22 19:29:15 +00:00
parent 16589e841a
commit 69c6d05ce1
13 changed files with 152 additions and 152 deletions

View File

@ -70,7 +70,7 @@ int main(int argc, char** argv) {
Optimizer::Parameters::verbosityLevel verbosity = pose2SLAM::Optimizer::Parameters::SILENT;
Optimizer optimizer_result = optimizer.levenbergMarquardt(1e-15, 1e-15, verbosity);
Values result = *optimizer_result.config();
Values result = *optimizer_result.values();
result.print("final result");
return 0;
}

View File

@ -52,7 +52,7 @@ int main(void) {
SPCGOptimizer optimizer2 = optimizer.levenbergMarquardt(parameter);
cout << "after optimization, sum of error is " << optimizer2.error() << endl;
result = *optimizer2.config() ;
result = *optimizer2.values() ;
result.print("final result") ;
return 0 ;

View File

@ -45,7 +45,7 @@ namespace gtsam {
// Levenberg-Marquardt
Optimizer result = optimizer.levenbergMarquardt(parameters);
return *result.config();
return *result.values();
}
/**
@ -64,7 +64,7 @@ namespace gtsam {
// Levenberg-Marquardt
Optimizer result = optimizer.levenbergMarquardt(parameters);
return *result.config();
return *result.values();
}
// /**
@ -83,7 +83,7 @@ namespace gtsam {
//
// // Levenberg-Marquardt
// SPCGOptimizer result = optimizer.levenbergMarquardt(parameters);
// return *result.config();
// return *result.values();
// }
/**

View File

@ -17,7 +17,7 @@ namespace gtsam {
ERROR,
LAMBDA,
TRYLAMBDA,
CONFIG,
VALUES,
DELTA,
TRYCONFIG,
TRYDELTA,

View File

@ -74,13 +74,13 @@ namespace gtsam {
/* ************************************************************************* */
template<class G, class C, class L, class S, class W>
NonlinearOptimizer<G, C, L, S, W>::NonlinearOptimizer(shared_graph graph,
shared_values config, shared_ordering ordering, double lambda) :
graph_(graph), config_(config), error_(graph->error(*config)),
ordering_(ordering), lambda_(lambda), dimensions_(new vector<size_t>(config->dims(*ordering))) {
shared_values values, shared_ordering ordering, double lambda) :
graph_(graph), values_(values), error_(graph->error(*values)),
ordering_(ordering), lambda_(lambda), dimensions_(new vector<size_t>(values->dims(*ordering))) {
if (!graph) throw std::invalid_argument(
"NonlinearOptimizer constructor: graph = NULL");
if (!config) throw std::invalid_argument(
"NonlinearOptimizer constructor: config = NULL");
if (!values) throw std::invalid_argument(
"NonlinearOptimizer constructor: values = NULL");
if (!ordering) throw std::invalid_argument(
"NonlinearOptimizer constructor: ordering = NULL");
}
@ -90,8 +90,8 @@ namespace gtsam {
/* ************************************************************************* */
template<class G, class C, class L, class S, class W>
VectorValues NonlinearOptimizer<G, C, L, S, W>::linearizeAndOptimizeForDelta() const {
boost::shared_ptr<L> linearized = graph_->linearize(*config_, *ordering_);
// NonlinearOptimizer prepared(graph_, config_, ordering_, error_, lambda_);
boost::shared_ptr<L> linearized = graph_->linearize(*values_, *ordering_);
// NonlinearOptimizer prepared(graph_, values_, ordering_, error_, lambda_);
return *S(*linearized).optimize();
}
@ -108,11 +108,11 @@ namespace gtsam {
if (verbosity >= Parameters::DELTA)
delta.print("delta");
// take old config and update it
shared_values newValues(new C(config_->expmap(delta, *ordering_)));
// take old values and update it
shared_values newValues(new C(values_->expmap(delta, *ordering_)));
// maybe show output
if (verbosity >= Parameters::CONFIG)
if (verbosity >= Parameters::VALUES)
newValues->print("newValues");
NonlinearOptimizer newOptimizer = newValues_(newValues);
@ -181,10 +181,10 @@ namespace gtsam {
if (verbosity >= Parameters::TRYDELTA)
delta.print("delta");
// update config
shared_values newValues(new C(config_->expmap(delta, *ordering_))); // TODO: updateValues
// if (verbosity >= TRYCONFIG)
// newValues->print("config");
// update values
shared_values newValues(new C(values_->expmap(delta, *ordering_))); // TODO: updateValues
// if (verbosity >= TRYvalues)
// newValues->print("values");
// create new optimization state with more adventurous lambda
NonlinearOptimizer next(newValuesNewLambda_(newValues, lambda_ / factor));
@ -219,9 +219,9 @@ namespace gtsam {
// Either we're not cautious, or the same lambda was worse than the current error.
// The more adventerous lambda was worse too, so make lambda more conservative
// and keep the same config.
// and keep the same values.
// TODO: can we avoid copying the config ?
// TODO: can we avoid copying the values ?
if(lambdaMode >= Parameters::BOUNDED && lambda_ >= 1.0e5) {
return NonlinearOptimizer(newValues_(newValues));
} else {
@ -240,15 +240,15 @@ namespace gtsam {
Parameters::verbosityLevel verbosity, double lambdaFactor, Parameters::LambdaMode lambdaMode) const {
// show output
if (verbosity >= Parameters::CONFIG)
config_->print("config");
if (verbosity >= Parameters::VALUES)
values_->print("values");
if (verbosity >= Parameters::ERROR)
cout << "error: " << error_ << endl;
if (verbosity >= Parameters::LAMBDA)
cout << "lambda = " << lambda_ << endl;
// linearize all factors once
boost::shared_ptr<L> linear = graph_->linearize(*config_, *ordering_);
boost::shared_ptr<L> linear = graph_->linearize(*values_, *ordering_);
if (verbosity >= Parameters::LINEAR)
linear->print("linear");
@ -298,8 +298,8 @@ namespace gtsam {
// return converged state or iterate
if (converged || para.maxIterations_ <= 1) {
// maybe show output
if (para.verbosity_ >= Parameters::CONFIG)
next.config_->print("final config");
if (para.verbosity_ >= Parameters::VALUES)
next.values_->print("final values");
if (para.verbosity_ >= Parameters::ERROR)
cout << "final error: " << next.error_ << endl;
if (para.verbosity_ >= Parameters::LAMBDA)

View File

@ -84,7 +84,7 @@ namespace gtsam {
// keep a values structure and its error
// These typically change once per iteration (in a functional way)
const shared_values config_;
const shared_values values_;
const double error_;
const shared_ordering ordering_;
@ -106,12 +106,12 @@ namespace gtsam {
* Constructor that does not do any computation
*/
NonlinearOptimizer(shared_graph graph, shared_values config, shared_ordering ordering,
const double error, const double lambda, shared_dimensions dimensions): graph_(graph), config_(config),
const double error, const double lambda, shared_dimensions dimensions): graph_(graph), values_(config),
error_(error), ordering_(ordering), lambda_(lambda), dimensions_(dimensions) {}
/** Create a new NonlinearOptimizer with a different lambda */
This newLambda_(double newLambda) const {
return NonlinearOptimizer(graph_, config_, ordering_, error_, newLambda, dimensions_); }
return NonlinearOptimizer(graph_, values_, ordering_, error_, newLambda, dimensions_); }
This newValues_(shared_values newValues) const {
return NonlinearOptimizer(graph_, newValues, ordering_, graph_->error(*newValues), lambda_, dimensions_); }
@ -131,7 +131,7 @@ namespace gtsam {
* Copy constructor
*/
NonlinearOptimizer(const NonlinearOptimizer<G, T, L, GS> &optimizer) :
graph_(optimizer.graph_), config_(optimizer.config_), error_(optimizer.error_),
graph_(optimizer.graph_), values_(optimizer.values_), error_(optimizer.error_),
ordering_(optimizer.ordering_), lambda_(optimizer.lambda_), dimensions_(optimizer.dimensions_) {}
/**
@ -149,10 +149,10 @@ namespace gtsam {
}
/**
* Return the config
* Return the values
*/
shared_values config() const{
return config_;
shared_values values() const{
return values_;
}
/**
@ -227,7 +227,7 @@ namespace gtsam {
// Levenberg-Marquardt
NonlinearOptimizer result = optimizer.levenbergMarquardt(relativeThreshold,
absoluteThreshold, verbosity);
return result.config();
return result.values();
}
/**
@ -258,7 +258,7 @@ namespace gtsam {
// Gauss-Newton
NonlinearOptimizer result = optimizer.gaussNewton(relativeThreshold,
absoluteThreshold, verbosity);
return result.config();
return result.values();
}
/**

View File

@ -50,22 +50,22 @@ namespace gtsam {
/* ************************************************************************* */
/** TupleValues 1 */
template<class VALUES1>
TupleValues1<VALUES1>::TupleValues1(const TupleValues1<VALUES1>& config) :
TupleValuesEnd<VALUES1> (config) {}
TupleValues1<VALUES1>::TupleValues1(const TupleValues1<VALUES1>& values) :
TupleValuesEnd<VALUES1> (values) {}
template<class VALUES1>
TupleValues1<VALUES1>::TupleValues1(const VALUES1& cfg1) :
TupleValuesEnd<VALUES1> (cfg1) {}
template<class VALUES1>
TupleValues1<VALUES1>::TupleValues1(const TupleValuesEnd<VALUES1>& config) :
TupleValuesEnd<VALUES1>(config) {}
TupleValues1<VALUES1>::TupleValues1(const TupleValuesEnd<VALUES1>& values) :
TupleValuesEnd<VALUES1>(values) {}
/* ************************************************************************* */
/** TupleValues 2 */
template<class VALUES1, class VALUES2>
TupleValues2<VALUES1, VALUES2>::TupleValues2(const TupleValues2<VALUES1, VALUES2>& config) :
TupleValues<VALUES1, TupleValuesEnd<VALUES2> >(config) {}
TupleValues2<VALUES1, VALUES2>::TupleValues2(const TupleValues2<VALUES1, VALUES2>& values) :
TupleValues<VALUES1, TupleValuesEnd<VALUES2> >(values) {}
template<class VALUES1, class VALUES2>
TupleValues2<VALUES1, VALUES2>::TupleValues2(const VALUES1& cfg1, const VALUES2& cfg2) :
@ -73,15 +73,15 @@ TupleValues2<VALUES1, VALUES2>::TupleValues2(const VALUES1& cfg1, const VALUES2&
cfg1, TupleValuesEnd<VALUES2>(cfg2)) {}
template<class VALUES1, class VALUES2>
TupleValues2<VALUES1, VALUES2>::TupleValues2(const TupleValues<VALUES1, TupleValuesEnd<VALUES2> >& config) :
TupleValues<VALUES1, TupleValuesEnd<VALUES2> >(config) {}
TupleValues2<VALUES1, VALUES2>::TupleValues2(const TupleValues<VALUES1, TupleValuesEnd<VALUES2> >& values) :
TupleValues<VALUES1, TupleValuesEnd<VALUES2> >(values) {}
/* ************************************************************************* */
/** TupleValues 3 */
template<class VALUES1, class VALUES2, class VALUES3>
TupleValues3<VALUES1, VALUES2, VALUES3>::TupleValues3(
const TupleValues3<VALUES1, VALUES2, VALUES3>& config) :
TupleValues<VALUES1, TupleValues<VALUES2, TupleValuesEnd<VALUES3> > >(config) {}
const TupleValues3<VALUES1, VALUES2, VALUES3>& values) :
TupleValues<VALUES1, TupleValues<VALUES2, TupleValuesEnd<VALUES3> > >(values) {}
template<class VALUES1, class VALUES2, class VALUES3>
TupleValues3<VALUES1, VALUES2, VALUES3>::TupleValues3(
@ -92,16 +92,16 @@ TupleValues3<VALUES1, VALUES2, VALUES3>::TupleValues3(
template<class VALUES1, class VALUES2, class VALUES3>
TupleValues3<VALUES1, VALUES2, VALUES3>::TupleValues3(
const TupleValues<VALUES1, TupleValues<VALUES2, TupleValuesEnd<VALUES3> > >& config) :
TupleValues<VALUES1, TupleValues<VALUES2, TupleValuesEnd<VALUES3> > >(config) {}
const TupleValues<VALUES1, TupleValues<VALUES2, TupleValuesEnd<VALUES3> > >& values) :
TupleValues<VALUES1, TupleValues<VALUES2, TupleValuesEnd<VALUES3> > >(values) {}
/* ************************************************************************* */
/** TupleValues 4 */
template<class VALUES1, class VALUES2, class VALUES3, class VALUES4>
TupleValues4<VALUES1, VALUES2, VALUES3, VALUES4>::TupleValues4(
const TupleValues4<VALUES1, VALUES2, VALUES3, VALUES4>& config) :
const TupleValues4<VALUES1, VALUES2, VALUES3, VALUES4>& values) :
TupleValues<VALUES1, TupleValues<VALUES2,
TupleValues<VALUES3, TupleValuesEnd<VALUES4> > > >(config) {}
TupleValues<VALUES3, TupleValuesEnd<VALUES4> > > >(values) {}
template<class VALUES1, class VALUES2, class VALUES3, class VALUES4>
TupleValues4<VALUES1, VALUES2, VALUES3, VALUES4>::TupleValues4(
@ -116,17 +116,17 @@ TupleValues4<VALUES1, VALUES2, VALUES3, VALUES4>::TupleValues4(
template<class VALUES1, class VALUES2, class VALUES3, class VALUES4>
TupleValues4<VALUES1, VALUES2, VALUES3, VALUES4>::TupleValues4(
const TupleValues<VALUES1, TupleValues<VALUES2,
TupleValues<VALUES3, TupleValuesEnd<VALUES4> > > >& config) :
TupleValues<VALUES3, TupleValuesEnd<VALUES4> > > >& values) :
TupleValues<VALUES1, TupleValues<VALUES2,TupleValues<VALUES3,
TupleValuesEnd<VALUES4> > > >(config) {}
TupleValuesEnd<VALUES4> > > >(values) {}
/* ************************************************************************* */
/** TupleValues 5 */
template<class VALUES1, class VALUES2, class VALUES3, class VALUES4, class VALUES5>
TupleValues5<VALUES1, VALUES2, VALUES3, VALUES4, VALUES5>::TupleValues5(
const TupleValues5<VALUES1, VALUES2, VALUES3, VALUES4, VALUES5>& config) :
const TupleValues5<VALUES1, VALUES2, VALUES3, VALUES4, VALUES5>& values) :
TupleValues<VALUES1, TupleValues<VALUES2, TupleValues<VALUES3,
TupleValues<VALUES4, TupleValuesEnd<VALUES5> > > > >(config) {}
TupleValues<VALUES4, TupleValuesEnd<VALUES5> > > > >(values) {}
template<class VALUES1, class VALUES2, class VALUES3, class VALUES4, class VALUES5>
TupleValues5<VALUES1, VALUES2, VALUES3, VALUES4, VALUES5>::TupleValues5(
@ -144,9 +144,9 @@ TupleValues5<VALUES1, VALUES2, VALUES3, VALUES4, VALUES5>::TupleValues5(
template<class VALUES1, class VALUES2, class VALUES3, class VALUES4, class VALUES5>
TupleValues5<VALUES1, VALUES2, VALUES3, VALUES4, VALUES5>::TupleValues5(
const TupleValues<VALUES1, TupleValues<VALUES2, TupleValues<VALUES3,
TupleValues<VALUES4, TupleValuesEnd<VALUES5> > > > >& config) :
TupleValues<VALUES4, TupleValuesEnd<VALUES5> > > > >& values) :
TupleValues<VALUES1, TupleValues<VALUES2, TupleValues<VALUES3,
TupleValues<VALUES4, TupleValuesEnd<VALUES5> > > > >(config) {}
TupleValues<VALUES4, TupleValuesEnd<VALUES5> > > > >(values) {}
/* ************************************************************************* */
/** TupleValues 6 */
@ -154,10 +154,10 @@ template<class VALUES1, class VALUES2, class VALUES3,
class VALUES4, class VALUES5, class VALUES6>
TupleValues6<VALUES1, VALUES2, VALUES3, VALUES4, VALUES5, VALUES6>::TupleValues6(
const TupleValues6<VALUES1, VALUES2, VALUES3,
VALUES4, VALUES5, VALUES6>& config) :
VALUES4, VALUES5, VALUES6>& values) :
TupleValues<VALUES1, TupleValues<VALUES2, TupleValues<VALUES3,
TupleValues<VALUES4, TupleValues<VALUES5,
TupleValuesEnd<VALUES6> > > > > >(config) {}
TupleValuesEnd<VALUES6> > > > > >(values) {}
template<class VALUES1, class VALUES2, class VALUES3,
class VALUES4, class VALUES5, class VALUES6>
@ -180,9 +180,9 @@ template<class VALUES1, class VALUES2, class VALUES3,
TupleValues6<VALUES1, VALUES2, VALUES3, VALUES4, VALUES5, VALUES6>::TupleValues6(
const TupleValues<VALUES1, TupleValues<VALUES2, TupleValues<VALUES3,
TupleValues<VALUES4, TupleValues<VALUES5,
TupleValuesEnd<VALUES6> > > > > >& config) :
TupleValuesEnd<VALUES6> > > > > >& values) :
TupleValues<VALUES1, TupleValues<VALUES2, TupleValues<VALUES3,
TupleValues<VALUES4, TupleValues<VALUES5,
TupleValuesEnd<VALUES6> > > > > >(config) {}
TupleValuesEnd<VALUES6> > > > > >(values) {}
}

View File

@ -30,8 +30,8 @@ namespace gtsam {
* reduce run-time overhead and keep static type checking. The interface
* mimics that of a single LieValues.
*
* This uses a recursive structure of config pairs to form a lisp-like
* list, with a special case (TupleValuesEnd) that contains only one config
* This uses a recursive structure of values pairs to form a lisp-like
* list, with a special case (TupleValuesEnd) that contains only one values
* at the end. Because this recursion is done at compile time, there is no
* runtime performance hit to using this structure.
*
@ -43,19 +43,19 @@ namespace gtsam {
* Design and extension note:
* To implement a recursively templated data structure, note that most operations
* have two versions: one with templates and one without. The templated one allows
* for the arguments to be passed to the next config, while the specialized one
* operates on the "first" config. TupleValuesEnd contains only the specialized version.
* for the arguments to be passed to the next values, while the specialized one
* operates on the "first" values. TupleValuesEnd contains only the specialized version.
*/
template<class VALUES1, class VALUES2>
class TupleValues : public Testable<TupleValues<VALUES1, VALUES2> > {
protected:
// Data for internal configs
VALUES1 first_; /// Arbitrary config
VALUES2 second_; /// A TupleValues or TupleValuesEnd, which wraps an arbitrary config
// Data for internal valuess
VALUES1 first_; /// Arbitrary values
VALUES2 second_; /// A TupleValues or TupleValuesEnd, which wraps an arbitrary values
public:
// typedefs for config subtypes
// typedefs for values subtypes
typedef class VALUES1::Key Key1;
typedef class VALUES1::Value Value1;
@ -63,10 +63,10 @@ namespace gtsam {
TupleValues() {}
/** Copy constructor */
TupleValues(const TupleValues<VALUES1, VALUES2>& config) :
first_(config.first_), second_(config.second_) {}
TupleValues(const TupleValues<VALUES1, VALUES2>& values) :
first_(values.first_), second_(values.second_) {}
/** Construct from configs */
/** Construct from valuess */
TupleValues(const VALUES1& cfg1, const VALUES2& cfg2) :
first_(cfg1), second_(cfg2) {}
@ -82,8 +82,8 @@ namespace gtsam {
}
/**
* Insert a key/value pair to the config.
* Note: if the key is already in the config, the config will not be changed.
* Insert a key/value pair to the values.
* Note: if the key is already in the values, the values will not be changed.
* Use update() to allow for changing existing values.
* @param key is the key - can be an int (second version) if the can can be initialized from an int
* @param value is the value to insert
@ -94,27 +94,27 @@ namespace gtsam {
void insert(const Key1& key, const Value1& value) {first_.insert(key, value);}
/**
* Insert a complete config at a time.
* Note: if the key is already in the config, the config will not be changed.
* Insert a complete values at a time.
* Note: if the key is already in the values, the values will not be changed.
* Use update() to allow for changing existing values.
* @param config is a full config to add
* @param values is a full values to add
*/
template<class CFG1, class CFG2>
void insert(const TupleValues<CFG1, CFG2>& config) { second_.insert(config); }
void insert(const TupleValues<VALUES1, VALUES2>& config) {
first_.insert(config.first_);
second_.insert(config.second_);
void insert(const TupleValues<CFG1, CFG2>& values) { second_.insert(values); }
void insert(const TupleValues<VALUES1, VALUES2>& values) {
first_.insert(values.first_);
second_.insert(values.second_);
}
/**
* Update function for whole configs - this will change existing values
* @param config is a config to add
* Update function for whole valuess - this will change existing values
* @param values is a values to add
*/
template<class CFG1, class CFG2>
void update(const TupleValues<CFG1, CFG2>& config) { second_.update(config); }
void update(const TupleValues<VALUES1, VALUES2>& config) {
first_.update(config.first_);
second_.update(config.second_);
void update(const TupleValues<CFG1, CFG2>& values) { second_.update(values); }
void update(const TupleValues<VALUES1, VALUES2>& values) {
first_.update(values.first_);
second_.update(values.second_);
}
/**
@ -127,19 +127,19 @@ namespace gtsam {
void update(const Key1& key, const Value1& value) { first_.update(key, value); }
/**
* Insert a subconfig
* @param config is the config to insert
* Insert a subvalues
* @param values is the values to insert
*/
template<class CFG>
void insertSub(const CFG& config) { second_.insertSub(config); }
void insertSub(const VALUES1& config) { first_.insert(config); }
void insertSub(const CFG& values) { second_.insertSub(values); }
void insertSub(const VALUES1& values) { first_.insert(values); }
/** erase an element by key */
template<class KEY>
void erase(const KEY& j) { second_.erase(j); }
void erase(const Key1& j) { first_.erase(j); }
/** clears the config */
/** clears the values */
void clear() { first_.clear(); second_.clear(); }
/** determine whether an element exists */
@ -162,8 +162,8 @@ namespace gtsam {
const typename KEY::Value & at(const KEY& j) const { return second_.at(j); }
const Value1& at(const Key1& j) const { return first_.at(j); }
/** direct config access */
const VALUES1& config() const { return first_; }
/** direct values access */
const VALUES1& values() const { return first_; }
const VALUES2& rest() const { return second_; }
/** zero: create VectorValues of appropriate structure */
@ -176,7 +176,7 @@ namespace gtsam {
/** @return number of key/value pairs stored */
size_t size() const { return first_.size() + second_.size(); }
/** @return true if config is empty */
/** @return true if values is empty */
bool empty() const { return first_.empty() && second_.empty(); }
/** @return The dimensionality of the tangent space */
@ -248,7 +248,7 @@ namespace gtsam {
};
/**
* End of a recursive TupleValues - contains only one config
* End of a recursive TupleValues - contains only one values
*
* Do not use this class directly - it should only be used as a part
* of a recursive structure
@ -257,7 +257,7 @@ namespace gtsam {
class TupleValuesEnd : public Testable<TupleValuesEnd<VALUES> > {
protected:
// Data for internal configs
// Data for internal valuess
VALUES first_;
public:
@ -267,8 +267,8 @@ namespace gtsam {
TupleValuesEnd() {}
TupleValuesEnd(const TupleValuesEnd<VALUES>& config) :
first_(config.first_) {}
TupleValuesEnd(const TupleValuesEnd<VALUES>& values) :
first_(values.first_) {}
TupleValuesEnd(const VALUES& cfg) :
first_(cfg) {}
@ -284,17 +284,17 @@ namespace gtsam {
void insert(const Key1& key, const Value1& value) {first_.insert(key, value); }
void insert(int key, const Value1& value) {first_.insert(Key1(key), value);}
void insert(const TupleValuesEnd<VALUES>& config) {first_.insert(config.first_); }
void insert(const TupleValuesEnd<VALUES>& values) {first_.insert(values.first_); }
void update(const TupleValuesEnd<VALUES>& config) {first_.update(config.first_); }
void update(const TupleValuesEnd<VALUES>& values) {first_.update(values.first_); }
void update(const Key1& key, const Value1& value) { first_.update(key, value); }
void insertSub(const VALUES& config) {first_.insert(config); }
void insertSub(const VALUES& values) {first_.insert(values); }
const Value1& operator[](const Key1& j) const { return first_[j]; }
const VALUES& config() const { return first_; }
const VALUES& values() const { return first_; }
void erase(const Key1& j) { first_.erase(j); }
@ -355,11 +355,11 @@ namespace gtsam {
};
/**
* Wrapper classes to act as containers for configs. Note that these can be cascaded
* recursively, as they are TupleValuess, and are primarily a short form of the config
* Wrapper classes to act as containers for valuess. Note that these can be cascaded
* recursively, as they are TupleValuess, and are primarily a short form of the values
* structure to make use of the TupleValuess easier.
*
* The interface is designed to mimic PairValues, but for 2-6 config types.
* The interface is designed to mimic PairValues, but for 2-6 values types.
*/
template<class C1>
@ -372,12 +372,12 @@ namespace gtsam {
typedef TupleValues1<C1> This;
TupleValues1() {}
TupleValues1(const This& config);
TupleValues1(const Base& config);
TupleValues1(const This& values);
TupleValues1(const Base& values);
TupleValues1(const Values1& cfg1);
// access functions
inline const Values1& first() const { return this->config(); }
inline const Values1& first() const { return this->values(); }
};
template<class C1, class C2>
@ -391,13 +391,13 @@ namespace gtsam {
typedef TupleValues2<C1, C2> This;
TupleValues2() {}
TupleValues2(const This& config);
TupleValues2(const Base& config);
TupleValues2(const This& values);
TupleValues2(const Base& values);
TupleValues2(const Values1& cfg1, const Values2& cfg2);
// access functions
inline const Values1& first() const { return this->config(); }
inline const Values2& second() const { return this->rest().config(); }
inline const Values1& first() const { return this->values(); }
inline const Values2& second() const { return this->rest().values(); }
};
template<class C1, class C2, class C3>
@ -409,14 +409,14 @@ namespace gtsam {
typedef C3 Values3;
TupleValues3() {}
TupleValues3(const TupleValues<C1, TupleValues<C2, TupleValuesEnd<C3> > >& config);
TupleValues3(const TupleValues3<C1, C2, C3>& config);
TupleValues3(const TupleValues<C1, TupleValues<C2, TupleValuesEnd<C3> > >& values);
TupleValues3(const TupleValues3<C1, C2, C3>& values);
TupleValues3(const Values1& cfg1, const Values2& cfg2, const Values3& cfg3);
// access functions
inline const Values1& first() const { return this->config(); }
inline const Values2& second() const { return this->rest().config(); }
inline const Values3& third() const { return this->rest().rest().config(); }
inline const Values1& first() const { return this->values(); }
inline const Values2& second() const { return this->rest().values(); }
inline const Values3& third() const { return this->rest().rest().values(); }
};
template<class C1, class C2, class C3, class C4>
@ -432,15 +432,15 @@ namespace gtsam {
typedef TupleValues4<C1, C2, C3, C4> This;
TupleValues4() {}
TupleValues4(const This& config);
TupleValues4(const Base& config);
TupleValues4(const This& values);
TupleValues4(const Base& values);
TupleValues4(const Values1& cfg1, const Values2& cfg2, const Values3& cfg3,const Values4& cfg4);
// access functions
inline const Values1& first() const { return this->config(); }
inline const Values2& second() const { return this->rest().config(); }
inline const Values3& third() const { return this->rest().rest().config(); }
inline const Values4& fourth() const { return this->rest().rest().rest().config(); }
inline const Values1& first() const { return this->values(); }
inline const Values2& second() const { return this->rest().values(); }
inline const Values3& third() const { return this->rest().rest().values(); }
inline const Values4& fourth() const { return this->rest().rest().rest().values(); }
};
template<class C1, class C2, class C3, class C4, class C5>
@ -454,17 +454,17 @@ namespace gtsam {
typedef C5 Values5;
TupleValues5() {}
TupleValues5(const TupleValues5<C1, C2, C3, C4, C5>& config);
TupleValues5(const TupleValues<C1, TupleValues<C2, TupleValues<C3, TupleValues<C4, TupleValuesEnd<C5> > > > >& config);
TupleValues5(const TupleValues5<C1, C2, C3, C4, C5>& values);
TupleValues5(const TupleValues<C1, TupleValues<C2, TupleValues<C3, TupleValues<C4, TupleValuesEnd<C5> > > > >& values);
TupleValues5(const Values1& cfg1, const Values2& cfg2, const Values3& cfg3,
const Values4& cfg4, const Values5& cfg5);
// access functions
inline const Values1& first() const { return this->config(); }
inline const Values2& second() const { return this->rest().config(); }
inline const Values3& third() const { return this->rest().rest().config(); }
inline const Values4& fourth() const { return this->rest().rest().rest().config(); }
inline const Values5& fifth() const { return this->rest().rest().rest().rest().config(); }
inline const Values1& first() const { return this->values(); }
inline const Values2& second() const { return this->rest().values(); }
inline const Values3& third() const { return this->rest().rest().values(); }
inline const Values4& fourth() const { return this->rest().rest().rest().values(); }
inline const Values5& fifth() const { return this->rest().rest().rest().rest().values(); }
};
template<class C1, class C2, class C3, class C4, class C5, class C6>
@ -479,17 +479,17 @@ namespace gtsam {
typedef C6 Values6;
TupleValues6() {}
TupleValues6(const TupleValues6<C1, C2, C3, C4, C5, C6>& config);
TupleValues6(const TupleValues<C1, TupleValues<C2, TupleValues<C3, TupleValues<C4, TupleValues<C5, TupleValuesEnd<C6> > > > > >& config);
TupleValues6(const TupleValues6<C1, C2, C3, C4, C5, C6>& values);
TupleValues6(const TupleValues<C1, TupleValues<C2, TupleValues<C3, TupleValues<C4, TupleValues<C5, TupleValuesEnd<C6> > > > > >& values);
TupleValues6(const Values1& cfg1, const Values2& cfg2, const Values3& cfg3,
const Values4& cfg4, const Values5& cfg5, const Values6& cfg6);
// access functions
inline const Values1& first() const { return this->config(); }
inline const Values2& second() const { return this->rest().config(); }
inline const Values3& third() const { return this->rest().rest().config(); }
inline const Values4& fourth() const { return this->rest().rest().rest().config(); }
inline const Values5& fifth() const { return this->rest().rest().rest().rest().config(); }
inline const Values6& sixth() const { return this->rest().rest().rest().rest().rest().config(); }
inline const Values1& first() const { return this->values(); }
inline const Values2& second() const { return this->rest().values(); }
inline const Values3& third() const { return this->rest().rest().values(); }
inline const Values4& fourth() const { return this->rest().rest().rest().values(); }
inline const Values5& fifth() const { return this->rest().rest().rest().rest().values(); }
inline const Values6& sixth() const { return this->rest().rest().rest().rest().rest().values(); }
};
}

View File

@ -122,7 +122,7 @@ TEST(Pose2Graph, optimize) {
Pose2Values expected;
expected.insert(0, Pose2(0,0,0));
expected.insert(1, Pose2(1,2,M_PI_2));
CHECK(assert_equal(expected, *optimizer.config()));
CHECK(assert_equal(expected, *optimizer.values()));
}
/* ************************************************************************* */
@ -156,7 +156,7 @@ TEST(Pose2Graph, optimizeThreePoses) {
pose2SLAM::Optimizer::Parameters::verbosityLevel verbosity = pose2SLAM::Optimizer::Parameters::SILENT;
pose2SLAM::Optimizer optimizer = optimizer0.levenbergMarquardt(1e-15, 1e-15, verbosity);
Pose2Values actual = *optimizer.config();
Pose2Values actual = *optimizer.values();
// Check with ground truth
CHECK(assert_equal(hexagon, actual));
@ -199,7 +199,7 @@ TEST(Pose2Graph, optimizeCircle) {
pose2SLAM::Optimizer::Parameters::verbosityLevel verbosity = pose2SLAM::Optimizer::Parameters::SILENT;
pose2SLAM::Optimizer optimizer = optimizer0.levenbergMarquardt(1e-15, 1e-15, verbosity);
Pose2Values actual = *optimizer.config();
Pose2Values actual = *optimizer.values();
// Check with ground truth
CHECK(assert_equal(hexagon, actual));

View File

@ -76,7 +76,7 @@ TEST(Pose3Graph, optimizeCircle) {
// Optimizer::verbosityLevel verbosity = Optimizer::ERROR;
Optimizer optimizer = optimizer0.levenbergMarquardt(1e-15, 1e-15, verbosity);
Pose3Values actual = *optimizer.config();
Pose3Values actual = *optimizer.values();
// Check with ground truth
CHECK(assert_equal(hexagon, actual,1e-4));

View File

@ -114,7 +114,7 @@ TEST( Graph, optimizeLM)
DOUBLES_EQUAL(0.0, optimizer.error(), 1e-9);
// check if correct
CHECK(assert_equal(*initialEstimate,*(afterOneIteration.config())));
CHECK(assert_equal(*initialEstimate,*(afterOneIteration.values())));
}
@ -151,7 +151,7 @@ TEST( Graph, optimizeLM2)
DOUBLES_EQUAL(0.0, optimizer.error(), 1e-9);
// check if correct
CHECK(assert_equal(*initialEstimate,*(afterOneIteration.config())));
CHECK(assert_equal(*initialEstimate,*(afterOneIteration.values())));
}
@ -186,7 +186,7 @@ TEST( Graph, CHECK_ORDERING)
DOUBLES_EQUAL(0.0, optimizer.error(), 1e-9);
// check if correct
CHECK(assert_equal(*initialEstimate,*(afterOneIteration.config())));
CHECK(assert_equal(*initialEstimate,*(afterOneIteration.values())));
}
/* ************************************************************************* */

View File

@ -204,7 +204,7 @@ TEST ( NonlinearEquality, allow_error_optimize ) {
// verify
PoseValues expected;
expected.insert(key1, feasible1);
EXPECT(assert_equal(expected, *result.config()));
EXPECT(assert_equal(expected, *result.values()));
}
/* ************************************************************************* */
@ -240,7 +240,7 @@ TEST ( NonlinearEquality, allow_error_optimize_with_factors ) {
// verify
PoseValues expected;
expected.insert(key1, feasible1);
EXPECT(assert_equal(expected, *result.config()));
EXPECT(assert_equal(expected, *result.values()));
}
/* ************************************************************************* */

View File

@ -137,7 +137,7 @@ TEST( NonlinearOptimizer, iterateLM )
}
delete(pointer);
CHECK(assert_equal(*iterated1.config(), *iterated2.config(), 1e-9));
CHECK(assert_equal(*iterated1.values(), *iterated2.values(), 1e-9));
}
/* ************************************************************************* */
@ -170,12 +170,12 @@ TEST( NonlinearOptimizer, optimize )
// Gauss-Newton
Optimizer actual1 = optimizer.gaussNewton(relativeThreshold,
absoluteThreshold);
DOUBLES_EQUAL(0,fg->error(*(actual1.config())),tol);
DOUBLES_EQUAL(0,fg->error(*(actual1.values())),tol);
// Levenberg-Marquardt
Optimizer actual2 = optimizer.levenbergMarquardt(relativeThreshold,
absoluteThreshold, Optimizer::Parameters::SILENT);
DOUBLES_EQUAL(0,fg->error(*(actual2.config())),tol);
DOUBLES_EQUAL(0,fg->error(*(actual2.values())),tol);
}
/* ************************************************************************* */
@ -255,7 +255,7 @@ TEST( NonlinearOptimizer, Factorization )
Pose2Values expected;
expected.insert(1, Pose2(0.,0.,0.));
expected.insert(2, Pose2(1.,0.,0.));
CHECK(assert_equal(expected, *optimized.config(), 1e-5));
CHECK(assert_equal(expected, *optimized.values(), 1e-5));
}
///* ************************************************************************* */
@ -290,7 +290,7 @@ TEST( NonlinearOptimizer, Factorization )
// Values expected;
// expected.insert(1, Pose2(0., 0., 0.));
// expected.insert(2, Pose2(1., 0., 0.));
// CHECK(assert_equal(expected, *optimized.config(), 1e-5));
// CHECK(assert_equal(expected, *optimized.values(), 1e-5));
//}
/* ************************************************************************* */