44 noiseModel::Diagonal::Sigmas(
Vector1(0));
46 noiseModel::Diagonal::Variances(
Vector3(1
e-6, 1
e-6, 1
e-8));
61 Key key_child = nodeKey;
65 if (tree.at(key_child) == key_child)
68 nodeTheta += deltaThetaMap.at(key_child);
70 key_parent = tree.at(key_child);
72 if (thetaFromRootMap.find(key_parent) != thetaFromRootMap.end()) {
73 nodeTheta += thetaFromRootMap.at(key_parent);
76 key_child = key_parent;
91 for(
const auto& [nodeKey,
_]: deltaThetaMap) {
95 thetaToRootMap.emplace(nodeKey, nodeTheta);
97 return thetaToRootMap;
102 vector<size_t>& spanningTreeIds, vector<size_t>& chordsIds,
109 for(
const std::shared_ptr<NonlinearFactor>& factor: g) {
110 if (factor->keys().size() == 2) {
114 std::shared_ptr<BetweenFactor<Pose2> > pose2Between =
119 double deltaTheta = pose2Between->
measured().theta();
122 if (tree.at(key1) ==
key2) {
123 deltaThetaMap.insert(pair<Key, double>(key1, -deltaTheta));
125 }
else if (tree.at(key2) ==
key1) {
126 deltaThetaMap.insert(pair<Key, double>(key2, deltaTheta));
131 spanningTreeIds.push_back(
id);
134 chordsIds.push_back(
id);
146 std::shared_ptr<BetweenFactor<Pose2> > pose2Between =
149 throw invalid_argument(
150 "buildLinearOrientationGraph: invalid between factor!");
151 deltaTheta = (
Vector(1) << pose2Between->measured().theta()).finished();
155 std::shared_ptr<noiseModel::Diagonal> diagonalModel =
158 throw invalid_argument(
"buildLinearOrientationGraph: invalid noise model " 159 "(current version assumes diagonal noise model)!");
160 Vector std_deltaTheta = (
Vector(1) << diagonalModel->sigma(2)).finished();
161 model_deltaTheta = noiseModel::Diagonal::Sigmas(std_deltaTheta);
166 const vector<size_t>& spanningTreeIds,
const vector<size_t>& chordsIds,
175 for(
const size_t& factorId: spanningTreeIds) {
179 lagoGraph.
add(key1, -I, key2, I, deltaTheta, model_deltaTheta);
182 for(
const size_t& factorId: chordsIds) {
186 double key1_DeltaTheta_key2 = deltaTheta(0);
188 double k2pi_noise = key1_DeltaTheta_key2 + orientationsToRoot.at(key1)
189 - orientationsToRoot.at(key2);
193 << key1_DeltaTheta_key2 - 2 * k *
M_PI).finished();
194 lagoGraph.
add(key1, -I, key2, I, deltaThetaRegularized, model_deltaTheta);
207 bool minUnassigned =
true;
209 for(
const std::shared_ptr<NonlinearFactor>& factor: pose2Graph) {
215 minUnassigned =
false;
217 if (key2 - key1 == 1) {
218 tree.emplace(key2, key1);
232 const auto edgeWeights = std::vector<double>(pose2Graph.
size(), 1.0);
233 const auto mstEdgeIndices =
240 std::map<Key, bool> visitationMap;
241 std::stack<std::pair<Key, Key>>
stack;
244 while (!stack.empty()) {
245 auto [u, parent] = stack.top();
247 if (visitationMap[u])
continue;
248 visitationMap[u] =
true;
249 predecessorMap[u] = parent;
250 for (
const auto& edgeIdx : mstEdgeIndices) {
251 const auto v = pose2Graph[edgeIdx]->
front();
252 const auto w = pose2Graph[edgeIdx]->
back();
253 if ((
v == u ||
w == u) && !visitationMap[
v == u ?
w :
v]) {
254 stack.push({v == u ?
w :
v, u});
259 return predecessorMap;
265 bool useOdometricPath) {
266 gttic(lago_computeOrientations);
270 if (useOdometricPath)
281 getSymbolicGraph(spanningTreeIds, chordsIds, deltaThetaMap, tree, pose2Graph);
288 spanningTreeIds, chordsIds, pose2Graph, orientationsToRoot, tree);
293 return orientationsLago;
298 bool useOdometricPath) {
310 gttic(lago_computePoses);
316 for(
const std::shared_ptr<NonlinearFactor>& factor: pose2graph) {
318 std::shared_ptr<BetweenFactor<Pose2> > pose2Between =
322 Key key1 = pose2Between->keys()[0];
323 double theta1 = orientationsLago.
at(key1)(0);
324 double s1 =
sin(theta1);
325 double c1 =
cos(theta1);
327 Key key2 = pose2Between->keys()[1];
328 double theta2 = orientationsLago.
at(key2)(0);
330 double linearDeltaRot = theta2 - theta1
331 - pose2Between->measured().theta();
332 linearDeltaRot =
Rot2(linearDeltaRot).
theta();
334 double dx = pose2Between->measured().x();
335 double dy = pose2Between->measured().y();
338 (
Vector(2) << c1 * dx - s1 * dy, s1 * dx + c1 * dy).finished();
339 Vector b = (
Vector(3) << globalDeltaCart, linearDeltaRot).finished();
341 J1(0, 2) = s1 * dx + c1 * dy;
342 J1(1, 2) = -c1 * dx + s1 * dy;
344 std::shared_ptr<noiseModel::Diagonal> diagonalModel =
346 pose2Between->noiseModel());
348 linearPose2graph.
add(key1, J1, key2, I3, b, diagonalModel);
350 throw invalid_argument(
351 "computeLagoPoses: cannot manage non between factor here!");
365 const Vector& poseVector = it.second;
366 Pose2 poseLago =
Pose2(poseVector(0), poseVector(1),
367 orientationsLago.
at(key)(0) + poseVector(2));
368 initialGuessLago.
insert(key, poseLago);
371 return initialGuessLago;
376 gttic(lago_initialize);
392 const Values& initialGuess) {
403 const Vector& orientation = it.second;
404 Pose2 poseLago =
Pose2(pose.
x(), pose.
y(), orientation(0));
405 initialGuessLago.
insert(key, poseLago);
408 return initialGuessLago;
const gtsam::Symbol key('X', 0)
Values initialize(const NonlinearFactorGraph &graph, const Values &initialGuess)
sharedFactor back() const
Jet< T, N > cos(const Jet< T, N > &f)
static void getDeltaThetaAndNoise(NonlinearFactor::shared_ptr factor, Vector &deltaTheta, noiseModel::Diagonal::shared_ptr &model_deltaTheta)
Eigen::Matrix< double, 1, 1 > Vector1
noiseModel::Diagonal::shared_ptr model
const ValueType at(Key j) const
sharedFactor front() const
key2doubleMap computeThetasToRoot(const key2doubleMap &deltaThetaMap, const PredecessorMap &tree)
common code between lago.* (2D) and InitializePose3.* (3D)
Jet< T, N > sin(const Jet< T, N > &f)
Values::value_type value_type
Typedef to pair<Key, Vector>
void getSymbolicGraph(vector< size_t > &spanningTreeIds, vector< size_t > &chordsIds, key2doubleMap &deltaThetaMap, const PredecessorMap &tree, const NonlinearFactorGraph &g)
NonlinearFactorGraph graph
std::vector< size_t > kruskal(const FactorGraph< FACTOR > &fg, const std::vector< double > &weights)
void g(const string &key, int i)
VectorValues optimize(const Eliminate &function=EliminationTraitsType::DefaultEliminate) const
std::map< Key, Key > PredecessorMap
Initialize Pose2 in a factor graph using LAGO (Linear Approximation for Graph Optimization). see papers:
static const noiseModel::Diagonal::shared_ptr priorOrientationNoise
void add(const GaussianFactor &factor)
const Symbol key1('v', 1)
Matrix stack(size_t nrMatrices,...)
static double computeThetaToRoot(const Key nodeKey, const PredecessorMap &tree, const key2doubleMap &deltaThetaMap, const key2doubleMap &thetaFromRootMap)
Array< int, Dynamic, 1 > v
Array< double, 1, 3 > e(1./3., 0.5, 2.)
static PredecessorMap findOdometricPath(const NonlinearFactorGraph &pose2Graph)
static VectorValues computeOrientations(const NonlinearFactorGraph &pose2Graph, bool useOdometricPath)
VectorValues initializeOrientations(const NonlinearFactorGraph &graph, bool useOdometricPath)
PredecessorMap findMinimumSpanningTree(const NonlinearFactorGraph &pose2Graph)
Values computePoses(const NonlinearFactorGraph &pose2graph, VectorValues &orientationsLago)
static const Pose3 pose(Rot3(Vector3(1, -1, -1).asDiagonal()), Point3(0, 0, 0.5))
constexpr descr< N - 1 > _(char const (&text)[N])
GaussianFactorGraph buildLinearOrientationGraph(const vector< size_t > &spanningTreeIds, const vector< size_t > &chordsIds, const NonlinearFactorGraph &g, const key2doubleMap &orientationsToRoot, const PredecessorMap &tree)
std::shared_ptr< This > shared_ptr
static constexpr Key kAnchorKey
void insert(Key j, const Value &val)
std::map< Key, double > key2doubleMap
FastVector< Key > KeyVector
Define collection type once and for all - also used in wrappers.
std::shared_ptr< Diagonal > shared_ptr
Eigen::Matrix< double, Eigen::Dynamic, 1 > Vector
const VALUE & measured() const
return the measurement
std::uint64_t Key
Integer nonlinear key type.
noiseModel::Base::shared_ptr SharedNoiseModel
const Symbol key2('v', 2)
static const noiseModel::Diagonal::shared_ptr priorPose2Noise
EIGEN_DEVICE_FUNC const RoundReturnType round() const