InitializePose3.cpp
Go to the documentation of this file.
1 /* ----------------------------------------------------------------------------
2 
3  * GTSAM Copyright 2010, Georgia Tech Research Corporation,
4  * Atlanta, Georgia 30332-0415
5  * All Rights Reserved
6  * Authors: Frank Dellaert, et al. (see THANKS for the full author list)
7 
8  * See LICENSE for the license information
9 
10  * -------------------------------------------------------------------------- */
11 
20 
25 #include <gtsam/inference/Symbol.h>
26 #include <gtsam/geometry/Pose2.h>
27 #include <gtsam/geometry/Pose3.h>
28 #include <gtsam/base/timing.h>
29 
30 #include <boost/math/special_functions.hpp>
31 
32 #include <utility>
33 
34 using namespace std;
35 
36 namespace gtsam {
37 
38 /* ************************************************************************* */
40 
41  GaussianFactorGraph linearGraph;
42 
43  for(const auto& factor: g) {
44  Matrix3 Rij;
45  double rotationPrecision = 1.0;
46 
47  auto pose3Between = boost::dynamic_pointer_cast<BetweenFactor<Pose3> >(factor);
48  if (pose3Between){
49  Rij = pose3Between->measured().rotation().matrix();
50  Vector precisions = Vector::Zero(6);
51  precisions[0] = 1.0; // vector of all zeros except first entry equal to 1
52  pose3Between->noiseModel()->whitenInPlace(precisions); // gets marginal precision of first variable
53  rotationPrecision = precisions[0]; // rotations first
54  }else{
55  cout << "Error in buildLinearOrientationGraph" << endl;
56  }
57 
58  const auto& keys = factor->keys();
59  Key key1 = keys[0], key2 = keys[1];
60  Matrix M9 = Z_9x9;
61  M9.block(0,0,3,3) = Rij;
62  M9.block(3,3,3,3) = Rij;
63  M9.block(6,6,3,3) = Rij;
64  linearGraph.add(key1, -I_9x9, key2, M9, Z_9x1, noiseModel::Isotropic::Precision(9, rotationPrecision));
65  }
66  // prior on the anchor orientation
67  linearGraph.add(
69  (Vector(9) << 1.0, 0.0, 0.0, /* */ 0.0, 1.0, 0.0, /* */ 0.0, 0.0, 1.0)
70  .finished(),
71  noiseModel::Isotropic::Precision(9, 1));
72  return linearGraph;
73 }
74 
75 /* ************************************************************************* */
76 // Transform VectorValues into valid Rot3
77 Values InitializePose3::normalizeRelaxedRotations(
78  const VectorValues& relaxedRot3) {
79  gttic(InitializePose3_computeOrientationsChordal);
80 
81  Values validRot3;
82  for(const auto& it: relaxedRot3) {
83  Key key = it.first;
84  if (key != initialize::kAnchorKey) {
85  Matrix3 M;
86  M << Eigen::Map<const Matrix3>(it.second.data()); // Recover M from vectorized
87 
88  // ClosestTo finds rotation matrix closest to H in Frobenius sense
89  Rot3 initRot = Rot3::ClosestTo(M.transpose());
90  validRot3.insert(key, initRot);
91  }
92  }
93  return validRot3;
94 }
95 
96 /* ************************************************************************* */
97 NonlinearFactorGraph InitializePose3::buildPose3graph(
98  const NonlinearFactorGraph& graph) {
99  gttic(InitializePose3_buildPose3graph);
100  return initialize::buildPoseGraph<Pose3>(graph);
101 }
102 
103 /* ************************************************************************* */
104 Values InitializePose3::computeOrientationsChordal(
105  const NonlinearFactorGraph& pose3Graph) {
106  gttic(InitializePose3_computeOrientationsChordal);
107 
108  // regularize measurements and plug everything in a factor graph
109  GaussianFactorGraph relaxedGraph = buildLinearOrientationGraph(pose3Graph);
110 
111  // Solve the LFG
112  VectorValues relaxedRot3 = relaxedGraph.optimize();
113 
114  // normalize and compute Rot3
115  return normalizeRelaxedRotations(relaxedRot3);
116 }
117 
118 /* ************************************************************************* */
119 Values InitializePose3::computeOrientationsGradient(
120  const NonlinearFactorGraph& pose3Graph, const Values& givenGuess,
121  const size_t maxIter, const bool setRefFrame) {
122  gttic(InitializePose3_computeOrientationsGradient);
123 
124  // this works on the inverse rotations, according to Tron&Vidal,2011
125  Values inverseRot;
126  inverseRot.insert(initialize::kAnchorKey, Rot3());
127  for(const auto key_value: givenGuess) {
128  Key key = key_value.key;
129  const Pose3& pose = givenGuess.at<Pose3>(key);
130  inverseRot.insert(key, pose.rotation().inverse());
131  }
132 
133  // Create the map of edges incident on each node
134  KeyVectorMap adjEdgesMap;
135  KeyRotMap factorId2RotMap;
136 
137  createSymbolicGraph(pose3Graph, &adjEdgesMap, &factorId2RotMap);
138 
139  // calculate max node degree & allocate gradient
140  size_t maxNodeDeg = 0;
141  VectorValues grad;
142  for(const auto key_value: inverseRot) {
143  Key key = key_value.key;
144  grad.insert(key,Z_3x1);
145  size_t currNodeDeg = (adjEdgesMap.at(key)).size();
146  if(currNodeDeg > maxNodeDeg)
147  maxNodeDeg = currNodeDeg;
148  }
149 
150  // Create parameters
151  double b = 1;
152  double f0 = 1/b - (1/b + M_PI) * exp(-b*M_PI);
153  double a = (M_PI*M_PI)/(2*f0);
154  double rho = 2*a*b;
155  double mu_max = maxNodeDeg * rho;
156  double stepsize = 2/mu_max; // = 1/(a b dG)
157 
158  double maxGrad;
159  // gradient iterations
160  size_t it;
161  for (it = 0; it < maxIter; it++) {
163  // compute the gradient at each node
164  maxGrad = 0;
165  for (const auto key_value : inverseRot) {
166  Key key = key_value.key;
167  Vector gradKey = Z_3x1;
168  // collect the gradient for each edge incident on key
169  for (const size_t& factorId : adjEdgesMap.at(key)) {
170  Rot3 Rij = factorId2RotMap.at(factorId);
171  Rot3 Ri = inverseRot.at<Rot3>(key);
172  auto factor = pose3Graph.at(factorId);
173  const auto& keys = factor->keys();
174  if (key == keys[0]) {
175  Key key1 = keys[1];
176  Rot3 Rj = inverseRot.at<Rot3>(key1);
177  gradKey = gradKey + gradientTron(Ri, Rij * Rj, a, b);
178  } else if (key == keys[1]) {
179  Key key0 = keys[0];
180  Rot3 Rj = inverseRot.at<Rot3>(key0);
181  gradKey = gradKey + gradientTron(Ri, Rij.between(Rj), a, b);
182  } else {
183  cout << "Error in gradient computation" << endl;
184  }
185  } // end of i-th gradient computation
186  grad.at(key) = stepsize * gradKey;
187 
188  double normGradKey = (gradKey).norm();
189  if(normGradKey>maxGrad)
190  maxGrad = normGradKey;
191  } // end of loop over nodes
192 
194  // update estimates
195  inverseRot = inverseRot.retract(grad);
196 
198  // check stopping condition
199  if (it>20 && maxGrad < 5e-3)
200  break;
201  } // enf of gradient iterations
202 
203  // Return correct rotations
204  const Rot3& Rref = inverseRot.at<Rot3>(initialize::kAnchorKey); // This will be set to the identity as so far we included no prior
205  Values estimateRot;
206  for(const auto key_value: inverseRot) {
207  Key key = key_value.key;
208  if (key != initialize::kAnchorKey) {
209  const Rot3& R = inverseRot.at<Rot3>(key);
210  if(setRefFrame)
211  estimateRot.insert(key, Rref.compose(R.inverse()));
212  else
213  estimateRot.insert(key, R.inverse());
214  }
215  }
216  return estimateRot;
217 }
218 
219 /* ************************************************************************* */
220 void InitializePose3::createSymbolicGraph(
221  const NonlinearFactorGraph& pose3Graph, KeyVectorMap* adjEdgesMap,
222  KeyRotMap* factorId2RotMap) {
223  size_t factorId = 0;
224  for (const auto& factor : pose3Graph) {
225  auto pose3Between =
226  boost::dynamic_pointer_cast<BetweenFactor<Pose3> >(factor);
227  if (pose3Between) {
228  Rot3 Rij = pose3Between->measured().rotation();
229  factorId2RotMap->emplace(factorId, Rij);
230 
231  Key key1 = pose3Between->key1();
232  if (adjEdgesMap->find(key1) != adjEdgesMap->end()) { // key is already in
233  adjEdgesMap->at(key1).push_back(factorId);
234  } else {
235  vector<size_t> edge_id;
236  edge_id.push_back(factorId);
237  adjEdgesMap->emplace(key1, edge_id);
238  }
239  Key key2 = pose3Between->key2();
240  if (adjEdgesMap->find(key2) != adjEdgesMap->end()) { // key is already in
241  adjEdgesMap->at(key2).push_back(factorId);
242  } else {
243  vector<size_t> edge_id;
244  edge_id.push_back(factorId);
245  adjEdgesMap->emplace(key2, edge_id);
246  }
247  } else {
248  cout << "Error in createSymbolicGraph" << endl;
249  }
250  factorId++;
251  }
252 }
253 
254 /* ************************************************************************* */
255 Vector3 InitializePose3::gradientTron(const Rot3& R1, const Rot3& R2, const double a, const double b) {
256  Vector3 logRot = Rot3::Logmap(R1.between(R2));
257 
258  double th = logRot.norm();
259  if(th != th){ // the second case means that th = nan (logRot does not work well for +/-pi)
260  Rot3 R1pert = R1.compose( Rot3::Expmap(Vector3(0.01, 0.01, 0.01)) ); // some perturbation
261  logRot = Rot3::Logmap(R1pert.between(R2));
262  th = logRot.norm();
263  }
264  // exclude small or invalid rotations
265  if (th > 1e-5 && th == th) { // nonzero valid rotations
266  logRot = logRot / th;
267  } else {
268  logRot = Z_3x1;
269  th = 0.0;
270  }
271 
272  double fdot = a*b*th*exp(-b*th);
273  return fdot*logRot;
274 }
275 
276 /* ************************************************************************* */
278  // We "extract" the Pose3 subgraph of the original graph: this
279  // is done to properly model priors and avoiding operating on a larger graph
280  NonlinearFactorGraph pose3Graph = buildPose3graph(graph);
281 
282  // Get orientations from relative orientation measurements
283  return computeOrientationsChordal(pose3Graph);
284 }
285 
288  NonlinearFactorGraph* posegraph,
289  bool singleIter) {
290  gttic(InitializePose3_computePoses);
291  return initialize::computePoses<Pose3>(initialRot, posegraph, singleIter);
292 }
293 
294 /* ************************************************************************* */
296  const Values& givenGuess, bool useGradient) {
297  gttic(InitializePose3_initialize);
298  Values initialValues;
299 
300  // We "extract" the Pose3 subgraph of the original graph: this
301  // is done to properly model priors and avoiding operating on a larger graph
302  NonlinearFactorGraph pose3Graph = buildPose3graph(graph);
303 
304  // Get orientations from relative orientation measurements
305  Values orientations;
306  if (useGradient)
307  orientations = computeOrientationsGradient(pose3Graph, givenGuess);
308  else
309  orientations = computeOrientationsChordal(pose3Graph);
310 
311  // Compute the full poses (1 GN iteration on full poses)
312  return computePoses(orientations, &pose3Graph);
313 }
314 
315 /* ************************************************************************* */
317  return initialize(graph, Values(), false);
318 }
319 
320 } // namespace gtsam
Initialize Pose3 in a factor graph.
Matrix< RealScalar, Dynamic, Dynamic > M
Definition: bench_gemm.cpp:38
static const Eigen::MatrixBase< Vector3 >::ConstantReturnType Z_3x1
Definition: Vector.h:46
VectorValues optimize(const Eliminate &function=EliminationTraitsType::DefaultEliminate) const
Scalar * b
Definition: benchVecAdd.cpp:17
Eigen::Vector3d Vector3
Definition: Vector.h:43
EIGEN_DEVICE_FUNC const ExpReturnType exp() const
void insert(Key j, const Value &val)
Definition: Values.cpp:140
Eigen::MatrixXd Matrix
Definition: base/Matrix.h:43
common code between lago.* (2D) and InitializePose3.* (3D)
#define M_PI
Definition: main.h:78
Rot2 R(Rot2::fromAngle(0.1))
Pose2_ Expmap(const Vector3_ &xi)
Definition: Half.h:150
std::map< Key, Rot3 > KeyRotMap
const VALUE & measured() const
return the measurement
Vector & at(Key j)
Definition: VectorValues.h:137
NonlinearFactorGraph graph
static Values computePoses(const Values &initialRot, NonlinearFactorGraph *posegraph, bool singleIter=true)
void g(const string &key, int i)
Definition: testBTree.cpp:43
GaussianFactorGraph buildLinearOrientationGraph(const vector< size_t > &spanningTreeIds, const vector< size_t > &chordsIds, const NonlinearFactorGraph &g, const key2doubleMap &orientationsToRoot, const PredecessorMap< Key > &tree)
Definition: lago.cpp:161
Rot3 inverse() const
inverse of a rotation
Definition: Rot3.h:311
Array33i a
const Symbol key1('v', 1)
Scalar Scalar int size
Definition: benchVecAdd.cpp:17
std::map< Key, std::vector< size_t > > KeyVectorMap
#define gttic(label)
Definition: timing.h:280
void add(const GaussianFactor &factor)
Class compose(const Class &g) const
Definition: Lie.h:47
Eigen::VectorXd Vector
Definition: Vector.h:38
static const Pose3 pose(Rot3(Vector3(1,-1,-1).asDiagonal()), Point3(0, 0, 0.5))
Array< double, 1, 3 > e(1./3., 0.5, 2.)
VectorValues initializeOrientations(const NonlinearFactorGraph &graph, bool useOdometricPath)
Definition: lago.cpp:258
Q R1(Eigen::AngleAxisd(1, Q_z_axis))
traits
Definition: chartTesting.h:28
const sharedFactor at(size_t i) const
Definition: FactorGraph.h:315
std::vector< float > Values
const Symbol key2('v', 2)
static constexpr Key kAnchorKey
Class between(const Class &g) const
Definition: Lie.h:51
const KeyVector keys
2D Pose
3D Pose
Eigen::Matrix< double, Eigen::Dynamic, 1 > Vector
iterator insert(const std::pair< Key, Vector > &key_value)
Values initialize(const NonlinearFactorGraph &graph, bool useOdometricPath)
Definition: lago.cpp:338
Q R2(Eigen::AngleAxisd(2, Vector3(0, 1, 0)))
std::uint64_t Key
Integer nonlinear key type.
Definition: types.h:61
Timing utilities.
const Rot3 & rotation(OptionalJacobian< 3, 6 > Hself=boost::none) const
get rotation
Definition: Pose3.cpp:266


gtsam
Author(s):
autogenerated on Sat May 8 2021 02:42:14