clean up and formatting
parent
4a0257c0ce
commit
322a23d49c
|
@ -1,56 +1,52 @@
|
|||
/**
|
||||
* @file NonlinearConjugateGradientOptimizer.cpp
|
||||
* @brief Test simple CG optimizer
|
||||
* @file testNonlinearConjugateGradientOptimizer.cpp
|
||||
* @brief Test nonlinear CG optimizer
|
||||
* @author Yong-Dian Jian
|
||||
* @author Varun Agrawal
|
||||
* @date June 11, 2012
|
||||
*/
|
||||
|
||||
/**
|
||||
* @file testGradientDescentOptimizer.cpp
|
||||
* @brief Small test of NonlinearConjugateGradientOptimizer
|
||||
* @author Yong-Dian Jian
|
||||
* @date Jun 11, 2012
|
||||
*/
|
||||
|
||||
#include <gtsam/slam/BetweenFactor.h>
|
||||
#include <CppUnitLite/TestHarness.h>
|
||||
#include <gtsam/geometry/Pose2.h>
|
||||
#include <gtsam/nonlinear/NonlinearConjugateGradientOptimizer.h>
|
||||
#include <gtsam/nonlinear/NonlinearFactorGraph.h>
|
||||
#include <gtsam/nonlinear/Values.h>
|
||||
#include <gtsam/geometry/Pose2.h>
|
||||
|
||||
#include <CppUnitLite/TestHarness.h>
|
||||
|
||||
#include <gtsam/slam/BetweenFactor.h>
|
||||
|
||||
using namespace std;
|
||||
using namespace gtsam;
|
||||
|
||||
// Generate a small PoseSLAM problem
|
||||
std::tuple<NonlinearFactorGraph, Values> generateProblem() {
|
||||
|
||||
// 1. Create graph container and add factors to it
|
||||
NonlinearFactorGraph graph;
|
||||
|
||||
// 2a. Add Gaussian prior
|
||||
Pose2 priorMean(0.0, 0.0, 0.0); // prior at origin
|
||||
SharedDiagonal priorNoise = noiseModel::Diagonal::Sigmas(
|
||||
Vector3(0.3, 0.3, 0.1));
|
||||
Pose2 priorMean(0.0, 0.0, 0.0); // prior at origin
|
||||
SharedDiagonal priorNoise =
|
||||
noiseModel::Diagonal::Sigmas(Vector3(0.3, 0.3, 0.1));
|
||||
graph.addPrior(1, priorMean, priorNoise);
|
||||
|
||||
// 2b. Add odometry factors
|
||||
SharedDiagonal odometryNoise = noiseModel::Diagonal::Sigmas(
|
||||
Vector3(0.2, 0.2, 0.1));
|
||||
graph.emplace_shared<BetweenFactor<Pose2>>(1, 2, Pose2(2.0, 0.0, 0.0), odometryNoise);
|
||||
graph.emplace_shared<BetweenFactor<Pose2>>(2, 3, Pose2(2.0, 0.0, M_PI_2), odometryNoise);
|
||||
graph.emplace_shared<BetweenFactor<Pose2>>(3, 4, Pose2(2.0, 0.0, M_PI_2), odometryNoise);
|
||||
graph.emplace_shared<BetweenFactor<Pose2>>(4, 5, Pose2(2.0, 0.0, M_PI_2), odometryNoise);
|
||||
SharedDiagonal odometryNoise =
|
||||
noiseModel::Diagonal::Sigmas(Vector3(0.2, 0.2, 0.1));
|
||||
graph.emplace_shared<BetweenFactor<Pose2>>(1, 2, Pose2(2.0, 0.0, 0.0),
|
||||
odometryNoise);
|
||||
graph.emplace_shared<BetweenFactor<Pose2>>(2, 3, Pose2(2.0, 0.0, M_PI_2),
|
||||
odometryNoise);
|
||||
graph.emplace_shared<BetweenFactor<Pose2>>(3, 4, Pose2(2.0, 0.0, M_PI_2),
|
||||
odometryNoise);
|
||||
graph.emplace_shared<BetweenFactor<Pose2>>(4, 5, Pose2(2.0, 0.0, M_PI_2),
|
||||
odometryNoise);
|
||||
|
||||
// 2c. Add pose constraint
|
||||
SharedDiagonal constraintUncertainty = noiseModel::Diagonal::Sigmas(
|
||||
Vector3(0.2, 0.2, 0.1));
|
||||
SharedDiagonal constraintUncertainty =
|
||||
noiseModel::Diagonal::Sigmas(Vector3(0.2, 0.2, 0.1));
|
||||
graph.emplace_shared<BetweenFactor<Pose2>>(5, 2, Pose2(2.0, 0.0, M_PI_2),
|
||||
constraintUncertainty);
|
||||
constraintUncertainty);
|
||||
|
||||
// 3. Create the data structure to hold the initialEstimate estimate to the solution
|
||||
// 3. Create the data structure to hold the initialEstimate estimate to the
|
||||
// solution
|
||||
Values initialEstimate;
|
||||
Pose2 x1(0.5, 0.0, 0.2);
|
||||
initialEstimate.insert(1, x1);
|
||||
|
@ -68,16 +64,17 @@ std::tuple<NonlinearFactorGraph, Values> generateProblem() {
|
|||
|
||||
/* ************************************************************************* */
|
||||
TEST(NonlinearConjugateGradientOptimizer, Optimize) {
|
||||
const auto [graph, initialEstimate] = generateProblem();
|
||||
// cout << "initial error = " << graph.error(initialEstimate) << endl;
|
||||
const auto [graph, initialEstimate] = generateProblem();
|
||||
// cout << "initial error = " << graph.error(initialEstimate) << endl;
|
||||
|
||||
NonlinearOptimizerParams param;
|
||||
param.maxIterations = 500; /* requires a larger number of iterations to converge */
|
||||
param.maxIterations =
|
||||
500; /* requires a larger number of iterations to converge */
|
||||
param.verbosity = NonlinearOptimizerParams::SILENT;
|
||||
|
||||
NonlinearConjugateGradientOptimizer optimizer(graph, initialEstimate, param);
|
||||
Values result = optimizer.optimize();
|
||||
// cout << "cg final error = " << graph.error(result) << endl;
|
||||
// cout << "cg final error = " << graph.error(result) << endl;
|
||||
|
||||
EXPECT_DOUBLES_EQUAL(0.0, graph.error(result), 1e-4);
|
||||
}
|
||||
|
|
Loading…
Reference in New Issue