#include <gtsam/base/lieProxies.h>
#include <gtsam/base/testLie.h>
#include <gtsam/geometry/Rot3.h>
#include <gtsam/geometry/SO3.h>
#include <gtsam/geometry/SO4.h>
#include <gtsam/nonlinear/GaussNewtonOptimizer.h>
#include <gtsam/nonlinear/NonlinearFactorGraph.h>
#include <gtsam/nonlinear/factorTesting.h>
#include <gtsam/sfm/ShonanFactor.h>
#include <gtsam/slam/FrobeniusFactor.h>
#include <CppUnitLite/TestHarness.h>
Go to the source code of this file.
Namespaces | |
so3 | |
submanifold | |
Functions | |
int | main () |
TEST (ShonanFactor3, evaluateError) | |
TEST (ShonanFactor3, equivalenceToSO3) | |
TEST (ShonanFactor2, evaluateError) | |
Variables | |
SO3 | so3::id |
SO4 | submanifold::id |
SO4 | submanifold::Q1 = SO4::Expmap(v1) |
SO4 | submanifold::Q2 = SO4::Expmap(v2) |
SO3 | so3::R1 = SO3::Expmap(v1) |
SO3 | submanifold::R1 = SO3::Expmap(v1.tail<3>()) |
SO3 | so3::R12 = R1.between(R2) |
SO3 | submanifold::R12 = R1.between(R2) |
SO3 | so3::R2 = SO3::Expmap(v2) |
SO3 | submanifold::R2 = SO3::Expmap(v2.tail<3>()) |
Vector3 | so3::v1 = (Vector(3) << 0.1, 0, 0).finished() |
Vector6 | submanifold::v1 = (Vector(6) << 0, 0, 0, 0.1, 0, 0).finished() |
Vector3 | so3::v2 = (Vector(3) << 0.01, 0.02, 0.03).finished() |
Vector6 | submanifold::v2 = (Vector(6) << 0, 0, 0, 0.01, 0.02, 0.03).finished() |
int main | ( | void | ) |
Definition at line 117 of file testShonanFactor.cpp.
TEST | ( | ShonanFactor3 | , |
evaluateError | |||
) |
Definition at line 60 of file testShonanFactor.cpp.
TEST | ( | ShonanFactor3 | , |
equivalenceToSO3 | |||
) |
Definition at line 81 of file testShonanFactor.cpp.
TEST | ( | ShonanFactor2 | , |
evaluateError | |||
) |
Definition at line 95 of file testShonanFactor.cpp.