testEssentialMatrixConstraint.py
Go to the documentation of this file.
1 """
2 GTSAM Copyright 2010-2019, Georgia Tech Research Corporation,
3 Atlanta, Georgia 30332-0415
4 All Rights Reserved
5 
6 See LICENSE for the license information
7 
8 visual_isam unit tests.
9 Author: Frank Dellaert & Pablo Alcantarilla
10 """
11 
12 import unittest
13 
14 import gtsam
15 import numpy as np
16 from gtsam import (EssentialMatrix, EssentialMatrixConstraint, Point3, Pose3,
17  Rot3, Unit3, symbol)
18 from gtsam.utils.test_case import GtsamTestCase
19 
20 
23 
24  # Create a factor
25  poseKey1 = symbol('x', 1)
26  poseKey2 = symbol('x', 2)
27  trueRotation = Rot3.RzRyRx(0.15, 0.15, -0.20)
28  trueTranslation = Point3(+0.5, -1.0, +1.0)
29  trueDirection = Unit3(trueTranslation)
30  E = EssentialMatrix(trueRotation, trueDirection)
31  model = gtsam.noiseModel.Isotropic.Sigma(5, 0.25)
32  factor = EssentialMatrixConstraint(poseKey1, poseKey2, E, model)
33 
34  # Create a linearization point at the zero-error point
35  pose1 = Pose3(Rot3.RzRyRx(0.00, -0.15, 0.30), Point3(-4.0, 7.0, -10.0))
36  pose2 = Pose3(
37  Rot3.RzRyRx(0.179693265735950, 0.002945368776519,
38  0.102274823253840),
39  Point3(-3.37493895, 6.14660244, -8.93650986))
40 
41  expected = np.zeros((5, 1))
42  actual = factor.evaluateError(pose1, pose2)
43  self.gtsamAssertEquals(actual, expected, 1e-8)
44 
45 
46 if __name__ == "__main__":
47  unittest.main()
gtsam::utils.test_case.GtsamTestCase.gtsamAssertEquals
def gtsamAssertEquals(self, actual, expected, tol=1e-9)
Definition: test_case.py:19
gtsam::EssentialMatrix
Definition: EssentialMatrix.h:26
gtsam::Pose3
Definition: Pose3.h:37
testEssentialMatrixConstraint.TestVisualISAMExample
Definition: testEssentialMatrixConstraint.py:21
gtsam::EssentialMatrixConstraint
Definition: EssentialMatrixConstraint.h:30
gtsam::symbol
Key symbol(unsigned char c, std::uint64_t j)
Definition: inference/Symbol.h:139
gtsam::utils.test_case
Definition: test_case.py:1
gtsam::utils.test_case.GtsamTestCase
Definition: test_case.py:16
gtsam::Point3
Vector3 Point3
Definition: Point3.h:38
gtsam::noiseModel::Isotropic::Sigma
static shared_ptr Sigma(size_t dim, double sigma, bool smart=true)
Definition: NoiseModel.cpp:625
gtsam::Unit3
Represents a 3D point on a unit sphere.
Definition: Unit3.h:42
testEssentialMatrixConstraint.TestVisualISAMExample.test_VisualISAMExample
def test_VisualISAMExample(self)
Definition: testEssentialMatrixConstraint.py:22


gtsam
Author(s):
autogenerated on Sun Dec 22 2024 04:16:15