testRot3Optimization.cpp
Go to the documentation of this file.
1 /* ----------------------------------------------------------------------------
2 
3  * GTSAM Copyright 2010, Georgia Tech Research Corporation,
4  * Atlanta, Georgia 30332-0415
5  * All Rights Reserved
6  * Authors: Frank Dellaert, et al. (see THANKS for the full author list)
7 
8  * See LICENSE for the license information
9 
10  * -------------------------------------------------------------------------- */
11 
19 #include <gtsam/base/Testable.h>
21 #include <gtsam/base/lieProxies.h>
22 #include <gtsam/geometry/Point3.h>
23 #include <gtsam/geometry/Rot3.h>
26 #include <gtsam/inference/Symbol.h>
28 
29 using namespace gtsam;
30 
33 
35 
36 /* ************************************************************************* */
38 
39  // Optimize a circle
40  Values truth;
42  Graph fg;
43  fg.addPrior(R(0), Rot3(), noiseModel::Isotropic::Sigma(3, 0.01));
44  for(int j=0; j<6; ++j) {
45  truth.insert(R(j), Rot3::Rz(M_PI/3.0 * double(j)));
46  initial.insert(R(j), Rot3::Rz(M_PI/3.0 * double(j) + 0.1 * double(j%2)));
47  fg.emplace_shared<Between>(R(j), R((j+1)%6), Rot3::Rz(M_PI/3.0), noiseModel::Isotropic::Sigma(3, 0.01));
48  }
49 
50  Values final = GaussNewtonOptimizer(fg, initial).optimize();
51 
52  EXPECT(assert_equal(truth, final, 1e-5));
53 }
54 
55 /* ************************************************************************* */
56 int main() {
57  TestResult tr;
58  return TestRegistry::runAllTests(tr);
59 }
60 /* ************************************************************************* */
virtual const Values & optimize()
Concept check for values that can be used in unit tests.
Provides convenient mappings of common member functions for testing.
IsDerived< DERIVEDFACTOR > emplace_shared(Args &&... args)
Emplace a shared pointer to factor of given type.
Definition: FactorGraph.h:196
static int runAllTests(TestResult &result)
Factor Graph consisting of non-linear factors.
bool assert_equal(const Matrix &expected, const Matrix &actual, double tol)
Definition: Matrix.cpp:40
#define M_PI
Definition: main.h:106
Rot2 R(Rot2::fromAngle(0.1))
Values initial
Some functions to compute numerical derivatives.
Rot3 is a 3D rotation represented as a rotation matrix if the preprocessor symbol GTSAM_USE_QUATERNIO...
Definition: Rot3.h:58
int main()
void addPrior(Key key, const T &prior, const SharedNoiseModel &model=nullptr)
#define EXPECT(condition)
Definition: Test.h:150
Point3 optimize(const NonlinearFactorGraph &graph, const Values &values, Key landmarkKey)
BetweenFactor< Rot3 > Between
Array< double, 1, 3 > e(1./3., 0.5, 2.)
NonlinearFactorGraph Graph
traits
Definition: chartTesting.h:28
Key R(std::uint64_t j)
static Rot3 Rz(double t)
Rotation around Z axis as in http://en.wikipedia.org/wiki/Rotation_matrix, counterclockwise when look...
Definition: Rot3M.cpp:74
3D Point
void insert(Key j, const Value &val)
Definition: Values.cpp:155
TEST(SmartFactorBase, Pinhole)
std::ptrdiff_t j
static shared_ptr Sigma(size_t dim, double sigma, bool smart=true)
Definition: NoiseModel.cpp:594
3D rotation represented as a rotation matrix or quaternion


gtsam
Author(s):
autogenerated on Tue Jul 4 2023 02:39:18