41int main(
int argc,
char** argv) {
43 string outputFilename;
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");
51 commandLineArguments.
parseArgs(argc, argv);
54 bool loadStatus = inputGraph.
load(inputFilename.c_str());
56 cerr <<
"Error while loading input data" << endl;
66 for (OptimizableGraph::VertexIDMap::const_iterator it =
68 it != inputGraph.
vertices().end(); ++it) {
69 if (
dynamic_cast<VertexCam*
>(it->second)) {
90 assert(0 &&
"Failure adding camera vertex");
99 assert(0 &&
"Failure adding camera vertex");
104 for (OptimizableGraph::EdgeSet::const_iterator it =
105 inputGraph.
edges().begin();
106 it != inputGraph.
edges().end(); ++it) {
118 oe->
setMeasurement(Eigen::Vector3d(kx, ky, disparity / (fx * baseline)));
121 if (!outputGraph.
addEdge(oe)) {
122 assert(0 &&
"error adding edge");
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;
132 cout <<
"Writing output ... " << flush;
133 outputGraph.
save(outputFilename.c_str());
134 cout <<
"done." << endl;
EIGEN_STRONG_INLINE const Measurement & measurement() const
accessor functions for the measurement represented by the edge
virtual void setMeasurement(const Measurement &m)
EIGEN_STRONG_INLINE const InformationType & information() const
information matrix of the constraint
void setInformation(const InformationType &information)
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)
virtual void setId(int id)
void setKcam(double fx, double fy, double cx, double cy)
const Quaternion & rotation() const
const Vector3 & translation() const
SBACam Vertex, (x,y,z,qw,qx,qy,qz) the parameterization for the increments constructed is a 6d vector...
Vertex for a tracked point in space.
3D pose Vertex, represented as an Isometry3
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