test_lago.py
Go to the documentation of this file.
1 """
2 GTSAM Copyright 2010, Georgia Tech Research Corporation,
3 Atlanta, Georgia 30332-0415
4 All Rights Reserved
5 Authors: Frank Dellaert, et al. (see THANKS for the full author list)
6 See LICENSE for the license information
7 
8 Author: John Lambert (Python)
9 """
10 
11 import unittest
12 
13 import numpy as np
14 
15 import gtsam
16 from gtsam import BetweenFactorPose2, Point3, Pose2, PriorFactorPose2, Values
17 
18 
19 class TestLago(unittest.TestCase):
20  """Test selected LAGO methods."""
21 
22  def test_initialize(self) -> None:
23  """Smokescreen to ensure LAGO can be imported and run on toy data stored in a g2o file."""
24  g2oFile = gtsam.findExampleDataFile("noisyToyGraph.txt")
25 
27  graph, initial = gtsam.readG2o(g2oFile)
28 
29  # Add prior on the pose having index (key) = 0
30  priorModel = gtsam.noiseModel.Diagonal.Variances(Point3(1e-6, 1e-6, 1e-8))
31  graph.add(PriorFactorPose2(0, Pose2(), priorModel))
32 
33  estimateLago: Values = gtsam.lago.initialize(graph)
34  assert isinstance(estimateLago, Values)
35 
36  def test_initialize2(self) -> None:
37  """Smokescreen to ensure LAGO can be imported and run on toy data stored in a g2o file."""
38  # 1. Create a NonlinearFactorGraph with Pose2 factors
40 
41  # Add a prior on the first pose
42  prior_mean = Pose2(0.0, 0.0, 0.0)
43  prior_noise = gtsam.noiseModel.Diagonal.Sigmas(np.array([0.1, 0.1, 0.05]))
44  graph.add(PriorFactorPose2(0, prior_mean, prior_noise))
45 
46  # Add odometry factors (simulating moving in a square)
47  odometry_noise = gtsam.noiseModel.Diagonal.Sigmas(np.array([0.2, 0.2, 0.1]))
48  graph.add(BetweenFactorPose2(0, 1, Pose2(2.0, 0.0, 0.0), odometry_noise))
49  graph.add(BetweenFactorPose2(1, 2, Pose2(2.0, 0.0, np.pi / 2), odometry_noise))
50  graph.add(BetweenFactorPose2(2, 3, Pose2(2.0, 0.0, np.pi / 2), odometry_noise))
51  graph.add(BetweenFactorPose2(3, 4, Pose2(2.0, 0.0, np.pi / 2), odometry_noise))
52 
53  # Add a loop closure factor
54  loop_noise = gtsam.noiseModel.Diagonal.Sigmas(np.array([0.25, 0.25, 0.15]))
55  # Ideal loop closure would be Pose2(2.0, 0.0, np.pi/2)
56  measured_loop = Pose2(2.1, 0.1, np.pi / 2 + 0.05)
57  graph.add(BetweenFactorPose2(4, 0, measured_loop, loop_noise))
58 
59  estimateLago: Values = gtsam.lago.initialize(graph)
60  assert isinstance(estimateLago, Values)
61 
62 
63 if __name__ == "__main__":
64  unittest.main()
gtsam::lago::initialize
Values initialize(const NonlinearFactorGraph &graph, const Values &initialGuess)
Definition: lago.cpp:391
gtsam::readG2o
GraphAndValues readG2o(const std::string &g2oFile, const bool is3D, KernelFunctionType kernelFunctionType)
This function parses a g2o file and stores the measurements into a NonlinearFactorGraph and the initi...
Definition: dataset.cpp:621
test_lago.TestLago.test_initialize2
None test_initialize2(self)
Definition: test_lago.py:36
gtsam::noiseModel::Diagonal::Sigmas
static shared_ptr Sigmas(const Vector &sigmas, bool smart=true)
Definition: NoiseModel.cpp:283
PriorFactorPose2
PriorFactor< Pose2 > PriorFactorPose2
Definition: serialization.cpp:37
isinstance
bool isinstance(handle obj)
Definition: pytypes.h:842
gtsam::NonlinearFactorGraph
Definition: NonlinearFactorGraph.h:55
BetweenFactorPose2
BetweenFactor< Pose2 > BetweenFactorPose2
Definition: serialization.cpp:49
test_lago.TestLago
Definition: test_lago.py:19
gtsam::Point3
Vector3 Point3
Definition: Point3.h:38
gtsam::findExampleDataFile
GTSAM_EXPORT std::string findExampleDataFile(const std::string &name)
Definition: dataset.cpp:70
test_lago.TestLago.test_initialize
None test_initialize(self)
Definition: test_lago.py:22
gtsam::noiseModel::Diagonal::Variances
static shared_ptr Variances(const Vector &variances, bool smart=true)
Definition: NoiseModel.cpp:275
gtsam::Pose2
Definition: Pose2.h:39


gtsam
Author(s):
autogenerated on Wed May 28 2025 03:06:00