42 int main(
int argc,
char** argv)
45 string outputFilename;
48 commandLineArguments.
paramLeftOver(
"gm2dl-input", inputFilename,
"",
"gm2dl file which will be processed");
49 commandLineArguments.
paramLeftOver(
"gm2dl-output", outputFilename,
"",
"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 = inputGraph.
vertices().begin(); it != inputGraph.
vertices().end(); ++it) {
67 if (dynamic_cast<VertexCam*>(it->second)) {
87 assert(0 &&
"Failure adding camera vertex");
90 else if (dynamic_cast<VertexSBAPointXYZ*>(it->second)) {
97 assert(0 &&
"Failure adding camera vertex");
102 for (OptimizableGraph::EdgeSet::const_iterator it = inputGraph.
edges().begin(); it != inputGraph.
edges().end(); ++it) {
103 if (dynamic_cast<EdgeProjectP2SC*>(*it)) {
114 oe->
setMeasurement(Eigen::Vector3d(kx, ky, disparity / (fx * baseline)));
117 if (! outputGraph.
addEdge(oe)) {
118 assert(0 &&
"error adding edge");
123 cout <<
"Vertices in/out:\t" << inputGraph.
vertices().size() <<
" " << outputGraph.
vertices().size() << endl;
124 cout <<
"Edges in/out:\t" << inputGraph.
edges().size() <<
" " << outputGraph.
edges().size() << endl;
126 cout <<
"Writing output ... " << flush;
127 outputGraph.
save(outputFilename.c_str());
128 cout <<
"done." << endl;
int id() const
returns the id
Command line parsing of argc and argv.
const VertexIDMap & vertices() const
Vertex * vertex(int id)
returns the vertex number id appropriately casted
SBACam Vertex, (x,y,z,qw,qx,qy,qz) the parameterization for the increments constructed is a 6d vector...
virtual void setId(int id)
sets the id of the node in the graph be sure that the graph keeps consistent after changing the id ...
edge from a track to a depth camera node using a disparity measurement
bool setParameterId(int argNum, int paramId)
const VertexContainer & vertices() const
bool parseArgs(int argc, char **argv, bool exitOnError=true)
virtual bool save(std::ostream &os, int level=0) const
save the graph to a stream. Again uses the Factory system.
int main(int argc, char **argv)
const EdgeSet & edges() const
void paramLeftOver(const std::string &name, std::string &p, const std::string &defValue, const std::string &desc, bool optional=false)
EIGEN_STRONG_INLINE void setInformation(const InformationType &information)
const Eigen::Quaterniond & rotation() const
Vertex for a tracked point in space.
bool addParameter(Parameter *p)
void setEstimate(const EstimateType &et)
set the estimate for the vertex also calls updateCache()
virtual bool load(std::istream &is, bool createEdges=true)
load the graph from a stream. Uses the Factory singleton for creating the vertices and edges...
EIGEN_STRONG_INLINE const InformationType & information() const
information matrix of the constraint
virtual void setMeasurement(const Vector3D &m)
const EstimateType & estimate() const
return the current estimate of the vertex
3D pose Vertex, represented as an Isometry3D
void setKcam(double fx, double fy, double cx, double cy)
virtual bool addEdge(HyperGraph::Edge *e)
virtual bool addVertex(HyperGraph::Vertex *v, Data *userData)
EIGEN_STRONG_INLINE const Measurement & measurement() const
accessor functions for the measurement represented by the edge
const Vector3D & translation() const