28 #include <boost/math/special_functions.hpp> 39 noiseModel::Diagonal::Sigmas((
Vector(1) << 0).finished());
41 noiseModel::Diagonal::Variances(
Vector3(1
e-6, 1
e-6, 1
e-8));
56 Key key_child = nodeKey;
60 if (tree.at(key_child) == key_child)
63 nodeTheta += deltaThetaMap.at(key_child);
65 key_parent = tree.at(key_child);
67 if (thetaFromRootMap.find(key_parent) != thetaFromRootMap.end()) {
68 nodeTheta += thetaFromRootMap.at(key_parent);
71 key_child = key_parent;
86 for(
const key2doubleMap::value_type& it: deltaThetaMap) {
88 Key nodeKey = it.first;
91 thetaToRootMap.insert(pair<Key, double>(nodeKey, nodeTheta));
93 return thetaToRootMap;
98 vector<size_t>& spanningTreeIds, vector<size_t>& chordsIds,
105 for(
const boost::shared_ptr<NonlinearFactor>& factor: g) {
106 if (factor->keys().size() == 2) {
110 boost::shared_ptr<BetweenFactor<Pose2> > pose2Between =
115 double deltaTheta = pose2Between->
measured().theta();
118 if (tree.at(key1) ==
key2) {
119 deltaThetaMap.insert(pair<Key, double>(key1, -deltaTheta));
121 }
else if (tree.at(key2) ==
key1) {
122 deltaThetaMap.insert(pair<Key, double>(key2, deltaTheta));
127 spanningTreeIds.push_back(
id);
130 chordsIds.push_back(
id);
142 boost::shared_ptr<BetweenFactor<Pose2> > pose2Between =
145 throw invalid_argument(
146 "buildLinearOrientationGraph: invalid between factor!");
147 deltaTheta = (
Vector(1) << pose2Between->measured().theta()).finished();
151 boost::shared_ptr<noiseModel::Diagonal> 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();
157 model_deltaTheta = noiseModel::Diagonal::Sigmas(std_deltaTheta);
162 const vector<size_t>& spanningTreeIds,
const vector<size_t>& chordsIds,
171 for(
const size_t& factorId: spanningTreeIds) {
175 lagoGraph.
add(key1, -I, key2, I, deltaTheta, model_deltaTheta);
178 for(
const size_t& factorId: chordsIds) {
182 double key1_DeltaTheta_key2 = deltaTheta(0);
184 double k2pi_noise = key1_DeltaTheta_key2 + orientationsToRoot.at(key1)
185 - orientationsToRoot.at(key2);
189 << key1_DeltaTheta_key2 - 2 * k *
M_PI).finished();
190 lagoGraph.
add(key1, -I, key2, I, deltaThetaRegularized, model_deltaTheta);
203 bool minUnassigned =
true;
205 for(
const boost::shared_ptr<NonlinearFactor>& factor: pose2Graph) {
211 minUnassigned =
false;
213 if (key2 - key1 == 1) {
227 bool useOdometricPath) {
228 gttic(lago_computeOrientations);
232 if (useOdometricPath)
240 vector<size_t> spanningTreeIds;
241 vector<size_t> chordsIds;
242 getSymbolicGraph(spanningTreeIds, chordsIds, deltaThetaMap, tree, pose2Graph);
249 chordsIds, pose2Graph, orientationsToRoot, tree);
254 return orientationsLago;
259 bool useOdometricPath) {
272 gttic(lago_computePoses);
278 for(
const boost::shared_ptr<NonlinearFactor>& factor: pose2graph) {
280 boost::shared_ptr<BetweenFactor<Pose2> > pose2Between =
284 Key key1 = pose2Between->keys()[0];
285 double theta1 = orientationsLago.
at(key1)(0);
286 double s1 =
sin(theta1);
287 double c1 =
cos(theta1);
289 Key key2 = pose2Between->keys()[1];
290 double theta2 = orientationsLago.
at(key2)(0);
292 double linearDeltaRot = theta2 - theta1
293 - pose2Between->measured().theta();
294 linearDeltaRot =
Rot2(linearDeltaRot).
theta();
296 double dx = pose2Between->measured().x();
297 double dy = pose2Between->measured().y();
300 (
Vector(2) << c1 * dx - s1 * dy, s1 * dx + c1 * dy).finished();
301 Vector b = (
Vector(3) << globalDeltaCart, linearDeltaRot).finished();
303 J1(0, 2) = s1 * dx + c1 * dy;
304 J1(1, 2) = -c1 * dx + s1 * dy;
306 boost::shared_ptr<noiseModel::Diagonal> diagonalModel =
308 pose2Between->noiseModel());
310 linearPose2graph.
add(key1, J1, key2, I3, b, diagonalModel);
312 throw invalid_argument(
313 "computeLagoPoses: cannot manage non between factor here!");
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);
334 return initialGuessLago;
339 gttic(lago_initialize);
355 const Values& initialGuess) {
366 const Vector& orientation = it.second;
367 Pose2 poseLago =
Pose2(pose.
x(), pose.
y(), orientation(0));
368 initialGuessLago.
insert(key, poseLago);
371 return initialGuessLago;
static double computeThetaToRoot(const Key nodeKey, const PredecessorMap< Key > &tree, const key2doubleMap &deltaThetaMap, const key2doubleMap &thetaFromRootMap)
Values initialize(const NonlinearFactorGraph &graph, const Values &initialGuess)
void insert(const KEY &key, const KEY &parent)
static void getDeltaThetaAndNoise(NonlinearFactor::shared_ptr factor, Vector &deltaTheta, noiseModel::Diagonal::shared_ptr &model_deltaTheta)
VectorValues optimize(const Eliminate &function=EliminationTraitsType::DefaultEliminate) const
noiseModel::Diagonal::shared_ptr model
void insert(Key j, const Value &val)
common code between lago.* (2D) and InitializePose3.* (3D)
const VALUE & measured() const
return the measurement
Values::value_type value_type
Typedef to pair<Key, Vector>
NonlinearFactorGraph graph
void g(const string &key, int i)
GaussianFactorGraph buildLinearOrientationGraph(const vector< size_t > &spanningTreeIds, const vector< size_t > &chordsIds, const NonlinearFactorGraph &g, const key2doubleMap &orientationsToRoot, const PredecessorMap< Key > &tree)
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
static const noiseModel::Diagonal::shared_ptr priorOrientationNoise
void add(const GaussianFactor &factor)
FastVector< Key > KeyVector
Define collection type once and for all - also used in wrappers.
const ValueType at(Key j) const
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)
VectorValues initializeOrientations(const NonlinearFactorGraph &graph, bool useOdometricPath)
boost::shared_ptr< Diagonal > shared_ptr
void getSymbolicGraph(vector< size_t > &spanningTreeIds, vector< size_t > &chordsIds, key2doubleMap &deltaThetaMap, const PredecessorMap< Key > &tree, const NonlinearFactorGraph &g)
Values computePoses(const NonlinearFactorGraph &pose2graph, VectorValues &orientationsLago)
const Symbol key2('v', 2)
static constexpr Key kAnchorKey
PredecessorMap< KEY > findMinimumSpanningTree(const G &fg)
EIGEN_DEVICE_FUNC const SinReturnType sin() const
std::map< Key, double > key2doubleMap
Eigen::Matrix< double, Eigen::Dynamic, 1 > Vector
key2doubleMap computeThetasToRoot(const key2doubleMap &deltaThetaMap, const PredecessorMap< Key > &tree)
static PredecessorMap< Key > findOdometricPath(const NonlinearFactorGraph &pose2Graph)
std::uint64_t Key
Integer nonlinear key type.
noiseModel::Base::shared_ptr SharedNoiseModel
static const noiseModel::Diagonal::shared_ptr priorPose2Noise