RangeISAMExample_plaza2.cpp
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 // Both relative poses and recovered trajectory poses will be stored as Pose2 objects
20 #include <gtsam/geometry/Pose2.h>
21 
22 // Each variable in the system (poses and landmarks) must be identified with a unique key.
23 // We can either use simple integer keys (1, 2, 3, ...) or symbols (X1, X2, L1).
24 // Here we will use Symbols
25 #include <gtsam/inference/Symbol.h>
26 
27 // We want to use iSAM2 to solve the range-SLAM problem incrementally
28 #include <gtsam/nonlinear/ISAM2.h>
29 
30 // iSAM2 requires as input a set set of new factors to be added stored in a factor graph,
31 // and initial guesses for any new variables used in the added factors
33 #include <gtsam/nonlinear/Values.h>
34 
35 // We will use a non-liear solver to batch-inituialize from the first 150 frames
37 
38 // In GTSAM, measurement functions are represented as 'factors'. Several common factors
39 // have been provided with the library for solving robotics SLAM problems.
41 #include <gtsam/sam/RangeFactor.h>
42 #include <gtsam/slam/dataset.h>
43 
44 // Standard headers, added last, so we know headers above work on their own
45 #include <fstream>
46 #include <iostream>
47 
48 using namespace std;
49 using namespace gtsam;
50 namespace NM = gtsam::noiseModel;
51 
52 // data available at http://www.frc.ri.cmu.edu/projects/emergencyresponse/RangeData/
53 // Datafile format (from http://www.frc.ri.cmu.edu/projects/emergencyresponse/RangeData/log.html)
54 
55 // load the odometry
56 // DR: Odometry Input (delta distance traveled and delta heading change)
57 // Time (sec) Delta Dist. Trav. (m) Delta Heading (rad)
58 typedef pair<double, Pose2> TimedOdometry;
59 list<TimedOdometry> readOdometry() {
60  list<TimedOdometry> odometryList;
61  string data_file = findExampleDataFile("Plaza2_DR.txt");
62  ifstream is(data_file.c_str());
63 
64  while (is) {
65  double t, distance_traveled, delta_heading;
66  is >> t >> distance_traveled >> delta_heading;
67  odometryList.push_back(
68  TimedOdometry(t, Pose2(distance_traveled, 0, delta_heading)));
69  }
70  is.clear(); /* clears the end-of-file and error flags */
71  return odometryList;
72 }
73 
74 // load the ranges from TD
75 // Time (sec) Sender / Antenna ID Receiver Node ID Range (m)
76 typedef boost::tuple<double, size_t, double> RangeTriple;
77 vector<RangeTriple> readTriples() {
78  vector<RangeTriple> triples;
79  string data_file = findExampleDataFile("Plaza2_TD.txt");
80  ifstream is(data_file.c_str());
81 
82  while (is) {
83  double t, sender, range;
84  size_t receiver;
85  is >> t >> sender >> receiver >> range;
86  triples.push_back(RangeTriple(t, receiver, range));
87  }
88  is.clear(); /* clears the end-of-file and error flags */
89  return triples;
90 }
91 
92 // main
93 int main (int argc, char** argv) {
94 
95  // load Plaza2 data
96  list<TimedOdometry> odometry = readOdometry();
97 // size_t M = odometry.size();
98 
99  vector<RangeTriple> triples = readTriples();
100  size_t K = triples.size();
101 
102  // parameters
103  size_t minK = 150; // minimum number of range measurements to process initially
104  size_t incK = 25; // minimum number of range measurements to process after
105  bool groundTruth = false;
106  bool robust = true;
107 
108  // Set Noise parameters
109  Vector priorSigmas = Vector3(1,1,M_PI);
110  Vector odoSigmas = Vector3(0.05, 0.01, 0.1);
111  double sigmaR = 100; // range standard deviation
112  const NM::Base::shared_ptr // all same type
113  priorNoise = NM::Diagonal::Sigmas(priorSigmas), //prior
114  odoNoise = NM::Diagonal::Sigmas(odoSigmas), // odometry
115  gaussian = NM::Isotropic::Sigma(1, sigmaR), // non-robust
116  tukey = NM::Robust::Create(NM::mEstimator::Tukey::Create(15), gaussian), //robust
117  rangeNoise = robust ? tukey : gaussian;
118 
119  // Initialize iSAM
120  ISAM2 isam;
121 
122  // Add prior on first pose
123  Pose2 pose0 = Pose2(-34.2086489999201, 45.3007639991120,
124  M_PI - 2.02108900000000);
125  NonlinearFactorGraph newFactors;
126  newFactors.addPrior(0, pose0, priorNoise);
127  Values initial;
128  initial.insert(0, pose0);
129 
130  // initialize points
131  if (groundTruth) { // from TL file
132  initial.insert(symbol('L', 1), Point2(-68.9265, 18.3778));
133  initial.insert(symbol('L', 6), Point2(-37.5805, 69.2278));
134  initial.insert(symbol('L', 0), Point2(-33.6205, 26.9678));
135  initial.insert(symbol('L', 5), Point2(1.7095, -5.8122));
136  } else { // drawn from sigma=1 Gaussian in matlab version
137  initial.insert(symbol('L', 1), Point2(3.5784, 2.76944));
138  initial.insert(symbol('L', 6), Point2(-1.34989, 3.03492));
139  initial.insert(symbol('L', 0), Point2(0.725404, -0.0630549));
140  initial.insert(symbol('L', 5), Point2(0.714743, -0.204966));
141  }
142 
143  // set some loop variables
144  size_t i = 1; // step counter
145  size_t k = 0; // range measurement counter
146  bool initialized = false;
147  Pose2 lastPose = pose0;
148  size_t countK = 0;
149 
150  // Loop over odometry
151  gttic_(iSAM);
152  for(const TimedOdometry& timedOdometry: odometry) {
153  //--------------------------------- odometry loop -----------------------------------------
154  double t;
155  Pose2 odometry;
156  boost::tie(t, odometry) = timedOdometry;
157 
158  // add odometry factor
159  newFactors.push_back(BetweenFactor<Pose2>(i-1, i, odometry, odoNoise));
160 
161  // predict pose and add as initial estimate
162  Pose2 predictedPose = lastPose.compose(odometry);
163  lastPose = predictedPose;
164  initial.insert(i, predictedPose);
165 
166  // Check if there are range factors to be added
167  while (k < K && t >= boost::get<0>(triples[k])) {
168  size_t j = boost::get<1>(triples[k]);
169  double range = boost::get<2>(triples[k]);
170  newFactors.push_back(RangeFactor<Pose2, Point2>(i, symbol('L', j), range,rangeNoise));
171  k = k + 1;
172  countK = countK + 1;
173  }
174 
175  // Check whether to update iSAM 2
176  if ((k > minK) && (countK > incK)) {
177  if (!initialized) { // Do a full optimize for first minK ranges
178  gttic_(batchInitialization);
179  LevenbergMarquardtOptimizer batchOptimizer(newFactors, initial);
180  initial = batchOptimizer.optimize();
181  gttoc_(batchInitialization);
182  initialized = true;
183  }
184  gttic_(update);
185  isam.update(newFactors, initial);
186  gttoc_(update);
187  gttic_(calculateEstimate);
189  gttoc_(calculateEstimate);
190  lastPose = result.at<Pose2>(i);
191  newFactors = NonlinearFactorGraph();
192  initial = Values();
193  countK = 0;
194  }
195  i += 1;
196  //--------------------------------- odometry loop -----------------------------------------
197  } // end for
198  gttoc_(iSAM);
199 
200  // Print timings
201  tictoc_print_();
202 
203  exit(0);
204 }
205 
list< TimedOdometry > readOdometry()
virtual const Values & optimize()
#define gttic_(label)
Definition: timing.h:230
def update(text)
Definition: relicense.py:46
Eigen::Vector3d Vector3
Definition: Vector.h:43
A non-templated config holding any types of Manifold-group elements.
Factor Graph consisting of non-linear factors.
void insert(Key j, const Value &val)
Definition: Values.cpp:140
Vector2 Point2
Definition: Point2.h:27
#define M_PI
Definition: main.h:78
static Cal3_S2 K(500, 500, 0.1, 640/2, 480/2)
Values initial
Definition: Half.h:150
IsDerived< DERIVEDFACTOR > push_back(boost::shared_ptr< DERIVEDFACTOR > factor)
Add a factor directly using a shared_ptr.
Definition: FactorGraph.h:166
static shared_ptr Create(const RobustModel::shared_ptr &robust, const NoiseModel::shared_ptr noise)
Definition: NoiseModel.cpp:665
boost::tuple< double, size_t, double > RangeTriple
pair< double, Pose2 > TimedOdometry
void addPrior(Key key, const T &prior, const SharedNoiseModel &model=nullptr)
string findExampleDataFile(const string &name)
Definition: dataset.cpp:65
Values calculateEstimate() const
Definition: ISAM2.cpp:763
Class compose(const Class &g) const
Definition: Lie.h:47
SharedDiagonal odoNoise
Eigen::VectorXd Vector
Definition: Vector.h:38
Values result
const ValueType at(Key j) const
Definition: Values-inl.h:342
Incremental update functionality (ISAM2) for BayesTree, with fluid relinearization.
A nonlinear optimizer that uses the Levenberg-Marquardt trust-region scheme.
void tictoc_print_()
Definition: timing.h:253
NonlinearISAM isam(relinearizeInterval)
Key symbol(unsigned char c, std::uint64_t j)
boost::shared_ptr< Base > shared_ptr
Definition: NoiseModel.h:56
static Pose3 pose0
traits
Definition: chartTesting.h:28
std::vector< float > Values
vector< RangeTriple > readTriples()
static shared_ptr Sigmas(const Vector &sigmas, bool smart=true)
Definition: NoiseModel.cpp:270
virtual ISAM2Result update(const NonlinearFactorGraph &newFactors=NonlinearFactorGraph(), const Values &newTheta=Values(), const FactorIndices &removeFactorIndices=FactorIndices(), const boost::optional< FastMap< Key, int > > &constrainedKeys=boost::none, const boost::optional< FastList< Key > > &noRelinKeys=boost::none, const boost::optional< FastList< Key > > &extraReelimKeys=boost::none, bool force_relinearize=false)
Definition: ISAM2.cpp:396
noiseModel::Diagonal::shared_ptr priorNoise
Pose2 odometry(2.0, 0.0, 0.0)
int main(int argc, char **argv)
2D Pose
#define gttoc_(label)
Definition: timing.h:235
utility functions for loading datasets
std::ptrdiff_t j
Point2 t(10, 10)
static shared_ptr Sigma(size_t dim, double sigma, bool smart=true)
Definition: NoiseModel.cpp:567
All noise models live in the noiseModel namespace.


gtsam
Author(s):
autogenerated on Sat May 8 2021 02:43:48