Go to the documentation of this file.
   37 using namespace gtsam;
 
   38 using namespace symbol_shorthand;  
 
   41 int main(
int argc, 
char* argv[]) {
 
   52   auto E1 = EssentialMatrix::FromPose3(poses[0].
between(poses[1]));
 
   53   auto E2 = EssentialMatrix::FromPose3(poses[0].
between(poses[2]));
 
   56   std::array<std::array<Point2, 8>, 4> 
p;
 
   57   for (
size_t i = 0; 
i < 4; ++
i) {
 
   59     for (
size_t j = 0; 
j < 8; ++
j) {
 
   68   for (
size_t a = 0; 
a < 4; ++
a) {
 
   69     size_t b = (
a + 1) % 4;  
 
   70     size_t c = (
a + 2) % 4;  
 
   73     std::vector<std::tuple<Point2, Point2, Point2>> tuples1, tuples2, tuples3;
 
   76     for (
size_t j = 0; 
j < 8; ++
j) {
 
   77       tuples1.emplace_back(
p[
a][
j], 
p[
b][
j], 
p[
c][
j]);
 
   78       tuples2.emplace_back(
p[
a][
j], 
p[
c][
j], 
p[
b][
j]);
 
   79       tuples3.emplace_back(
p[
c][
j], 
p[
b][
j], 
p[
a][
j]);
 
   94       return (std::string)edge;
 
  102   delta << 1, 1, 1, 1, 1;
 
  107   for (
size_t a = 0; 
a < 4; ++
a) {
 
  108     size_t b = (
a + 1) % 4;  
 
  109     size_t c = (
a + 2) % 4;  
 
  115   for (
size_t i = 0; 
i < 4; ++
i) {
 
  124   params.setlambdaInitial(1000.0);  
 
  125   params.setVerbosityLM(
"SUMMARY");
 
  129   cout << 
"Initial error = " << 
graph.
error(initialEstimate) << endl;
 
  134   E1.print(
"Ground Truth E1:\n");
 
  135   E2.print(
"Ground Truth E2:\n");
 
  
virtual const Values & optimize()
std::vector< Point3 > createPoints()
Create a set of ground-truth landmarks.
Array< double, 1, 3 > e(1./3., 0.5, 2.)
A nonlinear optimizer that uses the Levenberg-Marquardt trust-region scheme.
Calibration model with a single focal length and zero skew.
const KeyFormatter & formatter
Transfers points between views using essential matrices, optimizes for calibrations of the views,...
static const SmartProjectionParams params
const Cal3_S2 cal(focalLength, focalLength, 0.0, principalPoint.x(), principalPoint.y())
unsigned char chr() const
double error(const Values &values) const
Base class for all pinhole cameras.
Calibration model with a single focal length and zero skew.
int main(int argc, char *argv[])
const gtsam::Symbol key('X', 0)
std::vector< Pose3 > posesOnCircle(int num_cameras=8, double R=30)
void printErrors(const Values &values, const std::string &str="NonlinearFactorGraph: ", const KeyFormatter &keyFormatter=DefaultKeyFormatter, const std::function< bool(const Factor *, double, size_t)> &printCondition=[](const Factor *, double, size_t) {return true;}) const
void print(const std::string &str="", const KeyFormatter &keyFormatter=DefaultKeyFormatter) const
Factor Graph consisting of non-linear factors.
void insert(Key j, const Value &val)
T between(const T &t1, const T &t2)
static const CalibratedCamera camera(kDefaultPose)
NonlinearFactorGraph graph
std::uint64_t Key
Integer nonlinear key type.
Simple example for the structure-from-motion problems.
A non-templated config holding any types of Manifold-group elements.
3D Pose manifold SO(3) x R^3 and group SE(3)
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.
void print(const std::string &str="NonlinearFactorGraph: ", const KeyFormatter &keyFormatter=DefaultKeyFormatter) const override
gtsam
Author(s): 
autogenerated on Wed May 28 2025 03:01:15