VisualISAMExample.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 
7 See LICENSE for the license information
8 
9 A visualSLAM example for the structure-from-motion problem on a simulated dataset
10 This version uses iSAM to solve the problem incrementally
11 """
12 
13 from __future__ import print_function
14 
15 import numpy as np
16 import gtsam
17 from gtsam.examples import SFMdata
18 from gtsam import (Cal3_S2, GenericProjectionFactorCal3_S2,
19  NonlinearFactorGraph, NonlinearISAM, Pose3,
20  PriorFactorPoint3, PriorFactorPose3, Rot3,
21  PinholeCameraCal3_S2, Values, Point3)
22 from gtsam.symbol_shorthand import X, L
23 
24 def main():
25  """
26  A structure-from-motion example with landmarks
27  - The landmarks form a 10 meter cube
28  - The robot rotates around the landmarks, always facing towards the cube
29  """
30 
31  # Define the camera calibration parameters
32  K = Cal3_S2(50.0, 50.0, 0.0, 50.0, 50.0)
33 
34  # Define the camera observation noise model
35  camera_noise = gtsam.noiseModel.Isotropic.Sigma(
36  2, 1.0) # one pixel in u and v
37 
38  # Create the set of ground-truth landmarks
39  points = SFMdata.createPoints()
40  # Create the set of ground-truth poses
41  poses = SFMdata.createPoses(K)
42 
43  # Create a NonlinearISAM object which will relinearize and reorder the variables
44  # every "reorderInterval" updates
45  isam = NonlinearISAM(reorderInterval=3)
46 
47  # Create a Factor Graph and Values to hold the new data
48  graph = NonlinearFactorGraph()
49  initial_estimate = Values()
50 
51  # Loop over the different poses, adding the observations to iSAM incrementally
52  for i, pose in enumerate(poses):
53  camera = PinholeCameraCal3_S2(pose, K)
54  # Add factors for each landmark observation
55  for j, point in enumerate(points):
56  measurement = camera.project(point)
58  measurement, camera_noise, X(i), L(j), K)
59  graph.push_back(factor)
60 
61  # Intentionally initialize the variables off from the ground truth
62  noise = Pose3(r=Rot3.Rodrigues(-0.1, 0.2, 0.25),
63  t=Point3(0.05, -0.10, 0.20))
64  initial_xi = pose.compose(noise)
65 
66  # Add an initial guess for the current pose
67  initial_estimate.insert(X(i), initial_xi)
68 
69  # If this is the first iteration, add a prior on the first pose to set the coordinate frame
70  # and a prior on the first landmark to set the scale
71  # Also, as iSAM solves incrementally, we must wait until each is observed at least twice before
72  # adding it to iSAM.
73  if i == 0:
74  # Add a prior on pose x0, with 0.3 rad std on roll,pitch,yaw and 0.1m x,y,z
76  np.array([0.3, 0.3, 0.3, 0.1, 0.1, 0.1]))
77  factor = PriorFactorPose3(X(0), poses[0], pose_noise)
78  graph.push_back(factor)
79 
80  # Add a prior on landmark l0
81  point_noise = gtsam.noiseModel.Isotropic.Sigma(3, 0.1)
82  factor = PriorFactorPoint3(L(0), points[0], point_noise)
83  graph.push_back(factor)
84 
85  # Add initial guesses to all observed landmarks
86  noise = np.array([-0.25, 0.20, 0.15])
87  for j, point in enumerate(points):
88  # Intentionally initialize the variables off from the ground truth
89  initial_lj = points[j] + noise
90  initial_estimate.insert(L(j), initial_lj)
91  else:
92  # Update iSAM with the new factors
93  isam.update(graph, initial_estimate)
94  current_estimate = isam.estimate()
95  print('*' * 50)
96  print('Frame {}:'.format(i))
97  current_estimate.print_('Current estimate: ')
98 
99  # Clear the factor graph and values for the next iteration
100  graph.resize(0)
101  initial_estimate.clear()
102 
103 
104 if __name__ == '__main__':
105  main()
void print(const Matrix &A, const string &s, ostream &stream)
Definition: Matrix.cpp:155
MatrixXd L
Definition: LLT_example.cpp:6
static shared_ptr Sigmas(const Vector &sigmas, bool smart=true)
Definition: NoiseModel.cpp:270
#define X
Definition: icosphere.cpp:20
static shared_ptr Sigma(size_t dim, double sigma, bool smart=true)
Definition: NoiseModel.cpp:567


gtsam
Author(s):
autogenerated on Sat May 8 2021 02:51:25