2 GTSAM Copyright 2010-2019, Georgia Tech Research Corporation, 3 Atlanta, Georgia 30332-0415 6 See LICENSE for the license information 8 visual_isam unit tests. 9 Author: Frank Dellaert & Pablo Alcantarilla 16 from gtsam
import (EssentialMatrix, EssentialMatrixConstraint, Point3, Pose3,
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)
32 factor = EssentialMatrixConstraint(poseKey1, poseKey2, E, model)
35 pose1 =
Pose3(Rot3.RzRyRx(0.00, -0.15, 0.30),
Point3(-4.0, 7.0, -10.0))
37 Rot3.RzRyRx(0.179693265735950, 0.002945368776519,
39 Point3(-3.37493895, 6.14660244, -8.93650986))
41 expected = np.zeros((5, 1))
42 actual = factor.evaluateError(pose1, pose2)
46 if __name__ ==
"__main__":
def gtsamAssertEquals(self, actual, expected, tol=1e-9)
Key symbol(unsigned char c, std::uint64_t j)
def test_VisualISAMExample(self)
static shared_ptr Sigma(size_t dim, double sigma, bool smart=true)