TranslationAveragingExample.py
Go to the documentation of this file.
1 """
2 GTSAM Copyright 2010-2018, 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 This example shows how 1dsfm uses outlier rejection (MFAS) and optimization (translation recovery)
10 together for estimating global translations from relative translation directions and global rotations.
11 The purpose of this example is to illustrate the connection between these two classes using a small SfM dataset.
12 
13 Author: Akshay Krishnan
14 Date: September 2020
15 """
16 
17 from collections import defaultdict
18 from typing import List, Tuple
19 
20 import gtsam
21 import numpy as np
22 from gtsam.examples import SFMdata
23 
24 # Hyperparameters for 1dsfm, values used from Kyle Wilson's code.
25 MAX_1DSFM_PROJECTION_DIRECTIONS = 48
26 OUTLIER_WEIGHT_THRESHOLD = 0.1
27 
28 
29 def get_data() -> Tuple[gtsam.Values, List[gtsam.BinaryMeasurementUnit3]]:
30  """"Returns global rotations and unit translation directions between 8 cameras
31  that lie on a circle and face the center. The poses of 8 cameras are obtained from SFMdata
32  and the unit translations directions between some camera pairs are computed from their
33  global translations. """
34  fx, fy, s, u0, v0 = 50.0, 50.0, 0.0, 50.0, 50.0
35  wTc_list = SFMdata.createPoses(gtsam.Cal3_S2(fx, fy, s, u0, v0))
36  # Rotations of the cameras in the world frame.
37  wRc_values = gtsam.Values()
38  # Normalized translation directions from camera i to camera j
39  # in the coordinate frame of camera i.
40  i_iZj_list = []
41  for i in range(0, len(wTc_list) - 2):
42  # Add the rotation.
43  wRi = wTc_list[i].rotation()
44  wRc_values.insert(i, wRi)
45  # Create unit translation measurements with next two poses.
46  for j in range(i + 1, i + 3):
47  # Compute the translation from pose i to pose j, in the world reference frame.
48  w_itj = wTc_list[j].translation() - wTc_list[i].translation()
49  # Obtain the translation in the camera i's reference frame.
50  i_itj = wRi.unrotate(w_itj)
51  # Compute the normalized unit translation direction.
52  i_iZj = gtsam.Unit3(i_itj)
53  i_iZj_list.append(gtsam.BinaryMeasurementUnit3(
54  i, j, i_iZj, gtsam.noiseModel.Isotropic.Sigma(3, 0.01)))
55  # Add the last two rotations.
56  wRc_values.insert(len(wTc_list) - 1, wTc_list[-1].rotation())
57  wRc_values.insert(len(wTc_list) - 2, wTc_list[-2].rotation())
58  return wRc_values, i_iZj_list
59 
60 
61 def filter_outliers(w_iZj_list: List[gtsam.BinaryMeasurementUnit3]) -> List[gtsam.BinaryMeasurementUnit3]:
62  """Removes outliers from a list of Unit3 measurements that are the
63  translation directions from camera i to camera j in the world frame."""
64 
65  # Indices of measurements that are to be used as projection directions.
66  # These are randomly chosen. All sampled directions must be unique.
67  num_directions_to_sample = min(
68  MAX_1DSFM_PROJECTION_DIRECTIONS, len(w_iZj_list))
69  sampled_indices = np.random.choice(
70  len(w_iZj_list), num_directions_to_sample, replace=False)
71 
72  # Sample projection directions from the measurements.
73  projection_directions = [w_iZj_list[idx].measured()
74  for idx in sampled_indices]
75 
76  outlier_weights = []
77  # Find the outlier weights for each direction using MFAS.
78  for direction in projection_directions:
79  algorithm = gtsam.MFAS(w_iZj_list, direction)
80  outlier_weights.append(algorithm.computeOutlierWeights())
81 
82  # Compute average of outlier weights. Each outlier weight is a map from a pair of Keys
83  # (camera IDs) to a weight, where weights are proportional to the probability of the edge
84  # being an outlier.
85  avg_outlier_weights = defaultdict(float)
86  for outlier_weight_dict in outlier_weights:
87  for keypair, weight in outlier_weight_dict.items():
88  avg_outlier_weights[keypair] += weight / len(outlier_weights)
89 
90  # Remove w_iZj that have weight greater than threshold, these are outliers.
91  w_iZj_inliers = []
92  [w_iZj_inliers.append(w_iZj) for w_iZj in w_iZj_list if avg_outlier_weights[(
93  w_iZj.key1(), w_iZj.key2())] < OUTLIER_WEIGHT_THRESHOLD]
94 
95  return w_iZj_inliers
96 
97 
98 def estimate_poses(i_iZj_list: List[gtsam.BinaryMeasurementUnit3],
99  wRc_values: gtsam.Values) -> gtsam.Values:
100  """Estimate poses given rotations and normalized translation directions between cameras.
101 
102  Args:
103  i_iZj_list: List of normalized translation direction measurements between camera pairs,
104  Z here refers to measurements. The measurements are of camera j with reference
105  to camera i (iZj), in camera i's coordinate frame (i_). iZj represents a unit
106  vector to j in i's frame and is not a transformation.
107  wRc_values: Rotations of the cameras in the world frame.
108 
109  Returns:
110  gtsam.Values: Estimated poses.
111  """
112 
113  # Convert the translation direction measurements to world frame using the rotations.
114  w_iZj_list = []
115  for i_iZj in i_iZj_list:
116  w_iZj = gtsam.Unit3(wRc_values.atRot3(i_iZj.key1())
117  .rotate(i_iZj.measured().point3()))
118  w_iZj_list.append(gtsam.BinaryMeasurementUnit3(
119  i_iZj.key1(), i_iZj.key2(), w_iZj, i_iZj.noiseModel()))
120 
121  # Remove the outliers in the unit translation directions.
122  w_iZj_inliers = filter_outliers(w_iZj_list)
123 
124  # Run the optimizer to obtain translations for normalized directions.
125  wtc_values = gtsam.TranslationRecovery().run(w_iZj_inliers)
126 
127  wTc_values = gtsam.Values()
128  for key in wRc_values.keys():
129  wTc_values.insert(key, gtsam.Pose3(
130  wRc_values.atRot3(key), wtc_values.atPoint3(key)))
131  return wTc_values
132 
133 
134 def main():
135  wRc_values, i_iZj_list = get_data()
136  wTc_values = estimate_poses(i_iZj_list, wRc_values)
137  print("**** Translation averaging output ****")
138  print(wTc_values)
139  print("**************************************")
140 
141 
142 if __name__ == '__main__':
143  main()
void print(const Matrix &A, const string &s, ostream &stream)
Definition: Matrix.cpp:155
Point2 measured(-17, 30)
Rot3_ rotation(const Pose3_ &pose)
#define min(a, b)
Definition: datatypes.h:19
Represents a 3D point on a unit sphere.
Definition: Unit3.h:42
Point3_ translation(const Pose3_ &pose)
Point3_ rotate(const Rot3_ &x, const Point3_ &p)
The most common 5DOF 3D->2D calibration.
Definition: Cal3_S2.h:34
Point3_ point3(const Unit3_ &v)
Double_ range(const Point2_ &p, const Point2_ &q)
size_t len(handle h)
Get the length of a Python object.
Definition: pytypes.h:2244
static shared_ptr Sigma(size_t dim, double sigma, bool smart=true)
Definition: NoiseModel.cpp:594


gtsam
Author(s):
autogenerated on Tue Jul 4 2023 02:40:22