42 {
43
44 int nodesPerLevel;
45 int numLaps;
46 bool randomSeed;
47 double radius;
48 std::vector<double> noiseTranslation;
49 std::vector<double> noiseRotation;
50 string outFilename;
52 arg.
param(
"o", outFilename,
"-",
"output filename");
53 arg.
param(
"nodesPerLevel", nodesPerLevel, 50,
54 "how many nodes per lap on the sphere");
55 arg.
param(
"laps", numLaps, 50,
56 "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>(),
59 "set the noise level for the translation, separated by semicolons "
60 "without spaces e.g: \"0.1;0.1;0.1\"");
61 arg.
param(
"noiseRotation", noiseRotation, std::vector<double>(),
62 "set the noise level for the rotation, separated by semicolons "
63 "without spaces e.g: \"0.001;0.001;0.001\"");
64 arg.
param(
"randomSeed", randomSeed,
false,
65 "use a randomized seed for generating the sphere");
67
68 if (noiseTranslation.size() == 0) {
69 cerr << "using default noise for the translation" << endl;
70 noiseTranslation.push_back(0.01);
71 noiseTranslation.push_back(0.01);
72 noiseTranslation.push_back(0.01);
73 }
74 cerr << "Noise for the translation:";
75 for (size_t i = 0; i < noiseTranslation.size(); ++i)
76 cerr << " " << noiseTranslation[i];
77 cerr << endl;
78 if (noiseRotation.size() == 0) {
79 cerr << "using default noise for the rotation" << endl;
80 noiseRotation.push_back(0.005);
81 noiseRotation.push_back(0.005);
82 noiseRotation.push_back(0.005);
83 }
84 cerr << "Noise for the rotation:";
85 for (size_t i = 0; i < noiseRotation.size(); ++i)
86 cerr << " " << noiseRotation[i];
87 cerr << endl;
88
89 Eigen::Matrix3d transNoise = Eigen::Matrix3d::Zero();
90 for (int i = 0; i < 3; ++i)
91 transNoise(i, i) = std::pow(noiseTranslation[i], 2);
92
93 Eigen::Matrix3d rotNoise = Eigen::Matrix3d::Zero();
94 for (int i = 0; i < 3; ++i) rotNoise(i, i) = std::pow(noiseRotation[i], 2);
95
96 Eigen::Matrix<double, 6, 6> information = Eigen::Matrix<double, 6, 6>::Zero();
97 information.block<3, 3>(0, 0) = transNoise.inverse();
98 information.block<3, 3>(3, 3) = rotNoise.inverse();
99
100 vector<VertexSE3*> vertices;
101 vector<EdgeSE3*> odometryEdges;
102 vector<EdgeSE3*> edges;
103 int id = 0;
104 for (int f = 0; f < numLaps; ++f) {
105 for (int n = 0; n < nodesPerLevel; ++n) {
108
109 Eigen::AngleAxisd rotz(-M_PI + 2 * n * M_PI / nodesPerLevel,
110 Eigen::Vector3d::UnitZ());
111 Eigen::AngleAxisd roty(
112 -0.5 * M_PI + id * M_PI / (numLaps * nodesPerLevel),
113 Eigen::Vector3d::UnitY());
114 Eigen::Matrix3d rot = (rotz * roty).toRotationMatrix();
115
116 Eigen::Isometry3d t;
117 t = rot;
118 t.translation() = t.linear() * Eigen::Vector3d(radius, 0, 0);
120 vertices.push_back(v);
121 }
122 }
123
124
125 for (size_t i = 1; i < vertices.size(); ++i) {
134 odometryEdges.push_back(e);
135 edges.push_back(e);
136 }
137
138
139 for (int f = 1; f < numLaps; ++f) {
140 for (int nn = 0; nn < nodesPerLevel; ++nn) {
141 VertexSE3* from = vertices[(f - 1) * nodesPerLevel + nn];
142 for (int n = -1; n <= 1; ++n) {
143 if (f == numLaps - 1 && n == 1) continue;
144 VertexSE3* to = vertices[f * nodesPerLevel + nn + n];
151 edges.push_back(e);
152 }
153 }
154 }
155
160
161 if (randomSeed) {
162 std::random_device r;
163 std::seed_seq seedSeq{r(), r(), r(), r(), r()};
164 vector<int> seeds(2);
165 seedSeq.generate(seeds.begin(), seeds.end());
166 cerr << "using seeds:";
167 for (size_t i = 0; i < seeds.size(); ++i) cerr << " " << seeds[i];
168 cerr << endl;
169 transSampler.
seed(seeds[0]);
170 rotSampler.
seed(seeds[1]);
171 }
172
173
174 for (size_t i = 0; i < edges.size(); ++i) {
176 Eigen::Quaterniond gtQuat = (Eigen::Quaterniond)e->
measurement().linear();
177 Eigen::Vector3d gtTrans = e->
measurement().translation();
178
180 double qw = 1.0 - quatXYZ.norm();
181 if (qw < 0) {
182 qw = 0.;
183 cerr << "x";
184 }
185 Eigen::Quaterniond rot(qw, quatXYZ.x(), quatXYZ.y(), quatXYZ.z());
186 rot.normalize();
188 rot = gtQuat * rot;
189 trans = gtTrans + trans;
190
191 Eigen::Isometry3d noisyMeasurement = (Eigen::Isometry3d)rot;
192 noisyMeasurement.translation() = trans;
194 }
195
196
197 for (size_t i = 0; i < odometryEdges.size(); ++i) {
202 aux.insert(from);
204 }
205
206
207 ofstream fileOutputStream;
208 if (outFilename != "-") {
209 cerr << "Writing into " << outFilename << endl;
210 fileOutputStream.open(outFilename.c_str());
211 } else {
212 cerr << "writing to stdout" << endl;
213 }
214
217
218 ostream& fout = outFilename != "-" ? fileOutputStream : cout;
219 for (size_t i = 0; i < vertices.size(); ++i) {
221 fout << vertexTag <<
" " << v->
id() <<
" ";
223 fout << endl;
224 }
225
226 for (size_t i = 0; i < edges.size(); ++i) {
230 fout << edgeTag <<
" " << from->
id() <<
" " << to->
id() <<
" ";
232 fout << endl;
233 }
234
235 return 0;
236}
EIGEN_STRONG_INLINE const Measurement & measurement() const
accessor functions for the measurement represented by the edge
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 param(const std::string &name, bool &p, bool defValue, const std::string &desc)
Edge between two 3D pose vertices.
virtual void setMeasurement(const Isometry3 &m)
virtual bool write(std::ostream &os) const
write the vertex to a stream
virtual void initialEstimate(const OptimizableGraph::VertexSet &from, OptimizableGraph::Vertex *to)
static Factory * instance()
return the instance
const std::string & tag(const HyperGraph::HyperGraphElement *v) const
return the TAG given a vertex
SampleType generateSample()
return a sample of the Gaussian distribution
void setDistribution(const CovarianceType &cov)
void setVertex(size_t i, Vertex *v)
const Vertex * vertex(size_t i) const
int id() const
returns the id
std::set< Vertex * > VertexSet
virtual void setId(int id)
3D pose Vertex, represented as an Isometry3
virtual bool write(std::ostream &os) const
write the vertex to a stream