test_VisualISAMExample.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 & Duy Nguyen Ta (Python)
10 """
11 import unittest
12 
13 import gtsam.utils.visual_data_generator as generator
14 import gtsam.utils.visual_isam as visual_isam
15 from gtsam import symbol
16 from gtsam.utils.test_case import GtsamTestCase
17 
18 
20  """Test class for ISAM2 with visual landmarks."""
22  """Test to see if ISAM works as expected for a simple visual SLAM example."""
23  # Data Options
24  options = generator.Options()
25  options.triangle = False
26  options.nrCameras = 20
27 
28  # iSAM Options
29  isamOptions = visual_isam.Options()
30  isamOptions.hardConstraint = False
31  isamOptions.pointPriors = False
32  isamOptions.batchInitialization = True
33  isamOptions.reorderInterval = 10
34  isamOptions.alwaysRelinearize = False
35 
36  # Generate data
37  data, truth = generator.generate_data(options)
38 
39  # Initialize iSAM with the first pose and points
40  isam, result, nextPose = visual_isam.initialize(
41  data, truth, isamOptions)
42 
43  # Main loop for iSAM: stepping through all poses
44  for currentPose in range(nextPose, options.nrCameras):
45  isam, result = visual_isam.step(data, isam, result, truth,
46  currentPose)
47 
48  for i, _ in enumerate(truth.cameras):
49  pose_i = result.atPose3(symbol('x', i))
50  self.gtsamAssertEquals(pose_i, truth.cameras[i].pose(), 1e-5)
51 
52  for j, _ in enumerate(truth.points):
53  point_j = result.atPoint3(symbol('l', j))
54  self.gtsamAssertEquals(point_j, truth.points[j], 1e-5)
55 
56 
57 if __name__ == "__main__":
58  unittest.main()
def gtsamAssertEquals(self, actual, expected, tol=1e-9)
Definition: test_case.py:18
Key symbol(unsigned char c, std::uint64_t j)
static const Pose3 pose(Rot3(Vector3(1, -1, -1).asDiagonal()), Point3(0, 0, 0.5))
Double_ range(const Point2_ &p, const Point2_ &q)


gtsam
Author(s):
autogenerated on Tue Jul 4 2023 02:37:46