Pose2SLAMStressTest.cpp
Go to the documentation of this file.
1 
8 // Create N 3D poses, add relative motion between each consecutive poses. (The
9 // relative motion is simply a unit translation(1, 0, 0), no rotation). For each
10 // each pose, add some random noise to the x value of the translation part.
11 // Use gtsam to create a prior factor for the first pose and N-1 between factors
12 // and run optimization.
13 
15 #include <gtsam/geometry/Pose3.h>
20 #include <gtsam/nonlinear/Values.h>
23 
24 #include <random>
25 
26 using namespace std;
27 using namespace gtsam;
28 
29 void testGtsam(int numberNodes) {
30  std::random_device rd;
31  std::mt19937 e2(rd());
32  std::uniform_real_distribution<> dist(0, 1);
33 
34  vector<Pose3> poses;
35  for (int i = 0; i < numberNodes; ++i) {
36  Matrix4 M;
37  double r = dist(e2);
38  r = (r - 0.5) / 10 + i;
39  M << 1, 0, 0, r, 0, 1, 0, 0, 0, 0, 1, 0, 0, 0, 0, 1;
40  poses.push_back(Pose3(M));
41  }
42 
43  // prior factor for the first pose
44  auto priorModel = noiseModel::Isotropic::Variance(6, 1e-4);
45  Matrix4 first_M;
46  first_M << 1, 0, 0, 0, 0, 1, 0, 0, 0, 0, 1, 0, 0, 0, 0, 1;
47  Pose3 first = Pose3(first_M);
48 
50  graph.addPrior(0, first, priorModel);
51 
52  // vo noise model
53  auto VOCovarianceModel = noiseModel::Isotropic::Variance(6, 1e-3);
54 
55  // relative VO motion
56  Matrix4 vo_M;
57  vo_M << 1, 0, 0, 1, 0, 1, 0, 0, 0, 0, 1, 0, 0, 0, 0, 1;
58  Pose3 relativeMotion(vo_M);
59  for (int i = 0; i < numberNodes - 1; ++i) {
60  graph.add(
61  BetweenFactor<Pose3>(i, i + 1, relativeMotion, VOCovarianceModel));
62  }
63 
64  // inital values
66  for (int i = 0; i < numberNodes; ++i) {
67  initial.insert(i, poses[i]);
68  }
69 
71  params.setVerbosity("ERROR");
72  params.setOrderingType("METIS");
73  params.setLinearSolverType("MULTIFRONTAL_CHOLESKY");
75  auto result = optimizer.optimize();
76 }
77 
78 int main(int args, char* argv[]) {
79  int numberNodes = stoi(argv[1]);
80  cout << "number of_nodes: " << numberNodes << endl;
81  testGtsam(numberNodes);
82  return 0;
83 }
gtsam::NonlinearOptimizer::optimize
virtual const Values & optimize()
Definition: NonlinearOptimizer.h:98
e
Array< double, 1, 3 > e(1./3., 0.5, 2.)
LevenbergMarquardtOptimizer.h
A nonlinear optimizer that uses the Levenberg-Marquardt trust-region scheme.
initial
Values initial
Definition: OdometryOptimize.cpp:2
vanilla::params
static const SmartProjectionParams params
Definition: smartFactorScenarios.h:69
result
Values result
Definition: OdometryOptimize.cpp:8
GaussNewtonOptimizer.h
BetweenFactor.h
gtsam::Pose3
Definition: Pose3.h:37
StereoFactor.h
A non-linear factor for stereo measurements.
gtsam::NonlinearFactorGraph
Definition: NonlinearFactorGraph.h:55
gtsam::NonlinearFactorGraph::addPrior
void addPrior(Key key, const T &prior, const SharedNoiseModel &model=nullptr)
Definition: NonlinearFactorGraph.h:199
gtsam::LevenbergMarquardtOptimizer
Definition: LevenbergMarquardtOptimizer.h:35
Cal3_S2Stereo.h
The most common 5DOF 3D->2D calibration + Stereo baseline.
NonlinearEquality.h
testGtsam
void testGtsam(int numberNodes)
Definition: Pose2SLAMStressTest.cpp:29
gtsam
traits
Definition: chartTesting.h:28
NonlinearFactorGraph.h
Factor Graph consisting of non-linear factors.
gtsam::Values
Definition: Values.h:65
std
Definition: BFloat16.h:88
args
Definition: pytypes.h:2163
gtsam::LevenbergMarquardtParams
Definition: LevenbergMarquardtParams.h:35
initial
Definition: testScenarioRunner.cpp:148
main
int main(int args, char *argv[])
Definition: Pose2SLAMStressTest.cpp:78
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
i
int i
Definition: BiCGSTAB_step_by_step.cpp:9
Values.h
A non-templated config holding any types of Manifold-group elements.
Pose3.h
3D Pose
gtsam::BetweenFactor
Definition: BetweenFactor.h:40
M
Matrix< RealScalar, Dynamic, Dynamic > M
Definition: bench_gemm.cpp:51


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