lago.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 
19 #include <gtsam/slam/lago.h>
20 
24 #include <gtsam/inference/Symbol.h>
25 #include <gtsam/geometry/Pose2.h>
26 #include <gtsam/base/timing.h>
27 
28 #include <boost/math/special_functions.hpp>
29 
30 using namespace std;
31 
32 namespace gtsam {
33 namespace lago {
34 
35 static const Matrix I = I_1x1;
36 static const Matrix I3 = I_3x3;
37 
39  noiseModel::Diagonal::Sigmas((Vector(1) << 0).finished());
41  noiseModel::Diagonal::Variances(Vector3(1e-6, 1e-6, 1e-8));
42 
43 /* ************************************************************************* */
51 static double computeThetaToRoot(const Key nodeKey,
52  const PredecessorMap<Key>& tree, const key2doubleMap& deltaThetaMap,
53  const key2doubleMap& thetaFromRootMap) {
54 
55  double nodeTheta = 0;
56  Key key_child = nodeKey; // the node
57  Key key_parent = 0; // the initialization does not matter
58  while (1) {
59  // We check if we reached the root
60  if (tree.at(key_child) == key_child) // if we reached the root
61  break;
62  // we sum the delta theta corresponding to the edge parent->child
63  nodeTheta += deltaThetaMap.at(key_child);
64  // we get the parent
65  key_parent = tree.at(key_child); // the parent
66  // we check if we connected to some part of the tree we know
67  if (thetaFromRootMap.find(key_parent) != thetaFromRootMap.end()) {
68  nodeTheta += thetaFromRootMap.at(key_parent);
69  break;
70  }
71  key_child = key_parent; // we move upwards in the tree
72  }
73  return nodeTheta;
74 }
75 
76 /* ************************************************************************* */
78  const PredecessorMap<Key>& tree) {
79 
80  key2doubleMap thetaToRootMap;
81 
82  // Orientation of the roo
83  thetaToRootMap.insert(pair<Key, double>(initialize::kAnchorKey, 0.0));
84 
85  // for all nodes in the tree
86  for(const key2doubleMap::value_type& it: deltaThetaMap) {
87  // compute the orientation wrt root
88  Key nodeKey = it.first;
89  double nodeTheta = computeThetaToRoot(nodeKey, tree, deltaThetaMap,
90  thetaToRootMap);
91  thetaToRootMap.insert(pair<Key, double>(nodeKey, nodeTheta));
92  }
93  return thetaToRootMap;
94 }
95 
96 /* ************************************************************************* */
98 /*OUTPUTS*/vector<size_t>& spanningTreeIds, vector<size_t>& chordsIds,
99  key2doubleMap& deltaThetaMap,
100  /*INPUTS*/const PredecessorMap<Key>& tree, const NonlinearFactorGraph& g) {
101 
102  // Get keys for which you want the orientation
103  size_t id = 0;
104  // Loop over the factors
105  for(const boost::shared_ptr<NonlinearFactor>& factor: g) {
106  if (factor->keys().size() == 2) {
107  Key key1 = factor->keys()[0];
108  Key key2 = factor->keys()[1];
109  // recast to a between
110  boost::shared_ptr<BetweenFactor<Pose2> > pose2Between =
111  boost::dynamic_pointer_cast<BetweenFactor<Pose2> >(factor);
112  if (!pose2Between)
113  continue;
114  // get the orientation - measured().theta();
115  double deltaTheta = pose2Between->measured().theta();
116  // insert (directed) orientations in the map "deltaThetaMap"
117  bool inTree = false;
118  if (tree.at(key1) == key2) { // key2 -> key1
119  deltaThetaMap.insert(pair<Key, double>(key1, -deltaTheta));
120  inTree = true;
121  } else if (tree.at(key2) == key1) { // key1 -> key2
122  deltaThetaMap.insert(pair<Key, double>(key2, deltaTheta));
123  inTree = true;
124  }
125  // store factor slot, distinguishing spanning tree edges from chordsIds
126  if (inTree == true)
127  spanningTreeIds.push_back(id);
128  else
129  // it's a chord!
130  chordsIds.push_back(id);
131  }
132  id++;
133  }
134 }
135 
136 /* ************************************************************************* */
137 // Retrieve the deltaTheta and the corresponding noise model from a BetweenFactor<Pose2>
139  Vector& deltaTheta, noiseModel::Diagonal::shared_ptr& model_deltaTheta) {
140 
141  // Get the relative rotation measurement from the between factor
142  boost::shared_ptr<BetweenFactor<Pose2> > pose2Between =
143  boost::dynamic_pointer_cast<BetweenFactor<Pose2> >(factor);
144  if (!pose2Between)
145  throw invalid_argument(
146  "buildLinearOrientationGraph: invalid between factor!");
147  deltaTheta = (Vector(1) << pose2Between->measured().theta()).finished();
148 
149  // Retrieve the noise model for the relative rotation
150  SharedNoiseModel model = pose2Between->noiseModel();
151  boost::shared_ptr<noiseModel::Diagonal> diagonalModel =
152  boost::dynamic_pointer_cast<noiseModel::Diagonal>(model);
153  if (!diagonalModel)
154  throw invalid_argument("buildLinearOrientationGraph: invalid noise model "
155  "(current version assumes diagonal noise model)!");
156  Vector std_deltaTheta = (Vector(1) << diagonalModel->sigma(2)).finished(); // std on the angular measurement
157  model_deltaTheta = noiseModel::Diagonal::Sigmas(std_deltaTheta);
158 }
159 
160 /* ************************************************************************* */
162  const vector<size_t>& spanningTreeIds, const vector<size_t>& chordsIds,
163  const NonlinearFactorGraph& g, const key2doubleMap& orientationsToRoot,
164  const PredecessorMap<Key>& tree) {
165 
166  GaussianFactorGraph lagoGraph;
167  Vector deltaTheta;
168  noiseModel::Diagonal::shared_ptr model_deltaTheta;
169 
170  // put original measurements in the spanning tree
171  for(const size_t& factorId: spanningTreeIds) {
172  const KeyVector& keys = g[factorId]->keys();
173  Key key1 = keys[0], key2 = keys[1];
174  getDeltaThetaAndNoise(g[factorId], deltaTheta, model_deltaTheta);
175  lagoGraph.add(key1, -I, key2, I, deltaTheta, model_deltaTheta);
176  }
177  // put regularized measurements in the chordsIds
178  for(const size_t& factorId: chordsIds) {
179  const KeyVector& keys = g[factorId]->keys();
180  Key key1 = keys[0], key2 = keys[1];
181  getDeltaThetaAndNoise(g[factorId], deltaTheta, model_deltaTheta);
182  double key1_DeltaTheta_key2 = deltaTheta(0);
184  double k2pi_noise = key1_DeltaTheta_key2 + orientationsToRoot.at(key1)
185  - orientationsToRoot.at(key2); // this coincides to summing up measurements along the cycle induced by the chord
186  double k = boost::math::round(k2pi_noise / (2 * M_PI));
187  //if (k2pi_noise - 2*k*M_PI > 1e-5) cout << k2pi_noise - 2*k*M_PI << endl; // for debug
188  Vector deltaThetaRegularized = (Vector(1)
189  << key1_DeltaTheta_key2 - 2 * k * M_PI).finished();
190  lagoGraph.add(key1, -I, key2, I, deltaThetaRegularized, model_deltaTheta);
191  }
192  // prior on the anchor orientation
193  lagoGraph.add(initialize::kAnchorKey, I, (Vector(1) << 0.0).finished(), priorOrientationNoise);
194  return lagoGraph;
195 }
196 
197 /* ************************************************************************* */
199  const NonlinearFactorGraph& pose2Graph) {
200 
202  Key minKey = initialize::kAnchorKey; // this initialization does not matter
203  bool minUnassigned = true;
204 
205  for(const boost::shared_ptr<NonlinearFactor>& factor: pose2Graph) {
206 
207  Key key1 = std::min(factor->keys()[0], factor->keys()[1]);
208  Key key2 = std::max(factor->keys()[0], factor->keys()[1]);
209  if (minUnassigned) {
210  minKey = key1;
211  minUnassigned = false;
212  }
213  if (key2 - key1 == 1) { // consecutive keys
214  tree.insert(key2, key1);
215  if (key1 < minKey)
216  minKey = key1;
217  }
218  }
219  tree.insert(minKey, initialize::kAnchorKey);
221  return tree;
222 }
223 
224 /* ************************************************************************* */
225 // Return the orientations of a graph including only BetweenFactors<Pose2>
227  bool useOdometricPath) {
228  gttic(lago_computeOrientations);
229 
230  // Find a minimum spanning tree
232  if (useOdometricPath)
233  tree = findOdometricPath(pose2Graph);
234  else
236  BetweenFactor<Pose2> >(pose2Graph);
237 
238  // Create a linear factor graph (LFG) of scalars
239  key2doubleMap deltaThetaMap;
240  vector<size_t> spanningTreeIds; // ids of between factors forming the spanning tree T
241  vector<size_t> chordsIds; // ids of between factors corresponding to chordsIds wrt T
242  getSymbolicGraph(spanningTreeIds, chordsIds, deltaThetaMap, tree, pose2Graph);
243 
244  // temporary structure to correct wraparounds along loops
245  key2doubleMap orientationsToRoot = computeThetasToRoot(deltaThetaMap, tree);
246 
247  // regularize measurements and plug everything in a factor graph
248  GaussianFactorGraph lagoGraph = buildLinearOrientationGraph(spanningTreeIds,
249  chordsIds, pose2Graph, orientationsToRoot, tree);
250 
251  // Solve the LFG
252  VectorValues orientationsLago = lagoGraph.optimize();
253 
254  return orientationsLago;
255 }
256 
257 /* ************************************************************************* */
259  bool useOdometricPath) {
260 
261  // We "extract" the Pose2 subgraph of the original graph: this
262  // is done to properly model priors and avoiding operating on a larger graph
263  NonlinearFactorGraph pose2Graph = initialize::buildPoseGraph<Pose2>(graph);
264 
265  // Get orientations from relative orientation measurements
266  return computeOrientations(pose2Graph, useOdometricPath);
267 }
268 
269 /* ************************************************************************* */
271  VectorValues& orientationsLago) {
272  gttic(lago_computePoses);
273 
274  // Linearized graph on full poses
275  GaussianFactorGraph linearPose2graph;
276 
277  // We include the linear version of each between factor
278  for(const boost::shared_ptr<NonlinearFactor>& factor: pose2graph) {
279 
280  boost::shared_ptr<BetweenFactor<Pose2> > pose2Between =
281  boost::dynamic_pointer_cast<BetweenFactor<Pose2> >(factor);
282 
283  if (pose2Between) {
284  Key key1 = pose2Between->keys()[0];
285  double theta1 = orientationsLago.at(key1)(0);
286  double s1 = sin(theta1);
287  double c1 = cos(theta1);
288 
289  Key key2 = pose2Between->keys()[1];
290  double theta2 = orientationsLago.at(key2)(0);
291 
292  double linearDeltaRot = theta2 - theta1
293  - pose2Between->measured().theta();
294  linearDeltaRot = Rot2(linearDeltaRot).theta(); // to normalize
295 
296  double dx = pose2Between->measured().x();
297  double dy = pose2Between->measured().y();
298 
299  Vector globalDeltaCart = //
300  (Vector(2) << c1 * dx - s1 * dy, s1 * dx + c1 * dy).finished();
301  Vector b = (Vector(3) << globalDeltaCart, linearDeltaRot).finished(); // rhs
302  Matrix J1 = -I3;
303  J1(0, 2) = s1 * dx + c1 * dy;
304  J1(1, 2) = -c1 * dx + s1 * dy;
305  // Retrieve the noise model for the relative rotation
306  boost::shared_ptr<noiseModel::Diagonal> diagonalModel =
307  boost::dynamic_pointer_cast<noiseModel::Diagonal>(
308  pose2Between->noiseModel());
309 
310  linearPose2graph.add(key1, J1, key2, I3, b, diagonalModel);
311  } else {
312  throw invalid_argument(
313  "computeLagoPoses: cannot manage non between factor here!");
314  }
315  }
316  // add prior
317  linearPose2graph.add(initialize::kAnchorKey, I3, Vector3(0.0, 0.0, 0.0),
318  priorPose2Noise);
319 
320  // optimize
321  VectorValues posesLago = linearPose2graph.optimize();
322 
323  // put into Values structure
324  Values initialGuessLago;
325  for(const VectorValues::value_type& it: posesLago) {
326  Key key = it.first;
327  if (key != initialize::kAnchorKey) {
328  const Vector& poseVector = it.second;
329  Pose2 poseLago = Pose2(poseVector(0), poseVector(1),
330  orientationsLago.at(key)(0) + poseVector(2));
331  initialGuessLago.insert(key, poseLago);
332  }
333  }
334  return initialGuessLago;
335 }
336 
337 /* ************************************************************************* */
338 Values initialize(const NonlinearFactorGraph& graph, bool useOdometricPath) {
339  gttic(lago_initialize);
340 
341  // We "extract" the Pose2 subgraph of the original graph: this
342  // is done to properly model priors and avoiding operating on a larger graph
343  NonlinearFactorGraph pose2Graph = initialize::buildPoseGraph<Pose2>(graph);
344 
345  // Get orientations from relative orientation measurements
346  VectorValues orientationsLago = computeOrientations(pose2Graph,
347  useOdometricPath);
348 
349  // Compute the full poses
350  return computePoses(pose2Graph, orientationsLago);
351 }
352 
353 /* ************************************************************************* */
355  const Values& initialGuess) {
356  Values initialGuessLago;
357 
358  // get the orientation estimates from LAGO
359  VectorValues orientations = initializeOrientations(graph);
360 
361  // for all nodes in the tree
362  for(const VectorValues::value_type& it: orientations) {
363  Key key = it.first;
364  if (key != initialize::kAnchorKey) {
365  const Pose2& pose = initialGuess.at<Pose2>(key);
366  const Vector& orientation = it.second;
367  Pose2 poseLago = Pose2(pose.x(), pose.y(), orientation(0));
368  initialGuessLago.insert(key, poseLago);
369  }
370  }
371  return initialGuessLago;
372 }
373 
374 } // end of namespace lago
375 } // end of namespace gtsam
static double computeThetaToRoot(const Key nodeKey, const PredecessorMap< Key > &tree, const key2doubleMap &deltaThetaMap, const key2doubleMap &thetaFromRootMap)
Definition: lago.cpp:51
Values initialize(const NonlinearFactorGraph &graph, const Values &initialGuess)
Definition: lago.cpp:354
void insert(const KEY &key, const KEY &parent)
Definition: graph.h:61
#define max(a, b)
Definition: datatypes.h:20
static const Matrix I3
Definition: lago.cpp:36
static void getDeltaThetaAndNoise(NonlinearFactor::shared_ptr factor, Vector &deltaTheta, noiseModel::Diagonal::shared_ptr &model_deltaTheta)
Definition: lago.cpp:138
VectorValues optimize(const Eliminate &function=EliminationTraitsType::DefaultEliminate) const
Scalar * b
Definition: benchVecAdd.cpp:17
double y() const
get y
Definition: Pose2.h:218
Eigen::Vector3d Vector3
Definition: Vector.h:43
noiseModel::Diagonal::shared_ptr model
void insert(Key j, const Value &val)
Definition: Values.cpp:140
#define min(a, b)
Definition: datatypes.h:19
KeySet keys() const
Eigen::MatrixXd Matrix
Definition: base/Matrix.h:43
common code between lago.* (2D) and InitializePose3.* (3D)
#define M_PI
Definition: main.h:78
Definition: Half.h:150
const VALUE & measured() const
return the measurement
Values::value_type value_type
Typedef to pair<Key, Vector>
Definition: VectorValues.h:84
Vector & at(Key j)
Definition: VectorValues.h:137
NonlinearFactorGraph graph
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
const Symbol key1('v', 1)
EIGEN_DEVICE_FUNC const RoundReturnType round() const
Initialize Pose2 in a factor graph using LAGO (Linear Approximation for Graph Optimization). see papers:
EIGEN_DEVICE_FUNC const CosReturnType cos() const
#define gttic(label)
Definition: timing.h:280
static const noiseModel::Diagonal::shared_ptr priorOrientationNoise
Definition: lago.cpp:38
void add(const GaussianFactor &factor)
FastVector< Key > KeyVector
Define collection type once and for all - also used in wrappers.
Definition: Key.h:86
Eigen::VectorXd Vector
Definition: Vector.h:38
double theta() const
Definition: Rot2.h:183
const ValueType at(Key j) const
Definition: Values-inl.h:342
static const Pose3 pose(Rot3(Vector3(1,-1,-1).asDiagonal()), Point3(0, 0, 0.5))
boost::shared_ptr< This > shared_ptr
Array< double, 1, 3 > e(1./3., 0.5, 2.)
static VectorValues computeOrientations(const NonlinearFactorGraph &pose2Graph, bool useOdometricPath)
Definition: lago.cpp:226
VectorValues initializeOrientations(const NonlinearFactorGraph &graph, bool useOdometricPath)
Definition: lago.cpp:258
static const Matrix I
Definition: lago.cpp:35
boost::shared_ptr< Diagonal > shared_ptr
Definition: NoiseModel.h:301
void getSymbolicGraph(vector< size_t > &spanningTreeIds, vector< size_t > &chordsIds, key2doubleMap &deltaThetaMap, const PredecessorMap< Key > &tree, const NonlinearFactorGraph &g)
Definition: lago.cpp:97
traits
Definition: chartTesting.h:28
Values computePoses(const NonlinearFactorGraph &pose2graph, VectorValues &orientationsLago)
Definition: lago.cpp:270
double x() const
get x
Definition: Pose2.h:215
const Symbol key2('v', 2)
static constexpr Key kAnchorKey
PredecessorMap< KEY > findMinimumSpanningTree(const G &fg)
Definition: graph-inl.h:232
EIGEN_DEVICE_FUNC const SinReturnType sin() const
std::map< Key, double > key2doubleMap
Definition: lago.h:45
const KeyVector keys
2D Pose
Eigen::Matrix< double, Eigen::Dynamic, 1 > Vector
key2doubleMap computeThetasToRoot(const key2doubleMap &deltaThetaMap, const PredecessorMap< Key > &tree)
Definition: lago.cpp:77
static PredecessorMap< Key > findOdometricPath(const NonlinearFactorGraph &pose2Graph)
Definition: lago.cpp:198
std::uint64_t Key
Integer nonlinear key type.
Definition: types.h:61
static const Key c1
Timing utilities.
noiseModel::Base::shared_ptr SharedNoiseModel
Definition: NoiseModel.h:734
static const noiseModel::Diagonal::shared_ptr priorPose2Noise
Definition: lago.cpp:40


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