#include <iostream>#include <string>#include <gtsam/geometry/Pose3.h>#include <gtsam/nonlinear/ISAM2.h>#include <gtsam/nonlinear/Values.h>#include <gtsam/nonlinear/NonlinearFactorGraph.h>#include <gtsam/slam/BetweenFactor.h>#include <gtsam/nonlinear/IncrementalFixedLagSmoother.h>#include <gtsam/inference/Symbol.h>#include <gtsam/slam/dataset.h>
Go to the source code of this file.
Typedefs | |
| typedef Eigen::Matrix< double, 6, 6 > | Matrix6 |
Enumerations | |
| enum | FactorType { PRIOR = 0, BETWEEN = 1 } |
Functions | |
| Pose3 | createPose (double x, double y, double z, double roll, double pitch, double yaw) |
| Create a Pose3 object from individual pose parameters. More... | |
| int | main () |
| Main function: Reads poses data from a text file and performs incremental fixed-lag smoothing. More... | |
| Matrix6 | readCovarianceMatrix (istringstream &iss) |
| Read a 6x6 covariance matrix from an input string stream. More... | |
| void | saveG2oGraph (const NonlinearFactorGraph &graph, const Values &estimate, const string &filename, int iterCount) |
| Save the factor graph and estimates to a .g2o file (for visualization/debugging). More... | |
| typedef Eigen::Matrix<double, 6, 6> Matrix6 |
Definition at line 77 of file IncrementalFixedLagSmootherExample.cpp.
| enum FactorType |
| Enumerator | |
|---|---|
| PRIOR | |
| BETWEEN | |
Definition at line 72 of file IncrementalFixedLagSmootherExample.cpp.
| Pose3 createPose | ( | double | x, |
| double | y, | ||
| double | z, | ||
| double | roll, | ||
| double | pitch, | ||
| double | yaw | ||
| ) |
Create a Pose3 object from individual pose parameters.
| x | Translation in x |
| y | Translation in y |
| z | Translation in z |
| roll | Rotation about x-axis |
| pitch | Rotation about y-axis |
| yaw | Rotation about z-axis |
Definition at line 108 of file IncrementalFixedLagSmootherExample.cpp.
| int main | ( | ) |
Main function: Reads poses data from a text file and performs incremental fixed-lag smoothing.
Data Flow: 1) Parse lines from "IncrementalFixedLagSmootherTestData.txt". 2) For each line:
Format: PRIOR factor factor_type timestamp key pose(x y z roll pitch yaw) cov(6x6)
Format: BETWEEN factor factor_type timestamp key1 key2 pose(x y z roll pitch yaw) cov(6x6)
Definition at line 147 of file IncrementalFixedLagSmootherExample.cpp.
| Matrix6 readCovarianceMatrix | ( | istringstream & | iss | ) |
Read a 6x6 covariance matrix from an input string stream.
| iss | Input string stream containing covariance entries. |
Definition at line 86 of file IncrementalFixedLagSmootherExample.cpp.
| void saveG2oGraph | ( | const NonlinearFactorGraph & | graph, |
| const Values & | estimate, | ||
| const string & | filename, | ||
| int | iterCount | ||
| ) |
Save the factor graph and estimates to a .g2o file (for visualization/debugging).
| graph | The factor graph |
| estimate | Current estimates of all variables |
| filename | Base filename for saving |
| iterCount | Iteration count to differentiate successive outputs |
Definition at line 121 of file IncrementalFixedLagSmootherExample.cpp.