Skip to content

Commit

Permalink
Move code shared between test into own file
Browse files Browse the repository at this point in the history
  • Loading branch information
RainerKuemmerle committed Dec 23, 2020
1 parent 9b3e19c commit 1b89597
Show file tree
Hide file tree
Showing 5 changed files with 116 additions and 55 deletions.
1 change: 1 addition & 0 deletions unit_test/general/CMakeLists.txt
Original file line number Diff line number Diff line change
@@ -1,4 +1,5 @@
add_executable(unittest_general
allocate_optimizer.cpp allocate_optimizer.h
graph_operations.cpp
clear_and_redo.cpp
)
Expand Down
49 changes: 49 additions & 0 deletions unit_test/general/allocate_optimizer.cpp
Original file line number Diff line number Diff line change
@@ -0,0 +1,49 @@
// g2o - General Graph Optimization
// Copyright (C) 2011 R. Kuemmerle, G. Grisetti, W. Burgard
// All rights reserved.
//
// Redistribution and use in source and binary forms, with or without
// modification, are permitted provided that the following conditions are
// met:
//
// * Redistributions of source code must retain the above copyright notice,
// this list of conditions and the following disclaimer.
// * Redistributions in binary form must reproduce the above copyright
// notice, this list of conditions and the following disclaimer in the
// documentation and/or other materials provided with the distribution.
//
// THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS
// IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED
// TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A
// PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT
// HOLDER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, INCIDENTAL,
// SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, BUT NOT LIMITED
// TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS OF USE, DATA, OR
// PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED AND ON ANY THEORY OF
// LIABILITY, WHETHER IN CONTRACT, STRICT LIABILITY, OR TORT (INCLUDING
// NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY OUT OF THE USE OF THIS
// SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE.

#include "g2o/core/block_solver.h"
#include "g2o/core/optimization_algorithm_gauss_newton.h"
#include "g2o/solvers/eigen/linear_solver_eigen.h"


namespace g2o {
namespace internal {

typedef g2o::BlockSolver<g2o::BlockSolverTraits<-1, -1> > SlamBlockSolver;
typedef g2o::LinearSolverEigen<SlamBlockSolver::PoseMatrixType> SlamLinearSolver;

g2o::SparseOptimizer* createOptimizerForTests() {
// Initialize the SparseOptimizer
g2o::SparseOptimizer* mOptimizer = new g2o::SparseOptimizer();
auto linearSolver = g2o::make_unique<SlamLinearSolver>();
linearSolver->setBlockOrdering(false);
auto blockSolver = g2o::make_unique<SlamBlockSolver>(std::move(linearSolver));
mOptimizer->setAlgorithm(new g2o::OptimizationAlgorithmGaussNewton(std::move(blockSolver)));
return mOptimizer;
}

} // namespace internal
} // namespace g2o
41 changes: 41 additions & 0 deletions unit_test/general/allocate_optimizer.h
Original file line number Diff line number Diff line change
@@ -0,0 +1,41 @@
// g2o - General Graph Optimization
// Copyright (C) 2011 R. Kuemmerle, G. Grisetti, W. Burgard
// All rights reserved.
//
// Redistribution and use in source and binary forms, with or without
// modification, are permitted provided that the following conditions are
// met:
//
// * Redistributions of source code must retain the above copyright notice,
// this list of conditions and the following disclaimer.
// * Redistributions in binary form must reproduce the above copyright
// notice, this list of conditions and the following disclaimer in the
// documentation and/or other materials provided with the distribution.
//
// THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS
// IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED
// TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A
// PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT
// HOLDER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, INCIDENTAL,
// SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, BUT NOT LIMITED
// TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS OF USE, DATA, OR
// PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED AND ON ANY THEORY OF
// LIABILITY, WHETHER IN CONTRACT, STRICT LIABILITY, OR TORT (INCLUDING
// NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY OUT OF THE USE OF THIS
// SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE.

#ifndef G2O_TEST_ALLOCATE_OPTIMIZER_H
#define G2O_TEST_ALLOCATE_OPTIMIZER_H

namespace g2o {

class SparseOptimizer;

namespace internal {

g2o::SparseOptimizer* createOptimizerForTests();

} // namespace internal
} // namespace g2o

#endif
44 changes: 17 additions & 27 deletions unit_test/general/clear_and_redo.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -24,60 +24,51 @@
// NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY OUT OF THE USE OF THIS
// SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE.

#include "gtest/gtest.h"

#include "g2o/core/block_solver.h"
#include "g2o/core/optimization_algorithm_gauss_newton.h"
#include "g2o/types/slam3d/types_slam3d.h"
#include "g2o/solvers/eigen/linear_solver_eigen.h"
#include "allocate_optimizer.h"
#include "g2o/core/sparse_optimizer.h"
#include "g2o/core/sparse_optimizer_terminate_action.h"
#include "g2o/types/slam3d/types_slam3d.h"
#include "gtest/gtest.h"

typedef g2o::BlockSolver< g2o::BlockSolverTraits<-1, -1> > SlamBlockSolver;
typedef g2o::LinearSolverEigen<SlamBlockSolver::PoseMatrixType> SlamLinearSolver;

TEST(General, ClearAndRedo)
{
TEST(General, ClearAndRedo) {
// Initialize the SparseOptimizer
g2o::SparseOptimizer mOptimizer;
auto linearSolver = g2o::make_unique<SlamLinearSolver>();
linearSolver->setBlockOrdering(false);
auto blockSolver = g2o::make_unique<SlamBlockSolver>(std::move(linearSolver));
mOptimizer.setAlgorithm(new g2o::OptimizationAlgorithmGaussNewton(std::move(blockSolver)));
std::unique_ptr<g2o::SparseOptimizer> mOptimizerPtr;
mOptimizerPtr.reset(g2o::internal::createOptimizerForTests());
g2o::SparseOptimizer& mOptimizer = *mOptimizerPtr;

// Set the default terminate action
g2o::SparseOptimizerTerminateAction* terminateAction = new g2o::SparseOptimizerTerminateAction;
mOptimizer.addPostIterationAction(terminateAction);

for(int i = 0; i < 2; i++)
{
for (int i = 0; i < 2; i++) {
// Add vertices
g2o::VertexSE3* v0 = new g2o::VertexSE3;
v0->setEstimate(Eigen::Transform<number_t,3,1>(Eigen::Translation<number_t, 3>(0,0,0)));
v0->setEstimate(Eigen::Transform<number_t, 3, 1>(Eigen::Translation<number_t, 3>(0, 0, 0)));
v0->setId(0);
mOptimizer.addVertex(v0);

g2o::VertexSE3* v1 = new g2o::VertexSE3;
v1->setEstimate(Eigen::Transform<number_t,3,1>(Eigen::Translation<number_t, 3>(0,0,0)));
v1->setEstimate(Eigen::Transform<number_t, 3, 1>(Eigen::Translation<number_t, 3>(0, 0, 0)));
v1->setId(1);
mOptimizer.addVertex(v1);

g2o::VertexSE3* v2 = new g2o::VertexSE3;
v2->setEstimate(Eigen::Transform<number_t,3,1>(Eigen::Translation<number_t, 3>(0,0,0)));
v2->setEstimate(Eigen::Transform<number_t, 3, 1>(Eigen::Translation<number_t, 3>(0, 0, 0)));
v2->setId(2);
mOptimizer.addVertex(v2);

// Add edges
g2o::EdgeSE3* e1 = new g2o::EdgeSE3();
e1->vertices()[0] = mOptimizer.vertex(0);
e1->vertices()[1] = mOptimizer.vertex(1);
e1->setMeasurement(g2o::Isometry3(Eigen::Translation<number_t, 3>(1,0,0)));
e1->setMeasurement(g2o::Isometry3(Eigen::Translation<number_t, 3>(1, 0, 0)));
e1->setInformation(g2o::MatrixN<6>::Identity());
mOptimizer.addEdge(e1);

g2o::EdgeSE3* e2 = new g2o::EdgeSE3();
e2->vertices()[0] = mOptimizer.vertex(1);
e2->vertices()[1] = mOptimizer.vertex(2);
e2->setMeasurement(g2o::Isometry3(Eigen::Translation<number_t, 3>(0,1,0)));
e2->setMeasurement(g2o::Isometry3(Eigen::Translation<number_t, 3>(0, 1, 0)));
e2->setInformation(g2o::MatrixN<6>::Identity());
mOptimizer.addEdge(e2);

Expand All @@ -90,14 +81,13 @@ TEST(General, ClearAndRedo)

v0->setFixed(true);

//mOptimizer.setVerbose(true);
// mOptimizer.setVerbose(true);
mOptimizer.initializeOptimization();
mOptimizer.computeInitialGuess();
mOptimizer.computeActiveErrors();
int iter = mOptimizer.optimize(10);
if (iter <= 0)
{
ADD_FAILURE();
if (iter <= 0) {
ADD_FAILURE() << "Optimization did not happen";
} else {
SUCCEED();
}
Expand Down
36 changes: 8 additions & 28 deletions unit_test/general/graph_operations.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -26,44 +26,24 @@

#include <numeric>

#include "g2o/core/block_solver.h"
#include "allocate_optimizer.h"
#include "g2o/core/factory.h"
#include "g2o/core/optimization_algorithm_gauss_newton.h"
#include "g2o/solvers/eigen/linear_solver_eigen.h"
#include "g2o/core/sparse_optimizer.h"
#include "g2o/stuff/string_tools.h"
#include "g2o/types/slam2d/types_slam2d.h"
#include "g2o/types/slam3d/types_slam3d.h"
#include "gmock/gmock.h"
#include "gtest/gtest.h"

typedef g2o::BlockSolver<g2o::BlockSolverTraits<-1, -1>> SlamBlockSolver;
typedef g2o::LinearSolverEigen<SlamBlockSolver::PoseMatrixType> SlamLinearSolver;

G2O_USE_TYPE_GROUP(slam2d);
G2O_USE_TYPE_GROUP(slam3d);

static g2o::SparseOptimizer* createOptimizer() {
// Initialize the SparseOptimizer
g2o::SparseOptimizer* mOptimizer = new g2o::SparseOptimizer();
auto linearSolver = g2o::make_unique<SlamLinearSolver>();
linearSolver->setBlockOrdering(false);
auto blockSolver = g2o::make_unique<SlamBlockSolver>(std::move(linearSolver));
mOptimizer->setAlgorithm(new g2o::OptimizationAlgorithmGaussNewton(std::move(blockSolver)));
return mOptimizer;
}

TEST(General, BinaryEdgeConstructor) {
g2o::EdgeSE3 e1;
ASSERT_EQ(NULL, e1.vertices()[0]);
ASSERT_EQ(NULL, e1.vertices()[1]);

g2o::EdgeSE2 e2;
ASSERT_EQ(NULL, e2.vertices()[0]);
ASSERT_EQ(NULL, e2.vertices()[1]);
ASSERT_EQ(nullptr, e2.vertices()[0]);
ASSERT_EQ(nullptr, e2.vertices()[1]);
}

TEST(General, GraphAddVertex) {
g2o::SparseOptimizer* optimizer = createOptimizer();
g2o::SparseOptimizer* optimizer = g2o::internal::createOptimizerForTests();

g2o::VertexSE2* v1 = new g2o::VertexSE2();
v1->setId(0);
Expand All @@ -78,15 +58,15 @@ TEST(General, GraphAddVertex) {
v2->setId(0);
ASSERT_FALSE(optimizer->addVertex(v2));
ASSERT_EQ(size_t(1), optimizer->vertices().size());
ASSERT_EQ(NULL, v2->graph());
ASSERT_EQ(nullptr, v2->graph());
delete v2;
}

delete optimizer;
}

TEST(General, GraphAddEdge) {
g2o::SparseOptimizer* optimizer = createOptimizer();
g2o::SparseOptimizer* optimizer = g2o::internal::createOptimizerForTests();

g2o::VertexSE2* v1 = new g2o::VertexSE2();
v1->setId(0);
Expand Down Expand Up @@ -129,7 +109,7 @@ TEST(General, GraphAddEdge) {
class GeneralGraphLoadSave : public ::testing::Test {
protected:
void SetUp() override {
optimizer.reset(createOptimizer());
optimizer.reset(g2o::internal::createOptimizerForTests());

// Add vertices
for (int i = 0; i < numVertices; ++i) {
Expand Down

0 comments on commit 1b89597

Please sign in to comment.