Go to the documentation of this file.
   67 using namespace gtsam;
 
   88     for (
int r = 0; r < 6; ++r) {
 
   89         for (
int c = 0; 
c < 6; ++
c) {
 
  122                   const string &
filename, 
int iterCount) {
 
  124     string countStr = to_string(iterCount);
 
  125     string paddedCount = string(5 - countStr.length(), 
'0') + countStr;
 
  126     string fullFilename = 
filename + 
"_" + paddedCount + 
".g2o";
 
  129     cout << 
"\nSaved graph to: " << fullFilename << endl;
 
  149     ifstream factor_file(factor_loc.c_str());
 
  150     cout << 
"Reading factors data file: " << factor_loc << endl;
 
  160     const double lag = 1.0;
 
  163     isamParameters.
print();
 
  176     while (getline(factor_file, line)) {
 
  177         if (line.empty()) 
continue;  
 
  178         cout << 
"\n======================== Processing line " << ++lineCount
 
  179              << 
" =========================" << endl;
 
  181         istringstream iss(line);
 
  185         if (factorType == 
PRIOR) {
 
  192             double x, 
y, 
z, roll, pitch, yaw;
 
  193             iss >> timestamp >> 
key >> 
x >> 
y >> 
z >> roll >> pitch >> yaw;
 
  196             auto noise = noiseModel::Gaussian::Covariance(cov);
 
  199             cout << 
"Add PRIOR factor on key " << 
key << endl;
 
  203                 newTimestamps[
X(
key)] = timestamp;
 
  205         } 
else if (factorType == 
BETWEEN) {
 
  213             double x1, 
y1, 
z1, roll1, pitch1, yaw1;
 
  214             iss >> 
x1 >> 
y1 >> 
z1 >> roll1 >> pitch1 >> yaw1;
 
  217             auto noise = noiseModel::Gaussian::Covariance(cov);
 
  220             cout << 
"Add BETWEEN factor: " << 
key1 << 
" -> " << 
key2 << endl;
 
  224                 newTimestamps[
X(
key2)] = timestamp;
 
  227             cerr << 
"Unknown factor type: " << factorType << endl;
 
  232         cout << 
"Before update - Graph has " << smoother.
getFactors().
size()
 
  234         cout << 
"New factors: " << newFactors.
size()
 
  235              << 
", New values: " << newValues.
size() << endl;
 
  239             smoother.
update(newFactors, newValues, newTimestamps);
 
  241             size_t maxExtraIterations = 3;
 
  242             for (
size_t i = 1; 
i < maxExtraIterations; ++
i) {
 
  246             cout << 
"After update - Graph has " << smoother.
getFactors().
size()
 
  251             if (!currentEstimate.
empty()) {
 
  253                 Key lastKey = currentEstimate.
keys().back();
 
  254                 lastPose = currentEstimate.
at<
Pose3>(lastKey);
 
  260             newTimestamps.clear();
 
  261         } 
catch (
const exception &
e) {
 
  262             cerr << 
"Smoother update failed: " << 
e.what() << endl;
 
  
const Symbol key1('v', 1)
void print(const std::string &str="") const
print iSAM2 parameters
An iSAM2-based fixed-lag smoother.
static const Pose3 pose(Rot3(Vector3(1, -1, -1).asDiagonal()), Point3(0, 0, 0.5))
Array< double, 1, 3 > e(1./3., 0.5, 2.)
Eigen::Matrix< double, 6, 6 > Matrix6
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).
Class compose(const Class &g) const
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 x
int main()
Main function: Reads poses data from a text file and performs incremental fixed-lag smoothing.
Matrix6 readCovarianceMatrix(istringstream &iss)
Read a 6x6 covariance matrix from an input string stream.
Pose3 createPose(double x, double y, double z, double roll, double pitch, double yaw)
Create a Pose3 object from individual pose parameters.
const ValueType at(Key j) const
virtual void resize(size_t size)
RelinearizationThreshold relinearizeThreshold
Result update(const NonlinearFactorGraph &newFactors=NonlinearFactorGraph(), const Values &newTheta=Values(), const KeyTimestampMap ×tamps=KeyTimestampMap(), const FactorIndices &factorsToRemove=FactorIndices()) override
const Symbol key2('v', 2)
utility functions for loading datasets
void addPrior(Key key, const T &prior, const SharedNoiseModel &model=nullptr)
const gtsam::Symbol key('X', 0)
Incremental update functionality (ISAM2) for BayesTree, with fluid relinearization.
const NonlinearFactorGraph & getFactors() const
std::map< Key, double > KeyTimestampMap
Typedef for a Key-Timestamp map/database.
Factor Graph consisting of non-linear factors.
bool findUnusedFactorSlots
void insert(Key j, const Value &val)
GTSAM_EXPORT std::string findExampleDataFile(const std::string &name)
Values calculateEstimate() const override
NonlinearFactorGraph graph
std::uint64_t Key
Integer nonlinear key type.
A non-templated config holding any types of Manifold-group elements.
3D Pose manifold SO(3) x R^3 and group SE(3)
IsDerived< DERIVEDFACTOR > emplace_shared(Args &&... args)
Emplace a shared pointer to factor of given type.
void writeG2o(const NonlinearFactorGraph &graph, const Values &estimate, const std::string &filename)
This function writes a g2o file from NonlinearFactorGraph and a Values structure.
gtsam
Author(s): 
autogenerated on Wed May 28 2025 03:01:27