Go to the documentation of this file.
   56 using namespace gtsam;
 
   62 int main(
int argc, 
char *argv[]) {
 
   64   auto K = std::make_shared<Cal3Fisheye>(
 
   65       278.66, 278.48, 0.0, 319.75, 241.96, -0.013721808247486035,
 
   66       0.020727425669427896, -0.012786476702685545, 0.0025242267320687625);
 
   69   auto measurementNoise = noiseModel::Isotropic::Sigma(2, 1.0);
 
   82   auto posePrior = noiseModel::Diagonal::Sigmas(
 
   83       (
Vector(6) << Vector3::Constant(0.1), Vector3::Constant(0.3)).finished());
 
   87   auto pointPrior = noiseModel::Isotropic::Sigma(3, 0.1);
 
   92   static const Point3 kDeltaPoint(-0.25, 0.20, 0.15);
 
   93   for (
size_t j = 0; 
j < points.
size(); ++
j)
 
   97   for (
size_t i = 0; 
i < poses.
size(); ++
i) {
 
   99     for (
size_t j = 0; 
j < points.
size(); ++
j) {
 
  108     static const Pose3 kDeltaPose(Rot3::Rodrigues(-0.1, 0.2, 0.25),
 
  109                                   Point3(0.05, -0.10, 0.20));
 
  110     initialEstimate.
insert(
X(
i), poses[
i] * kDeltaPose);
 
  114   params.setVerbosity(
"TERMINATION");
 
  115   params.maxIterations = 10000;
 
  117   std::cout << 
"Optimizing the factor graph" << std::endl;
 
  120   std::cout << 
"Optimization complete" << std::endl;
 
  122   std::cout << 
"initial error=" << 
graph.
error(initialEstimate) << std::endl;
 
  
virtual const Values & optimize()
Reprojection of a LANDMARK to a 2D point.
std::vector< Point3 > createPoints()
Create a set of ground-truth landmarks.
void saveGraph(const std::string &filename, const Values &values, const KeyFormatter &keyFormatter=DefaultKeyFormatter, const GraphvizFormatting &writer=GraphvizFormatting()) const
output to file with graphviz format, with Values/extra options.
static const SmartProjectionParams params
double error(const Values &values) const
int main(int argc, char *argv[])
std::vector< Pose3 > createPoses(const Pose3 &init=Pose3(Rot3::Ypr(M_PI_2, 0, -M_PI_2), {30, 0, 0}), const Pose3 &delta=Pose3(Rot3::Ypr(0, -M_PI_4, 0), {sin(M_PI_4) *30, 0, 30 *(1 - sin(M_PI_4))}), int steps=8)
Factor Graph consisting of non-linear factors.
void insert(Key j, const Value &val)
static const CalibratedCamera camera(kDefaultPose)
NonlinearFactorGraph graph
Simple example for the structure-from-motion problems.
Eigen::Matrix< double, Eigen::Dynamic, 1 > Vector
static Point2 measurement(323.0, 240.0)
A non-templated config holding any types of Manifold-group elements.
Point2 project(const Point3 &point, OptionalJacobian< 2, 6 > Dcamera={}, OptionalJacobian< 2, 3 > Dpoint={}) const
IsDerived< DERIVEDFACTOR > emplace_shared(Args &&... args)
Emplace a shared pointer to factor of given type.
Calibration of a fisheye camera.
gtsam
Author(s): 
autogenerated on Wed May 28 2025 03:01:17