File: FisheyeExample.cpp

package info (click to toggle)
gtsam 4.2.0%2Bdfsg-1
  • links: PTS, VCS
  • area: main
  • in suites: trixie
  • size: 46,096 kB
  • sloc: cpp: 127,191; python: 14,312; xml: 8,442; makefile: 250; sh: 119; ansic: 101
file content (129 lines) | stat: -rw-r--r-- 4,948 bytes parent folder | download | duplicates (2)
1
2
3
4
5
6
7
8
9
10
11
12
13
14
15
16
17
18
19
20
21
22
23
24
25
26
27
28
29
30
31
32
33
34
35
36
37
38
39
40
41
42
43
44
45
46
47
48
49
50
51
52
53
54
55
56
57
58
59
60
61
62
63
64
65
66
67
68
69
70
71
72
73
74
75
76
77
78
79
80
81
82
83
84
85
86
87
88
89
90
91
92
93
94
95
96
97
98
99
100
101
102
103
104
105
106
107
108
109
110
111
112
113
114
115
116
117
118
119
120
121
122
123
124
125
126
127
128
129
/* ----------------------------------------------------------------------------

 * GTSAM Copyright 2010, Georgia Tech Research Corporation,
 * Atlanta, Georgia 30332-0415
 * All Rights Reserved
 * Authors: Frank Dellaert, et al. (see THANKS for the full author list)

 * See LICENSE for the license information

 * -------------------------------------------------------------------------- */

/**
 * @file    FisheyeExample.cpp
 * @brief   A visualSLAM example for the structure-from-motion problem on a
 * simulated dataset. This version uses a fisheye camera model and a GaussNewton
 * solver to solve the graph in one batch
 * @author  ghaggin
 * @Date    Apr 9,2020
 */

/**
 * A structure-from-motion example with landmarks
 *  - The landmarks form a 10 meter cube
 *  - The robot rotates around the landmarks, always facing towards the cube
 */

// For loading the data
#include "SFMdata.h"

// Camera observations of landmarks will be stored as Point2 (x, y).
#include <gtsam/geometry/Point2.h>

// Each variable in the system (poses and landmarks) must be identified with a
// unique key. We can either use simple integer keys (1, 2, 3, ...) or symbols
// (X1, X2, L1). Here we will use Symbols
#include <gtsam/inference/Symbol.h>

// Use GaussNewtonOptimizer to solve graph
#include <gtsam/nonlinear/GaussNewtonOptimizer.h>
#include <gtsam/nonlinear/NonlinearFactorGraph.h>
#include <gtsam/nonlinear/Values.h>

// In GTSAM, measurement functions are represented as 'factors'. Several common
// factors have been provided with the library for solving robotics/SLAM/Bundle
// Adjustment problems. Here we will use Projection factors to model the
// camera's landmark observations. Also, we will initialize the robot at some
// location using a Prior factor.
#include <gtsam/geometry/Cal3Fisheye.h>
#include <gtsam/slam/PriorFactor.h>
#include <gtsam/slam/ProjectionFactor.h>

#include <fstream>
#include <vector>

using namespace std;
using namespace gtsam;

using symbol_shorthand::L;  // for landmarks
using symbol_shorthand::X;  // for poses

/* ************************************************************************* */
int main(int argc, char *argv[]) {
  // Define the camera calibration parameters
  auto K = boost::make_shared<Cal3Fisheye>(
      278.66, 278.48, 0.0, 319.75, 241.96, -0.013721808247486035,
      0.020727425669427896, -0.012786476702685545, 0.0025242267320687625);

  // Define the camera observation noise model, 1 pixel stddev
  auto measurementNoise = noiseModel::Isotropic::Sigma(2, 1.0);

  // Create the set of ground-truth landmarks
  const vector<Point3> points = createPoints();

  // Create the set of ground-truth poses
  const vector<Pose3> poses = createPoses();

  // Create a Factor Graph and Values to hold the new data
  NonlinearFactorGraph graph;
  Values initialEstimate;

  // Add a prior on pose x0, 0.1 rad on roll,pitch,yaw, and 30cm std on x,y,z
  auto posePrior = noiseModel::Diagonal::Sigmas(
      (Vector(6) << Vector3::Constant(0.1), Vector3::Constant(0.3)).finished());
  graph.emplace_shared<PriorFactor<Pose3>>(X(0), poses[0], posePrior);

  // Add a prior on landmark l0
  auto pointPrior = noiseModel::Isotropic::Sigma(3, 0.1);
  graph.emplace_shared<PriorFactor<Point3>>(L(0), points[0], pointPrior);

  // Add initial guesses to all observed landmarks
  // Intentionally initialize the variables off from the ground truth
  static const Point3 kDeltaPoint(-0.25, 0.20, 0.15);
  for (size_t j = 0; j < points.size(); ++j)
    initialEstimate.insert<Point3>(L(j), points[j] + kDeltaPoint);

  // Loop over the poses, adding the observations to the graph
  for (size_t i = 0; i < poses.size(); ++i) {
    // Add factors for each landmark observation
    for (size_t j = 0; j < points.size(); ++j) {
      PinholeCamera<Cal3Fisheye> camera(poses[i], *K);
      Point2 measurement = camera.project(points[j]);
      graph.emplace_shared<GenericProjectionFactor<Pose3, Point3, Cal3Fisheye>>(
          measurement, measurementNoise, X(i), L(j), K);
    }

    // Add an initial guess for the current pose
    // Intentionally initialize the variables off from the ground truth
    static const Pose3 kDeltaPose(Rot3::Rodrigues(-0.1, 0.2, 0.25),
                                  Point3(0.05, -0.10, 0.20));
    initialEstimate.insert(X(i), poses[i] * kDeltaPose);
  }

  GaussNewtonParams params;
  params.setVerbosity("TERMINATION");
  params.maxIterations = 10000;

  std::cout << "Optimizing the factor graph" << std::endl;
  GaussNewtonOptimizer optimizer(graph, initialEstimate, params);
  Values result = optimizer.optimize();
  std::cout << "Optimization complete" << std::endl;

  std::cout << "initial error=" << graph.error(initialEstimate) << std::endl;
  std::cout << "final error=" << graph.error(result) << std::endl;

  graph.saveGraph("examples/vio_batch.dot", result);

  return 0;
}
/* ************************************************************************* */