g2o
Loading...
Searching...
No Matches
Functions
g2o_anonymize_observations.cpp File Reference
#include <cstdlib>
#include <fstream>
#include <iostream>
#include <sstream>
#include "g2o/core/optimizable_graph.h"
#include "g2o/stuff/command_args.h"
#include "g2o/types/slam2d/types_slam2d.h"
#include "g2o/types/slam3d/types_slam3d.h"
Include dependency graph for g2o_anonymize_observations.cpp:

Go to the source code of this file.

Functions

template<typename T >
bool anonymizeLandmarkEdge (HyperGraph::Edge *e_, OptimizableGraph &g)
 
template<typename T >
bool anonymizePoseEdge (HyperGraph::Edge *e_, OptimizableGraph &g)
 
int main (int argc, char **argv)
 

Function Documentation

◆ anonymizeLandmarkEdge()

template<typename T >
bool anonymizeLandmarkEdge ( HyperGraph::Edge e_,
OptimizableGraph g 
)

Definition at line 41 of file g2o_anonymize_observations.cpp.

41 {
42 T* e = dynamic_cast<T*>(e_);
43 if (!e) return false;
44 g.setEdgeVertex(e, 1, 0);
45 return true;
46}
virtual bool setEdgeVertex(HyperGraph::Edge *e, int pos, HyperGraph::Vertex *v)

References g2o::OptimizableGraph::setEdgeVertex().

◆ anonymizePoseEdge()

template<typename T >
bool anonymizePoseEdge ( HyperGraph::Edge e_,
OptimizableGraph g 
)

Definition at line 49 of file g2o_anonymize_observations.cpp.

49 {
50 T* e = dynamic_cast<T*>(e_);
51 if (!e) return false;
52 HyperGraph::Vertex* from = e->vertex(0);
53 HyperGraph::Vertex* to = e->vertex(1);
54 if (from && to && from != to) {
55 int deltaId = abs(from->id() - to->id());
56 if (deltaId > 1) {
57 if (from->id() > to->id()) {
58 g.setEdgeVertex(e, 0, 0);
59 } else {
60 g.setEdgeVertex(e, 1, 0);
61 }
62 return true;
63 }
64 }
65 return false;
66}
abstract Vertex, your types must derive from that one
int id() const
returns the id
Jet< T, N > abs(const Jet< T, N > &f)
Definition jet.h:424

References g2o::HyperGraph::Vertex::id(), and g2o::OptimizableGraph::setEdgeVertex().

◆ main()

int main ( int  argc,
char **  argv 
)

Definition at line 68 of file g2o_anonymize_observations.cpp.

68 {
69 CommandArgs arg;
70 std::string outputFilename;
71 std::string inputFilename;
72 arg.param("o", outputFilename, "anon.g2o", "output file");
73 arg.paramLeftOver("graph-output", inputFilename, "",
74 "graph file which will be read", true);
75 arg.parseArgs(argc, argv);
76 OptimizableGraph graph;
77
78 if (inputFilename.size() == 0) {
79 cerr << "No input data specified" << endl;
80 return 0;
81 } else if (inputFilename == "-") {
82 cerr << "Read input from stdin" << endl;
83 if (!graph.load(cin)) {
84 cerr << "Error loading graph" << endl;
85 return 2;
86 }
87 } else {
88 cerr << "Read input from " << inputFilename << endl;
89 ifstream ifs(inputFilename.c_str());
90 if (!ifs) {
91 cerr << "Failed to open file" << endl;
92 return 1;
93 }
94 if (!graph.load(ifs)) {
95 cerr << "Error loading graph" << endl;
96 return 2;
97 }
98 }
99
100 for (HyperGraph::EdgeSet::iterator it = graph.edges().begin();
101 it != graph.edges().end(); ++it) {
102 HyperGraph::Edge* e = *it;
103 if (anonymizeLandmarkEdge<EdgeSE2PointXY>(e, graph)) continue;
104 if (anonymizeLandmarkEdge<EdgeSE2PointXYOffset>(e, graph)) continue;
105 if (anonymizeLandmarkEdge<EdgeSE2PointXYBearing>(e, graph)) continue;
106 if (anonymizePoseEdge<EdgeSE2>(e, graph)) continue;
107 if (anonymizePoseEdge<EdgeSE2Offset>(e, graph)) continue;
108 }
109
110 ofstream os(outputFilename.c_str());
111 graph.save(os);
112}
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)
void param(const std::string &name, bool &p, bool defValue, const std::string &desc)
const EdgeSet & edges() const
virtual bool save(std::ostream &os, int level=0) const
save the graph to a stream. Again uses the Factory system.
virtual bool load(std::istream &is)

References g2o::HyperGraph::edges(), g2o::OptimizableGraph::load(), g2o::CommandArgs::param(), g2o::CommandArgs::paramLeftOver(), g2o::CommandArgs::parseArgs(), and g2o::OptimizableGraph::save().