test_sam.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 Basis unit tests.
9 Author: Frank Dellaert & Varun Agrawal (Python)
10 """
11 import unittest
12 
13 import gtsam
14 from gtsam.utils.test_case import GtsamTestCase
15 
16 
18  """
19  Tests python binding for classes/functions in `sam.i`.
20  """
21  def test_RangeFactor2D(self):
22  """
23  Test that `measured` works as expected for RangeFactor2D.
24  """
25  measurement = 10.0
26  factor = gtsam.RangeFactor2D(1, 2, measurement,
28  self.assertEqual(measurement, factor.measured())
29 
31  """
32  Test that `measured` works as expected for BearingFactor2D.
33  """
34  measurement = gtsam.Rot2(.3)
35  factor = gtsam.BearingFactor2D(1, 2, measurement,
37  self.gtsamAssertEquals(measurement, factor.measured())
38 
40  """
41  Test that `measured` works as expected for BearingRangeFactor2D.
42  """
43  range_measurement = 10.0
44  bearing_measurement = gtsam.Rot2(0.3)
45  factor = gtsam.BearingRangeFactor2D(
46  1, 2, bearing_measurement, range_measurement,
48  measurement = factor.measured()
49 
50  self.assertEqual(range_measurement, measurement.range())
51  self.gtsamAssertEquals(bearing_measurement, measurement.bearing())
52 
54  """
55  Test that `measured` works as expected for BearingRangeFactor3D.
56  """
57  bearing_measurement = gtsam.Unit3()
58  range_measurement = 10.0
59  factor = gtsam.BearingRangeFactor3D(
60  1, 2, bearing_measurement, range_measurement,
62  measurement = factor.measured()
63 
64  self.assertEqual(range_measurement, measurement.range())
65  self.gtsamAssertEquals(bearing_measurement, measurement.bearing())
66 
68  """
69  Test that `measured` works as expected for BearingRangeFactorPose3.
70  """
71  range_measurement = 10.0
72  bearing_measurement = gtsam.Unit3()
73  factor = gtsam.BearingRangeFactorPose3(
74  1, 2, bearing_measurement, range_measurement,
76  measurement = factor.measured()
77 
78  self.assertEqual(range_measurement, measurement.range())
79  self.gtsamAssertEquals(bearing_measurement, measurement.bearing())
80 
81 
82 if __name__ == "__main__":
83  unittest.main()
test_sam.TestSam.test_RangeFactor2D
def test_RangeFactor2D(self)
Definition: test_sam.py:21
test_sam.TestSam.test_BearingRangeFactor3D
def test_BearingRangeFactor3D(self)
Definition: test_sam.py:53
gtsam::utils.test_case.GtsamTestCase.gtsamAssertEquals
def gtsamAssertEquals(self, actual, expected, tol=1e-9)
Definition: test_case.py:19
test_sam.TestSam
Definition: test_sam.py:17
test_sam.TestSam.test_BearingFactor2D
def test_BearingFactor2D(self)
Definition: test_sam.py:30
gtsam::utils.test_case
Definition: test_case.py:1
gtsam::Rot2
Definition: Rot2.h:35
test_sam.TestSam.test_BearingRangeFactorPose3
def test_BearingRangeFactorPose3(self)
Definition: test_sam.py:67
gtsam::utils.test_case.GtsamTestCase
Definition: test_case.py:16
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
test_sam.TestSam.test_BearingRangeFactor2D
def test_BearingRangeFactor2D(self)
Definition: test_sam.py:39


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