g2o
Loading...
Searching...
No Matches
Functions
convert_sba_slam3d.cpp File Reference
#include <cassert>
#include <fstream>
#include <iostream>
#include "g2o/core/optimizable_graph.h"
#include "g2o/stuff/command_args.h"
#include "g2o/stuff/macros.h"
#include "g2o/types/sba/types_sba.h"
#include "g2o/types/slam3d/edge_se3_pointxyz_disparity.h"
#include "g2o/types/slam3d/parameter_camera.h"
Include dependency graph for convert_sba_slam3d.cpp:

Go to the source code of this file.

Functions

int main (int argc, char **argv)
 

Function Documentation

◆ main()

int main ( int  argc,
char **  argv 
)

Definition at line 41 of file convert_sba_slam3d.cpp.

41 {
42 string inputFilename;
43 string outputFilename;
44 // command line parsing
45 CommandArgs commandLineArguments;
46 commandLineArguments.paramLeftOver("gm2dl-input", inputFilename, "",
47 "gm2dl file which will be processed");
48 commandLineArguments.paramLeftOver("gm2dl-output", outputFilename, "",
49 "name of the output file");
50
51 commandLineArguments.parseArgs(argc, argv);
52
53 OptimizableGraph inputGraph;
54 bool loadStatus = inputGraph.load(inputFilename.c_str());
55 if (!loadStatus) {
56 cerr << "Error while loading input data" << endl;
57 return 1;
58 }
59
60 OptimizableGraph outputGraph;
61
62 // process all the vertices first
63 double fx = -1;
64 double baseline = -1;
65 bool firstCam = true;
66 for (OptimizableGraph::VertexIDMap::const_iterator it =
67 inputGraph.vertices().begin();
68 it != inputGraph.vertices().end(); ++it) {
69 if (dynamic_cast<VertexCam*>(it->second)) {
70 VertexCam* v = static_cast<VertexCam*>(it->second);
71 if (firstCam) {
72 firstCam = false;
74 camParams->setId(0);
75 const SBACam& c = v->estimate();
76 baseline = c.baseline;
77 fx = c.Kcam(0, 0);
78 camParams->setKcam(c.Kcam(0, 0), c.Kcam(1, 1), c.Kcam(0, 2),
79 c.Kcam(1, 2));
80 outputGraph.addParameter(camParams);
81 }
82
83 VertexSE3* ov = new VertexSE3;
84 ov->setId(v->id());
85 Eigen::Isometry3d p;
86 p = v->estimate().rotation();
87 p.translation() = v->estimate().translation();
88 ov->setEstimate(p);
89 if (!outputGraph.addVertex(ov)) {
90 assert(0 && "Failure adding camera vertex");
91 }
92 } else if (dynamic_cast<VertexPointXYZ*>(it->second)) {
93 VertexPointXYZ* v = static_cast<VertexPointXYZ*>(it->second);
94
96 ov->setId(v->id());
97 ov->setEstimate(v->estimate());
98 if (!outputGraph.addVertex(ov)) {
99 assert(0 && "Failure adding camera vertex");
100 }
101 }
102 }
103
104 for (OptimizableGraph::EdgeSet::const_iterator it =
105 inputGraph.edges().begin();
106 it != inputGraph.edges().end(); ++it) {
107 if (dynamic_cast<EdgeProjectP2SC*>(*it)) {
108 EdgeProjectP2SC* e = static_cast<EdgeProjectP2SC*>(*it);
109
111 oe->vertices()[0] = outputGraph.vertex(e->vertices()[1]->id());
112 oe->vertices()[1] = outputGraph.vertex(e->vertices()[0]->id());
113
114 double kx = e->measurement().x();
115 double ky = e->measurement().y();
116 double disparity = kx - e->measurement()(2);
117
118 oe->setMeasurement(Eigen::Vector3d(kx, ky, disparity / (fx * baseline)));
119 oe->setInformation(e->information()); // TODO convert information matrix
120 oe->setParameterId(0, 0);
121 if (!outputGraph.addEdge(oe)) {
122 assert(0 && "error adding edge");
123 }
124 }
125 }
126
127 cout << "Vertices in/out:\t" << inputGraph.vertices().size() << " "
128 << outputGraph.vertices().size() << endl;
129 cout << "Edges in/out:\t" << inputGraph.edges().size() << " "
130 << outputGraph.edges().size() << endl;
131
132 cout << "Writing output ... " << flush;
133 outputGraph.save(outputFilename.c_str());
134 cout << "done." << endl;
135 return 0;
136}
EIGEN_STRONG_INLINE const Measurement & measurement() const
accessor functions for the measurement represented by the edge
Definition base_edge.h:119
virtual void setMeasurement(const Measurement &m)
Definition base_edge.h:122
EIGEN_STRONG_INLINE const InformationType & information() const
information matrix of the constraint
Definition base_edge.h:107
void setInformation(const InformationType &information)
Definition base_edge.h:111
const EstimateType & estimate() const
return the current estimate of the vertex
void setEstimate(const EstimateType &et)
set the estimate for the vertex also calls updateCache()
Command line parsing of argc and argv.
bool parseArgs(int argc, char **argv, bool exitOnError=true)
void paramLeftOver(const std::string &name, std::string &p, const std::string &defValue, const std::string &desc, bool optional=false)
edge from a track to a depth camera node using a disparity measurement
const VertexContainer & vertices() const
int id() const
returns the id
const EdgeSet & edges() const
const VertexIDMap & vertices() const
bool setParameterId(int argNum, int paramId)
parameters for a camera
void setKcam(double fx, double fy, double cx, double cy)
void setId(int id_)
Definition parameter.cpp:33
Matrix3 Kcam
Definition sbacam.h:51
double baseline
Definition sbacam.h:52
const Quaternion & rotation() const
Definition se3quat.h:93
const Vector3 & translation() const
Definition se3quat.h:89
SBACam Vertex, (x,y,z,qw,qx,qy,qz) the parameterization for the increments constructed is a 6d vector...
Definition vertex_cam.h:43
Vertex for a tracked point in space.
3D pose Vertex, represented as an Isometry3
Definition vertex_se3.h:50
virtual bool addEdge(HyperGraph::Edge *e)
virtual bool save(std::ostream &os, int level=0) const
save the graph to a stream. Again uses the Factory system.
bool addParameter(Parameter *p)
virtual bool addVertex(HyperGraph::Vertex *v, Data *userData)
virtual bool load(std::istream &is)
Vertex * vertex(int id)
returns the vertex number id appropriately casted

References g2o::OptimizableGraph::addEdge(), g2o::OptimizableGraph::addParameter(), g2o::OptimizableGraph::addVertex(), g2o::SBACam::baseline, g2o::HyperGraph::edges(), g2o::BaseVertex< D, T >::estimate(), g2o::HyperGraph::Vertex::id(), g2o::BaseEdge< D, E >::information(), g2o::SBACam::Kcam, g2o::OptimizableGraph::load(), g2o::BaseEdge< D, E >::measurement(), g2o::CommandArgs::paramLeftOver(), g2o::CommandArgs::parseArgs(), g2o::SE3Quat::rotation(), g2o::OptimizableGraph::save(), g2o::BaseVertex< D, T >::setEstimate(), g2o::OptimizableGraph::Vertex::setId(), g2o::Parameter::setId(), g2o::BaseEdge< D, E >::setInformation(), g2o::ParameterCamera::setKcam(), g2o::BaseEdge< D, E >::setMeasurement(), g2o::OptimizableGraph::Edge::setParameterId(), g2o::SE3Quat::translation(), g2o::OptimizableGraph::vertex(), g2o::HyperGraph::Edge::vertices(), and g2o::HyperGraph::vertices().