2 GTSAM Copyright 2010-2019, Georgia Tech Research Corporation, 3 Atlanta, Georgia 30332-0415 6 See LICENSE for the license information 21 """Test various GTSAM utilities.""" 23 """Test createKeyList.""" 26 self.assertEqual(kl.size(), 3)
29 self.assertEqual(kl.size(), 3)
32 """Test createKeyVector.""" 35 self.assertEqual(
len(kl), 3)
38 self.assertEqual(
len(kl), 3)
41 """Test createKeySet.""" 44 self.assertEqual(kl.size(), 3)
47 self.assertEqual(kl.size(), 3)
50 """Test extractPoint2.""" 54 initial.insert(2, point2)
56 point2.reshape(-1, 2))
59 """Test extractPoint3.""" 63 initial.insert(2, point3)
65 point3.reshape(-1, 3))
75 self.assertEqual(result.size(), 2)
78 """Test extractPose2.""" 80 pose2 = np.asarray((0.0, 0.1, 0.1))
95 self.assertEqual(result.size(), 2)
98 """Test extractPose3.""" 100 pose3 = np.asarray([1., 0., 0., 0., 1., 0., 0., 0., 1., 0., 0., 0.])
104 pose3.reshape(-1, 12))
107 """Test perturbPoint2.""" 113 not np.allclose(values.atPoint2(1),
gtsam.Point2(1, 1)))
116 """Test perturbPose2.""" 121 self.assertTrue(values.atPose2(0) !=
gtsam.Pose2())
124 """Test perturbPoint3.""" 128 values.insert(1, point3)
130 self.assertTrue(
not np.allclose(values.atPoint3(1), point3))
133 """Test insertBackprojections.""" 137 values, cam, [0, 1, 2], np.asarray([[20, 30, 40], [20, 30, 40]]),
139 np.testing.assert_allclose(values.atPoint3(0),
143 """Test insertProjectionFactors.""" 146 graph, 0, [0, 1], np.asarray([[20, 30], [20, 30]]),
148 self.assertEqual(graph.size(), 2)
152 graph, 0, [0, 1], np.asarray([[20, 30], [20, 30]]),
155 self.assertEqual(graph.size(), 2)
158 """Test reprojectionErrors.""" 159 pixels = np.asarray([[20, 30], [20, 30]])
170 np.testing.assert_allclose(errors, np.zeros((2, 2)))
173 """Test localToWorld.""" 182 np.testing.assert_allclose(world.atPoint2(0), expected_point2)
183 np.testing.assert_allclose(
184 world.atPose2(1).
matrix(), expected_pose2.matrix())
188 np.testing.assert_allclose(
189 world.atPose2(1).
matrix(), expected_pose2.matrix())
192 self.assertRaises(RuntimeError, world.atPoint2, 0)
195 if __name__ ==
"__main__":
void perturbPose2(Values &values, double sigmaT, double sigmaR, int32_t seed=42u)
Perturb all Pose2 values using normally distributed noise.
def test_insertProjectionFactors(self)
def test_createKeyList(self)
def test_createKeyVector(self)
FastList< Key > createKeyList(std::string s, const Vector &I)
void insertBackprojections(Values &values, const PinholeCamera< Cal3_S2 > &camera, const Vector &J, const Matrix &Z, double depth)
Insert a number of initial point values by backprojecting.
void perturbPoint2(Values &values, double sigma, int32_t seed=42u)
Perturb all Point2 values using normally distributed noise.
Matrix reprojectionErrors(const NonlinearFactorGraph &graph, const Values &values)
Calculate the errors of all projection factors in a graph.
Matrix extractPose3(const Values &values)
Extract all Pose3 values into a single matrix [r11 r12 r13 r21 r22 r23 r31 r32 r33 x y z]...
KeyVector createKeyVector(std::string s, const Vector &I)
void insertProjectionFactors(NonlinearFactorGraph &graph, Key i, const Vector &J, const Matrix &Z, const SharedNoiseModel &model, const Cal3_S2::shared_ptr K, const Pose3 &body_P_sensor=Pose3())
Insert multiple projection factors for a single pose key.
def test_createKeySet(self)
Rot3 is a 3D rotation represented as a rotation matrix if the preprocessor symbol GTSAM_USE_QUATERNIO...
Matrix extractPoint2(const Values &values)
Extract all Point2 values into a single matrix [x y].
def test_localToWorld(self)
KeySet createKeySet(std::string s, const Vector &I)
void perturbPoint3(Values &values, double sigma, int32_t seed=42u)
Perturb all Point3 values using normally distributed noise.
def test_perturbPoint2(self)
def test_insertBackprojections(self)
Values allPose3s(const Values &values)
Extract all Pose3 values.
The most common 5DOF 3D->2D calibration.
Values allPose2s(const Values &values)
Extract all Pose3 values.
Matrix extractPose2(const Values &values)
Extract all Pose2 values into a single matrix [x y theta].
def test_extractPose2(self)
def test_reprojectionErrors(self)
def test_extractPose3(self)
Values localToWorld(const Values &local, const Pose2 &base, const KeyVector user_keys=KeyVector())
Convert from local to world coordinates.
Map< Matrix< T, Dynamic, Dynamic, ColMajor >, 0, OuterStride<> > matrix(T *data, int rows, int cols, int stride)
def test_perturbPoint3(self)
def test_extractPoint3(self)
size_t len(handle h)
Get the length of a Python object.
def test_extractPoint2(self)
Matrix extractPoint3(const Values &values)
Extract all Point3 values into a single matrix [x y z].
static shared_ptr Sigma(size_t dim, double sigma, bool smart=true)
def test_perturbPose2(self)