replaced SimpleCamera with PinholeCamera and updated tests

release/4.3a0
Varun Agrawal 2020-07-27 21:25:27 -05:00
parent c8806dcb24
commit 95d3582c2e
6 changed files with 50 additions and 14 deletions

View File

@ -20,7 +20,7 @@ from gtsam.gtsam import (Cal3_S2, DoglegOptimizer,
GenericProjectionFactorCal3_S2, Marginals, GenericProjectionFactorCal3_S2, Marginals,
NonlinearFactorGraph, PinholeCameraCal3_S2, Point3, NonlinearFactorGraph, PinholeCameraCal3_S2, Point3,
Pose3, PriorFactorPoint3, PriorFactorPose3, Rot3, Pose3, PriorFactorPoint3, PriorFactorPose3, Rot3,
SimpleCamera, Values) PinholeCameraCal3_S2, Values)
from gtsam.utils import plot from gtsam.utils import plot

View File

@ -15,17 +15,18 @@ from __future__ import print_function
import unittest import unittest
import gtsam import gtsam
import numpy as np
from gtsam.gtsam.symbol_shorthand import X
from gtsam.utils.test_case import GtsamTestCase from gtsam.utils.test_case import GtsamTestCase
import numpy as np
def create_graph(): def create_graph():
"""Create a basic linear factor graph for testing""" """Create a basic linear factor graph for testing"""
graph = gtsam.GaussianFactorGraph() graph = gtsam.GaussianFactorGraph()
x0 = gtsam.symbol('x', 0) x0 = X(0)
x1 = gtsam.symbol('x', 1) x1 = X(1)
x2 = gtsam.symbol('x', 2) x2 = X(2)
BETWEEN_NOISE = gtsam.noiseModel.Diagonal.Sigmas(np.ones(1)) BETWEEN_NOISE = gtsam.noiseModel.Diagonal.Sigmas(np.ones(1))
PRIOR_NOISE = gtsam.noiseModel.Diagonal.Sigmas(np.ones(1)) PRIOR_NOISE = gtsam.noiseModel.Diagonal.Sigmas(np.ones(1))

View File

@ -15,10 +15,11 @@ from __future__ import print_function
import unittest import unittest
import gtsam import gtsam
from gtsam import (DoglegOptimizer, DoglegParams, GaussNewtonOptimizer, from gtsam import (DoglegOptimizer, DoglegParams,
DummyPreconditionerParameters, GaussNewtonOptimizer,
GaussNewtonParams, LevenbergMarquardtOptimizer, GaussNewtonParams, LevenbergMarquardtOptimizer,
LevenbergMarquardtParams, NonlinearFactorGraph, Ordering, LevenbergMarquardtParams, NonlinearFactorGraph, Ordering,
Point2, PriorFactorPoint2, Values) PCGSolverParameters, Point2, PriorFactorPoint2, Values)
from gtsam.utils.test_case import GtsamTestCase from gtsam.utils.test_case import GtsamTestCase
KEY1 = 1 KEY1 = 1
@ -61,6 +62,16 @@ class TestScenario(GtsamTestCase):
fg, initial_values, lmParams).optimize() fg, initial_values, lmParams).optimize()
self.assertAlmostEqual(0, fg.error(actual2)) self.assertAlmostEqual(0, fg.error(actual2))
# Levenberg-Marquardt
lmParams = LevenbergMarquardtParams.CeresDefaults()
lmParams.setLinearSolverType("ITERATIVE")
cgParams = PCGSolverParameters()
cgParams.setPreconditionerParams(DummyPreconditionerParameters())
lmParams.setIterativeParams(cgParams)
actual2 = LevenbergMarquardtOptimizer(
fg, initial_values, lmParams).optimize()
self.assertAlmostEqual(0, fg.error(actual2))
# Dogleg # Dogleg
dlParams = DoglegParams() dlParams = DoglegParams()
dlParams.setOrdering(ordering) dlParams.setOrdering(ordering)

View File

@ -35,5 +35,27 @@ class TestPriorFactor(GtsamTestCase):
values.insert(key, priorVector) values.insert(key, priorVector)
self.assertEqual(factor.error(values), 0) self.assertEqual(factor.error(values), 0)
def test_AddPrior(self):
"""
Test adding prior factors directly to factor graph via the .addPrior method.
"""
# define factor graph
graph = gtsam.NonlinearFactorGraph()
# define and add Pose3 prior
key = 5
priorPose3 = gtsam.Pose3()
model = gtsam.noiseModel.Unit.Create(6)
graph.addPriorPose3(key, priorPose3, model)
self.assertEqual(graph.size(), 1)
# define and add Vector prior
key = 3
priorVector = np.array([0., 0., 0.])
model = gtsam.noiseModel.Unit.Create(3)
graph.addPriorVector(key, priorVector, model)
self.assertEqual(graph.size(), 2)
if __name__ == "__main__": if __name__ == "__main__":
unittest.main() unittest.main()

View File

@ -15,6 +15,7 @@ import numpy as np
import gtsam import gtsam
import gtsam.utils.visual_data_generator as generator import gtsam.utils.visual_data_generator as generator
from gtsam import symbol from gtsam import symbol
from gtsam.gtsam.noiseModel improt Isotropic, Diagonal
from gtsam.utils.test_case import GtsamTestCase from gtsam.utils.test_case import GtsamTestCase
@ -34,7 +35,7 @@ class TestSFMExample(GtsamTestCase):
graph = gtsam.NonlinearFactorGraph() graph = gtsam.NonlinearFactorGraph()
# Add factors for all measurements # Add factors for all measurements
measurementNoise = gtsam.noiseModel.Isotropic.Sigma(2, measurementNoiseSigma) measurementNoise = Isotropic.Sigma(2, measurementNoiseSigma)
for i in range(len(data.Z)): for i in range(len(data.Z)):
for k in range(len(data.Z[i])): for k in range(len(data.Z[i])):
j = data.J[i][k] j = data.J[i][k]
@ -42,10 +43,10 @@ class TestSFMExample(GtsamTestCase):
data.Z[i][k], measurementNoise, data.Z[i][k], measurementNoise,
symbol('x', i), symbol('p', j), data.K)) symbol('x', i), symbol('p', j), data.K))
posePriorNoise = gtsam.noiseModel.Diagonal.Sigmas(poseNoiseSigmas) posePriorNoise = Diagonal.Sigmas(poseNoiseSigmas)
graph.add(gtsam.PriorFactorPose3(symbol('x', 0), graph.add(gtsam.PriorFactorPose3(symbol('x', 0),
truth.cameras[0].pose(), posePriorNoise)) truth.cameras[0].pose(), posePriorNoise))
pointPriorNoise = gtsam.noiseModel.Isotropic.Sigma(3, pointNoiseSigma) pointPriorNoise = Isotropic.Sigma(3, pointNoiseSigma)
graph.add(gtsam.PriorFactorPoint3(symbol('p', 0), graph.add(gtsam.PriorFactorPoint3(symbol('p', 0),
truth.points[0], pointPriorNoise)) truth.points[0], pointPriorNoise))

View File

@ -3,6 +3,7 @@ from __future__ import print_function
import numpy as np import numpy as np
from math import pi, cos, sin from math import pi, cos, sin
import gtsam import gtsam
from gtsam import PinholeCameraCal3_S2
class Options: class Options:
@ -99,10 +100,10 @@ def generate_data(options):
for i in range(options.nrCameras): for i in range(options.nrCameras):
theta = i * 2 * pi / options.nrCameras theta = i * 2 * pi / options.nrCameras
t = gtsam.Point3(r * cos(theta), r * sin(theta), height) t = gtsam.Point3(r * cos(theta), r * sin(theta), height)
truth.cameras[i] = gtsam.SimpleCamera.Lookat(t, truth.cameras[i] = PinholeCameraCal3_S2.Lookat(t,
gtsam.Point3(0, 0, 0), gtsam.Point3(0, 0, 0),
gtsam.Point3(0, 0, 1), gtsam.Point3(0, 0, 1),
truth.K) truth.K)
# Create measurements # Create measurements
for j in range(nrPoints): for j in range(nrPoints):
# All landmarks seen in every frame # All landmarks seen in every frame