InitializePose.h
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 #pragma once
20 
21 #include <gtsam/inference/Symbol.h>
26 
27 namespace gtsam {
28 namespace initialize {
29 
30 static constexpr Key kAnchorKey = 99999999;
31 
36 template <class Pose>
38  NonlinearFactorGraph poseGraph;
39 
40  for (const auto& factor : graph) {
41  // recast to a between on Pose
42  if (auto between =
43  std::dynamic_pointer_cast<BetweenFactor<Pose> >(factor))
44  poseGraph.add(between);
45 
46  // recast PriorFactor<Pose> to BetweenFactor<Pose>
47  if (auto prior = std::dynamic_pointer_cast<PriorFactor<Pose> >(factor))
49  kAnchorKey, prior->keys()[0], prior->prior(), prior->noiseModel());
50  }
51  return poseGraph;
52 }
53 
57 template <class Pose>
58 static Values computePoses(const Values& initialRot,
59  NonlinearFactorGraph* posegraph,
60  bool singleIter = true) {
61  const auto origin = Pose().translation();
62 
63  // Upgrade rotations to full poses
64  Values initialPose;
65  for (const auto& key_rot : initialRot.extract<typename Pose::Rotation>()) {
66  const Key& key = key_rot.first;
67  const auto& rot = key_rot.second;
68  const Pose initializedPose(rot, origin);
69  initialPose.insert(key, initializedPose);
70  }
71 
72  // add prior on dummy node
73  auto priorModel = noiseModel::Unit::Create(Pose::dimension);
74  initialPose.insert(kAnchorKey, Pose());
75  posegraph->emplace_shared<PriorFactor<Pose> >(kAnchorKey, Pose(), priorModel);
76 
77  // Create optimizer
79  if (singleIter) {
80  params.maxIterations = 1;
81  } else {
82  params.setVerbosity("TERMINATION");
83  }
84  GaussNewtonOptimizer optimizer(*posegraph, initialPose, params);
85  const Values GNresult = optimizer.optimize();
86 
87  // put into Values structure
88  Values estimate;
89  for (const auto& key_pose : GNresult.extract<Pose>()) {
90  const Key& key = key_pose.first;
91  if (key != kAnchorKey) {
92  const Pose& pose = key_pose.second;
93  estimate.insert(key, pose);
94  }
95  }
96  return estimate;
97 }
98 } // namespace initialize
99 } // namespace gtsam
gtsam::NonlinearOptimizer::optimize
virtual const Values & optimize()
Definition: NonlinearOptimizer.h:98
pose
static const Pose3 pose(Rot3(Vector3(1, -1, -1).asDiagonal()), Point3(0, 0, 0.5))
gtsam::between
Expression< T > between(const Expression< T > &t1, const Expression< T > &t2)
Definition: nonlinear/expressions.h:17
gtsam::GaussNewtonOptimizer
Definition: GaussNewtonOptimizer.h:38
Pose
Pose2 Pose
Definition: SolverComparer.cpp:68
gtsam::PriorFactor
Definition: nonlinear/PriorFactor.h:30
gtsam::initialize::computePoses
static Values computePoses(const Values &initialRot, NonlinearFactorGraph *posegraph, bool singleIter=true)
Definition: InitializePose.h:58
vanilla::params
static const SmartProjectionParams params
Definition: smartFactorScenarios.h:69
rot
int EIGEN_BLAS_FUNC() rot(int *n, RealScalar *px, int *incx, RealScalar *py, int *incy, RealScalar *pc, RealScalar *ps)
Definition: level1_real_impl.h:79
GaussNewtonOptimizer.h
PriorFactor.h
gtsam::Values::extract
std::map< Key, ValueType > extract(const std::function< bool(Key)> &filterFcn=&_truePredicate< Key >) const
Definition: Values-inl.h:105
BetweenFactor.h
gtsam::GaussNewtonParams
Definition: GaussNewtonOptimizer.h:30
gtsam::NonlinearFactorGraph
Definition: NonlinearFactorGraph.h:55
gtsam::noiseModel::Unit::Create
static shared_ptr Create(size_t dim)
Definition: NoiseModel.h:610
gtsam::LieGroup< Pose2, 3 >::dimension
@ dimension
Definition: Lie.h:39
Symbol.h
key
const gtsam::Symbol key('X', 0)
simulated2D::prior
Point2 prior(const Point2 &x)
Prior on a single pose.
Definition: simulated2D.h:88
gtsam::Rot2
Definition: Rot2.h:35
gtsam
traits
Definition: chartTesting.h:28
NonlinearFactorGraph.h
Factor Graph consisting of non-linear factors.
gtsam::Values
Definition: Values.h:65
origin
set noclip points set clip one set noclip two set bar set border lt lw set xdata set ydata set zdata set x2data set y2data set boxwidth set dummy y set format x g set format y g set format x2 g set format y2 g set format z g set angles radians set nogrid set key title set key left top Right noreverse box linetype linewidth samplen spacing width set nolabel set noarrow set nologscale set logscale x set set pointsize set encoding default set nopolar set noparametric set set set set surface set nocontour set clabel set mapping cartesian set nohidden3d set cntrparam order set cntrparam linear set cntrparam levels auto set cntrparam points set size set origin
Definition: gnuplot_common_settings.hh:45
gtsam::Values::insert
void insert(Key j, const Value &val)
Definition: Values.cpp:155
gtsam::initialize::kAnchorKey
static constexpr Key kAnchorKey
Definition: InitializePose.h:30
gtsam::initialize::buildPoseGraph
static NonlinearFactorGraph buildPoseGraph(const NonlinearFactorGraph &graph)
Definition: InitializePose.h:37
gtsam::FactorGraph::add
IsDerived< DERIVEDFACTOR > add(std::shared_ptr< DERIVEDFACTOR > factor)
add is a synonym for push_back.
Definition: FactorGraph.h:171
graph
NonlinearFactorGraph graph
Definition: doc/Code/OdometryExample.cpp:2
gtsam::Key
std::uint64_t Key
Integer nonlinear key type.
Definition: types.h:97
gtsam::lago::initialize
Values initialize(const NonlinearFactorGraph &graph, bool useOdometricPath)
Definition: lago.cpp:375
gtsam::FactorGraph::emplace_shared
IsDerived< DERIVEDFACTOR > emplace_shared(Args &&... args)
Emplace a shared pointer to factor of given type.
Definition: FactorGraph.h:153
gtsam::Pose2
Definition: Pose2.h:39
gtsam::BetweenFactor
Definition: BetweenFactor.h:40


gtsam
Author(s):
autogenerated on Tue Jun 25 2024 03:01:02