g2o
Functions
create_sphere.cpp File Reference
#include <iostream>
#include <fstream>
#include <vector>
#include <cmath>
#include <Eigen/Core>
#include <Eigen/StdVector>
#include "g2o/types/slam3d/vertex_se3.h"
#include "g2o/types/slam3d/edge_se3.h"
#include "g2o/stuff/sampler.h"
#include "g2o/stuff/command_args.h"
#include "g2o/core/factory.h"
Include dependency graph for create_sphere.cpp:

Go to the source code of this file.

Functions

int main (int argc, char **argv)
 

Function Documentation

int main ( int  argc,
char **  argv 
)

Definition at line 44 of file create_sphere.cpp.

References g2o::BaseVertex< D, T >::estimate(), g2o::GaussianSampler< SampleType, CovarianceType >::generateSample(), g2o::HyperGraph::Vertex::id(), g2o::EdgeSE3::initialEstimate(), M_PI, g2o::BaseEdge< D, E >::measurement(), g2o::CommandArgs::param(), g2o::CommandArgs::parseArgs(), g2o::GaussianSampler< SampleType, CovarianceType >::setDistribution(), g2o::BaseVertex< D, T >::setEstimate(), g2o::OptimizableGraph::Vertex::setId(), g2o::BaseEdge< D, E >::setInformation(), g2o::EdgeSE3::setMeasurement(), g2o::HyperGraph::Edge::setVertex(), g2o::HyperGraph::Edge::vertex(), vertices, g2o::EdgeSE3::write(), and g2o::VertexSE3::write().

45 {
46  // command line parsing
47  int nodesPerLevel;
48  int numLaps;
49  double radius;
50  std::vector<double> noiseTranslation;
51  std::vector<double> noiseRotation;
52  string outFilename;
53  CommandArgs arg;
54  arg.param("o", outFilename, "-", "output filename");
55  arg.param("nodesPerLevel", nodesPerLevel, 50, "how many nodes per lap on the sphere");
56  arg.param("laps", numLaps, 50, "how many times the robot travels around the sphere");
57  arg.param("radius", radius, 100., "radius of the sphere");
58  arg.param("noiseTranslation", noiseTranslation, std::vector<double>(), "set the noise level for the translation, separated by semicolons without spaces e.g: \"0.1;0.1;0.1\"");
59  arg.param("noiseRotation", noiseRotation, std::vector<double>(), "set the noise level for the rotation, separated by semicolons without spaces e.g: \"0.001;0.001;0.001\"");
60  arg.parseArgs(argc, argv);
61 
62  if (noiseTranslation.size() == 0) {
63  cerr << "using default noise for the translation" << endl;
64  noiseTranslation.push_back(0.01);
65  noiseTranslation.push_back(0.01);
66  noiseTranslation.push_back(0.01);
67  }
68  cerr << "Noise for the translation:";
69  for (size_t i = 0; i < noiseTranslation.size(); ++i)
70  cerr << " " << noiseTranslation[i];
71  cerr << endl;
72  if (noiseRotation.size() == 0) {
73  cerr << "using default noise for the rotation" << endl;
74  noiseRotation.push_back(0.005);
75  noiseRotation.push_back(0.005);
76  noiseRotation.push_back(0.005);
77  }
78  cerr << "Noise for the rotation:";
79  for (size_t i = 0; i < noiseRotation.size(); ++i)
80  cerr << " " << noiseRotation[i];
81  cerr << endl;
82 
83  Eigen::Matrix3d transNoise = Eigen::Matrix3d::Zero();
84  for (int i = 0; i < 3; ++i)
85  transNoise(i, i) = std::pow(noiseTranslation[i], 2);
86 
87  Eigen::Matrix3d rotNoise = Eigen::Matrix3d::Zero();
88  for (int i = 0; i < 3; ++i)
89  rotNoise(i, i) = std::pow(noiseRotation[i], 2);
90 
91  Eigen::Matrix<double, 6, 6> information = Eigen::Matrix<double, 6, 6>::Zero();
92  information.block<3,3>(0,0) = transNoise.inverse();
93  information.block<3,3>(3,3) = rotNoise.inverse();
94 
95  vector<VertexSE3*> vertices;
96  vector<EdgeSE3*> odometryEdges;
97  vector<EdgeSE3*> edges;
98  int id = 0;
99  for (int f = 0; f < numLaps; ++f){
100  for (int n = 0; n < nodesPerLevel; ++n) {
101  VertexSE3* v = new VertexSE3;
102  v->setId(id++);
103 
104  Eigen::AngleAxisd rotz(-M_PI + 2*n*M_PI / nodesPerLevel, Eigen::Vector3d::UnitZ());
105  Eigen::AngleAxisd roty(-0.5*M_PI + id*M_PI / (numLaps * nodesPerLevel), Eigen::Vector3d::UnitY());
106  Eigen::Matrix3d rot = (rotz * roty).toRotationMatrix();
107 
108  Eigen::Isometry3d t;
109  t = rot;
110  t.translation() = t.linear() * Eigen::Vector3d(radius, 0, 0);
111  v->setEstimate(t);
112  vertices.push_back(v);
113  }
114  }
115 
116  // generate odometry edges
117  for (size_t i = 1; i < vertices.size(); ++i) {
118  VertexSE3* prev = vertices[i-1];
119  VertexSE3* cur = vertices[i];
120  Eigen::Isometry3d t = prev->estimate().inverse() * cur->estimate();
121  EdgeSE3* e = new EdgeSE3;
122  e->setVertex(0, prev);
123  e->setVertex(1, cur);
124  e->setMeasurement(t);
125  e->setInformation(information);
126  odometryEdges.push_back(e);
127  edges.push_back(e);
128  }
129 
130  // generate loop closure edges
131  for (int f = 1; f < numLaps; ++f) {
132  for (int nn = 0; nn < nodesPerLevel; ++nn) {
133  VertexSE3* from = vertices[(f-1)*nodesPerLevel + nn];
134  for (int n = -1; n <= 1; ++n) {
135  if (f == numLaps-1 && n == 1)
136  continue;
137  VertexSE3* to = vertices[f*nodesPerLevel + nn + n];
138  Eigen::Isometry3d t = from->estimate().inverse() * to->estimate();
139  EdgeSE3* e = new EdgeSE3;
140  e->setVertex(0, from);
141  e->setVertex(1, to);
142  e->setMeasurement(t);
143  e->setInformation(information);
144  edges.push_back(e);
145  }
146  }
147  }
148 
150  transSampler.setDistribution(transNoise);
152  rotSampler.setDistribution(rotNoise);
153 
154  // noise for all the edges
155  for (size_t i = 0; i < edges.size(); ++i) {
156  EdgeSE3* e = edges[i];
157  Eigen::Quaterniond gtQuat = (Eigen::Quaterniond)e->measurement().linear();
158  Eigen::Vector3d gtTrans = e->measurement().translation();
159 
160  Eigen::Vector3d quatXYZ = rotSampler.generateSample();
161  double qw = 1.0 - quatXYZ.norm();
162  if (qw < 0) {
163  qw = 0.;
164  cerr << "x";
165  }
166  Eigen::Quaterniond rot(qw, quatXYZ.x(), quatXYZ.y(), quatXYZ.z());
167  rot.normalize();
168  Eigen::Vector3d trans = transSampler.generateSample();
169  rot = gtQuat * rot;
170  trans = gtTrans + trans;
171 
172  Eigen::Isometry3d noisyMeasurement = (Eigen::Isometry3d) rot;
173  noisyMeasurement.translation() = trans;
174  e->setMeasurement(noisyMeasurement);
175  }
176 
177  // concatenate all the odometry constraints to compute the initial state
178  for (size_t i =0; i < odometryEdges.size(); ++i) {
179  EdgeSE3* e = edges[i];
180  VertexSE3* from = static_cast<VertexSE3*>(e->vertex(0));
181  VertexSE3* to = static_cast<VertexSE3*>(e->vertex(1));
182  HyperGraph::VertexSet aux; aux.insert(from);
183  e->initialEstimate(aux, to);
184  }
185 
186  // write output
187  ofstream fileOutputStream;
188  if (outFilename != "-") {
189  cerr << "Writing into " << outFilename << endl;
190  fileOutputStream.open(outFilename.c_str());
191  } else {
192  cerr << "writing to stdout" << endl;
193  }
194 
195  string vertexTag = Factory::instance()->tag(vertices[0]);
196  string edgeTag = Factory::instance()->tag(edges[0]);
197 
198  ostream& fout = outFilename != "-" ? fileOutputStream : cout;
199  for (size_t i = 0; i < vertices.size(); ++i) {
200  VertexSE3* v = vertices[i];
201  fout << vertexTag << " " << v->id() << " ";
202  v->write(fout);
203  fout << endl;
204  }
205 
206  for (size_t i = 0; i < edges.size(); ++i) {
207  EdgeSE3* e = edges[i];
208  VertexSE3* from = static_cast<VertexSE3*>(e->vertex(0));
209  VertexSE3* to = static_cast<VertexSE3*>(e->vertex(1));
210  fout << edgeTag << " " << from->id() << " " << to->id() << " ";
211  e->write(fout);
212  fout << endl;
213  }
214 
215  return 0;
216 }
int id() const
returns the id
Definition: hyper_graph.h:148
const Vertex * vertex(size_t i) const
Definition: hyper_graph.h:186
Command line parsing of argc and argv.
Definition: command_args.h:46
std::set< Vertex * > VertexSet
Definition: hyper_graph.h:136
SampleType generateSample()
Definition: sampler.h:67
virtual bool write(std::ostream &os) const
write the vertex to a stream
Definition: edge_se3.cpp:42
void setVertex(size_t i, Vertex *v)
Definition: hyper_graph.h:194
virtual void initialEstimate(const OptimizableGraph::VertexSet &from, OptimizableGraph::Vertex *to)
Definition: edge_se3.cpp:81
Edge between two 3D pose vertices.
Definition: edge_se3.h:18
virtual bool write(std::ostream &os) const
write the vertex to a stream
Definition: vertex_se3.cpp:58
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 ...
Protocol The SLAM executable accepts such as solving the and retrieving or vertices in the explicitly state the reprensentation poses are represented by poses by VERTEX_XYZRPY In the Quaternions and other representations could be but note that it is up to the SLAM algorithm to choose the internal representation of the angles The keyword is followed by a unique vertex ID and an optional initialization of the or edges in the explicitly state the type of the constraint pose constraints are given by pose constraints by EDGE_XYZRPY The keyword is followed by a unique edge the IDs of the referenced vertices
Definition: protocol.txt:7
bool parseArgs(int argc, char **argv, bool exitOnError=true)
virtual void setMeasurement(const Isometry3D &m)
Definition: edge_se3.h:27
EIGEN_STRONG_INLINE void setInformation(const InformationType &information)
Definition: base_edge.h:69
void param(const std::string &name, bool &p, bool defValue, const std::string &desc)
void setEstimate(const EstimateType &et)
set the estimate for the vertex also calls updateCache()
Definition: base_vertex.h:101
const EstimateType & estimate() const
return the current estimate of the vertex
Definition: base_vertex.h:99
3D pose Vertex, represented as an Isometry3D
Definition: vertex_se3.h:50
void setDistribution(const CovarianceType &cov)
Definition: sampler.h:60
#define M_PI
Definition: misc.h:34
EIGEN_STRONG_INLINE const Measurement & measurement() const
accessor functions for the measurement represented by the edge
Definition: base_edge.h:75