2 GTSAM Copyright 2010-2018, Georgia Tech Research Corporation, 3 Atlanta, Georgia 30332-0415 5 Authors: Frank Dellaert, et al. (see THANKS for the full author list) 7 See LICENSE for the license information 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. 13 Author: Akshay Krishnan 17 from collections
import defaultdict
18 from typing
import List, Tuple
25 MAX_1DSFM_PROJECTION_DIRECTIONS = 48
26 OUTLIER_WEIGHT_THRESHOLD = 0.1
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))
41 for i
in range(0,
len(wTc_list) - 2):
44 wRc_values.insert(i, wRi)
46 for j
in range(i + 1, i + 3):
50 i_itj = wRi.unrotate(w_itj)
53 i_iZj_list.append(gtsam.BinaryMeasurementUnit3(
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
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.""" 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)
73 projection_directions = [w_iZj_list[idx].
measured()
74 for idx
in sampled_indices]
78 for direction
in projection_directions:
80 outlier_weights.append(algorithm.computeOutlierWeights())
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)
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]
100 """Estimate poses given rotations and normalized translation directions between cameras. 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. 110 gtsam.Values: Estimated poses. 115 for i_iZj
in i_iZj_list:
116 w_iZj =
gtsam.Unit3(wRc_values.atRot3(i_iZj.key1())
118 w_iZj_list.append(gtsam.BinaryMeasurementUnit3(
119 i_iZj.key1(), i_iZj.key2(), w_iZj, i_iZj.noiseModel()))
128 for key
in wRc_values.keys():
130 wRc_values.atRot3(key), wtc_values.atPoint3(key)))
137 print(
"**** Translation averaging output ****")
139 print(
"**************************************")
142 if __name__ ==
'__main__':
void print(const Matrix &A, const string &s, ostream &stream)
Rot3_ rotation(const Pose3_ &pose)
Represents a 3D point on a unit sphere.
Point3_ translation(const Pose3_ &pose)
Point3_ rotate(const Rot3_ &x, const Point3_ &p)
The most common 5DOF 3D->2D calibration.
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.
static shared_ptr Sigma(size_t dim, double sigma, bool smart=true)