Classes | Functions | Variables
City10000.h File Reference

Class for City10000 dataset. More...

#include <gtsam/geometry/Pose2.h>
#include <fstream>
Include dependency graph for City10000.h:
This graph shows which files directly or indirectly include this file:

Go to the source code of this file.

Classes

class  City10000Dataset
 

Functions

void writeResult (const Values &result, size_t numPoses, const std::string &filename="Hybrid_city10000.txt")
 Write the result of optimization to file. More...
 

Variables

const double kOpenLoopConstant = kOpenLoopModel->negLogConstant()
 
auto kOpenLoopModel = noiseModel::Diagonal::Sigmas(Vector3::Ones() * 10)
 
const double kPoseNoiseConstant = kPoseNoiseModel->negLogConstant()
 
auto kPoseNoiseModel
 
auto kPriorNoiseModel
 

Detailed Description

Class for City10000 dataset.

Author
Varun Agrawal
Date
February 3, 2025

Definition in file City10000.h.

Function Documentation

◆ writeResult()

void writeResult ( const Values result,
size_t  numPoses,
const std::string &  filename = "Hybrid_city10000.txt" 
)

Write the result of optimization to file.

Parameters
resultThe Values object with the final result.
num_posesThe number of poses to write to the file.
filenameThe file name to save the result to.

Definition at line 98 of file City10000.h.

Variable Documentation

◆ kOpenLoopConstant

const double kOpenLoopConstant = kOpenLoopModel->negLogConstant()

Definition at line 28 of file City10000.h.

◆ kOpenLoopModel

auto kOpenLoopModel = noiseModel::Diagonal::Sigmas(Vector3::Ones() * 10)

Definition at line 27 of file City10000.h.

◆ kPoseNoiseConstant

const double kPoseNoiseConstant = kPoseNoiseModel->negLogConstant()

Definition at line 35 of file City10000.h.

◆ kPoseNoiseModel

auto kPoseNoiseModel
Initial value:
= noiseModel::Diagonal::Sigmas(
(Vector(3) << 1.0 / 30.0, 1.0 / 30.0, 1.0 / 100.0).finished())

Definition at line 33 of file City10000.h.

◆ kPriorNoiseModel

auto kPriorNoiseModel
Initial value:
= noiseModel::Diagonal::Sigmas(
(Vector(3) << 0.0001, 0.0001, 0.0001).finished())

Definition at line 30 of file City10000.h.

ceres::Vector
Eigen::Matrix< double, Eigen::Dynamic, 1 > Vector
Definition: gtsam/3rdparty/ceres/eigen.h:38


gtsam
Author(s):
autogenerated on Wed Mar 19 2025 03:09:05