params parsed correctly
parent
ff40590fc3
commit
90dd2c7035
|
@ -18,6 +18,7 @@
|
||||||
*/
|
*/
|
||||||
|
|
||||||
#include <gtsam/nonlinear/LevenbergMarquardtOptimizer.h>
|
#include <gtsam/nonlinear/LevenbergMarquardtOptimizer.h>
|
||||||
|
#include <gtsam/nonlinear/GaussNewtonOptimizer.h>
|
||||||
#include <gtsam/nonlinear/NonlinearFactorGraph.h>
|
#include <gtsam/nonlinear/NonlinearFactorGraph.h>
|
||||||
#include <tests/smallExample.h>
|
#include <tests/smallExample.h>
|
||||||
|
|
||||||
|
@ -37,25 +38,32 @@ public:
|
||||||
// using BaseOptimizer = BaseOptimizerParameters::OptimizerType;
|
// using BaseOptimizer = BaseOptimizerParameters::OptimizerType;
|
||||||
GncParams(const BaseOptimizerParameters& baseOptimizerParams): baseOptimizerParams(baseOptimizerParams) {}
|
GncParams(const BaseOptimizerParameters& baseOptimizerParams): baseOptimizerParams(baseOptimizerParams) {}
|
||||||
|
|
||||||
|
// default constructor
|
||||||
|
GncParams(): baseOptimizerParams() {}
|
||||||
|
|
||||||
BaseOptimizerParameters baseOptimizerParams;
|
BaseOptimizerParameters baseOptimizerParams;
|
||||||
|
|
||||||
/// any other specific GNC parameters:
|
/// any other specific GNC parameters:
|
||||||
};
|
};
|
||||||
|
|
||||||
/* ************************************************************************* */
|
/* ************************************************************************* */
|
||||||
//template <class GncParameters>
|
template<class GncParameters>
|
||||||
//class GncOptimizer {
|
class GncOptimizer {
|
||||||
// public:
|
public:
|
||||||
// // types etc
|
// types etc
|
||||||
//
|
|
||||||
// private:
|
private:
|
||||||
// FG INITIAL GncParameters params_;
|
NonlinearFactorGraph nfg_;
|
||||||
//
|
Values state_;
|
||||||
// public:
|
GncParameters params_;
|
||||||
// GncOptimizer(FG, INITIAL, const GncParameters& params) : params(params) {
|
|
||||||
// // Check that all noise models are Gaussian
|
public:
|
||||||
// }
|
GncOptimizer(const NonlinearFactorGraph& graph,
|
||||||
//
|
const Values& initialValues, const GncParameters& params = GncParameters()) :
|
||||||
|
nfg_(graph), state_(initialValues), params_(params) {
|
||||||
|
// TODO: Check that all noise models are Gaussian
|
||||||
|
}
|
||||||
|
|
||||||
// Values optimize() const {
|
// Values optimize() const {
|
||||||
// NonlinearFactorGraph currentGraph = graph_;
|
// NonlinearFactorGraph currentGraph = graph_;
|
||||||
// for (i : {1, 2, 3}) {
|
// for (i : {1, 2, 3}) {
|
||||||
|
@ -66,15 +74,15 @@ public:
|
||||||
// }
|
// }
|
||||||
// graph_i = this->makeGraph(currentSolution);
|
// graph_i = this->makeGraph(currentSolution);
|
||||||
// }
|
// }
|
||||||
// }
|
//}
|
||||||
//
|
|
||||||
// NonlinearFactorGraph makeGraph(const Values& currentSolution) const {
|
//NonlinearFactorGraph makeGraph(const Values& currentSolution) const {
|
||||||
// // calculate some weights
|
// // calculate some weights
|
||||||
// this->calculateWeights();
|
// this->calculateWeights();
|
||||||
// // copy the graph with new weights
|
// // copy the graph with new weights
|
||||||
//
|
//
|
||||||
// }
|
//}
|
||||||
//};
|
};
|
||||||
|
|
||||||
///* ************************************************************************* */
|
///* ************************************************************************* */
|
||||||
//TEST(GncOptimizer, calculateWeights) {
|
//TEST(GncOptimizer, calculateWeights) {
|
||||||
|
@ -84,6 +92,32 @@ public:
|
||||||
//TEST(GncOptimizer, copyGraph) {
|
//TEST(GncOptimizer, copyGraph) {
|
||||||
//}
|
//}
|
||||||
|
|
||||||
|
/* ************************************************************************* */
|
||||||
|
TEST(GncOptimizer, gncParamsConstructor) {
|
||||||
|
|
||||||
|
//check params are correctly parsed
|
||||||
|
LevenbergMarquardtParams lmParams;
|
||||||
|
GncParams<LevenbergMarquardtParams> gncParams1(lmParams);
|
||||||
|
CHECK(lmParams.equals(gncParams1.baseOptimizerParams));
|
||||||
|
|
||||||
|
// check also default constructor
|
||||||
|
GncParams<LevenbergMarquardtParams> gncParams1b;
|
||||||
|
CHECK(lmParams.equals(gncParams1b.baseOptimizerParams));
|
||||||
|
|
||||||
|
// and check params become different if we change lmParams
|
||||||
|
lmParams.setVerbosity("DELTA");
|
||||||
|
CHECK(!lmParams.equals(gncParams1.baseOptimizerParams));
|
||||||
|
|
||||||
|
// and same for GN
|
||||||
|
GaussNewtonParams gnParams;
|
||||||
|
GncParams<GaussNewtonParams> gncParams2(gnParams);
|
||||||
|
CHECK(gnParams.equals(gncParams2.baseOptimizerParams));
|
||||||
|
|
||||||
|
// check default constructor
|
||||||
|
GncParams<GaussNewtonParams> gncParams2b;
|
||||||
|
CHECK(gnParams.equals(gncParams2b.baseOptimizerParams));
|
||||||
|
}
|
||||||
|
|
||||||
/* ************************************************************************* */
|
/* ************************************************************************* */
|
||||||
TEST(GncOptimizer, makeGraph) {
|
TEST(GncOptimizer, makeGraph) {
|
||||||
// has to have Gaussian noise models !
|
// has to have Gaussian noise models !
|
||||||
|
@ -95,7 +129,7 @@ TEST(GncOptimizer, makeGraph) {
|
||||||
|
|
||||||
LevenbergMarquardtParams lmParams;
|
LevenbergMarquardtParams lmParams;
|
||||||
GncParams<LevenbergMarquardtParams> gncParams(lmParams);
|
GncParams<LevenbergMarquardtParams> gncParams(lmParams);
|
||||||
// auto gnc = GncOptimizer(fg, initial, gncParams);
|
auto gnc = GncOptimizer<GncParams<LevenbergMarquardtParams>>(fg, initial, gncParams);
|
||||||
|
|
||||||
// NonlinearFactorGraph actual = gnc.makeGraph(initial);
|
// NonlinearFactorGraph actual = gnc.makeGraph(initial);
|
||||||
}
|
}
|
||||||
|
|
Loading…
Reference in New Issue