43void quat_to_euler(
const Eigen::Quaterniond& q,
double& yaw,
double& pitch,
45 const double& q0 = q.w();
46 const double& q1 = q.x();
47 const double& q2 = q.y();
48 const double& q3 = q.z();
49 roll =
atan2(2 * (q0 * q1 + q2 * q3), 1 - 2 * (q1 * q1 + q2 * q2));
50 pitch =
asin(2 * (q0 * q2 - q3 * q1));
51 yaw =
atan2(2 * (q0 * q3 + q1 * q2), 1 - 2 * (q2 * q2 + q3 * q3));
55 const Vector3d& tr0 = t.translation();
56 const Quaterniond& q0 = t.rotation();
59 double idelta = 1. / (2. * delta);
61 for (
int i = 0; i < 6; i++) {
68 ta = SE3Quat(q0, tra);
69 tb = SE3Quat(q0, trb);
85 ta = SE3Quat(qa, tr0);
86 tb = SE3Quat(qb, tr0);
89 Vector3d dtr = (tb.translation() - ta.translation()) * idelta;
90 Vector3d taAngles, tbAngles;
91 quat_to_euler(ta.rotation(), taAngles(2), taAngles(1), taAngles(0));
92 quat_to_euler(tb.rotation(), tbAngles(2), tbAngles(1), tbAngles(0));
94 (tbAngles - taAngles) * idelta;
96 for (
int j = 0; j < 6; j++) {
108 : _optimizer(optimizer),
109 _firstOptimization(true),
112 _updateGraphEachN(10),
115 _initSolverDone(false) {}
118 const std::vector<double>& values) {
135 const std::vector<double>& measurement,
136 const std::vector<double>& information) {
141 if (dimension == 3) {
142 SE2 transf(measurement[0], measurement[1], measurement[2]);
143 Eigen::Matrix3d infMat;
145 for (
int r = 0; r < 3; ++r)
146 for (
int c = r; c < 3; ++c, ++idx) {
147 assert(idx < (
int)information.size());
148 infMat(r, c) = infMat(c, r) = information[idx];
170 cerr <<
"FIRST EDGE ";
171 if (v1->
id() < v2->
id()) {
172 cerr <<
"fixing " << v1->
id() << endl;
175 cerr <<
"fixing " << v2->
id() << endl;
205 fromSet.insert(from);
212 cerr <<
"doInit wrong value\n";
216 }
else if (dimension == 6) {
217 Eigen::Isometry3d transf;
218 Matrix<double, 6, 6> infMat;
220 if (measurement.size() == 7) {
222 for (
int i = 0; i < 7; ++i) meas(i) = measurement[i];
225 Vector4::MapType(meas.data() + 3).normalize();
228 for (
int i = 0, idx = 0; i < infMat.rows(); ++i)
229 for (
int j = i; j < infMat.cols(); ++j) {
230 infMat(i, j) = information[idx++];
231 if (i != j) infMat(j, i) = infMat(i, j);
235 aux << measurement[0], measurement[1], measurement[2], measurement[3],
236 measurement[4], measurement[5];
238 Matrix<double, 6, 6> infMatEuler;
240 for (
int r = 0; r < 6; ++r)
241 for (
int c = r; c < 6; ++c, ++idx) {
242 assert(idx < (
int)information.size());
243 infMatEuler(r, c) = infMatEuler(c, r) = information[idx];
246 Matrix<double, 6, 6> J;
247 SE3Quat transfAsSe3(transf.matrix().topLeftCorner<3, 3>(),
248 transf.translation());
250 infMat.noalias() = J.transpose() * infMatEuler * J;
273 cerr <<
"FIRST EDGE ";
274 if (v1->
id() < v2->
id()) {
275 cerr <<
"fixing " << v1->
id() << endl;
278 cerr <<
"fixing " << v2->
id() << endl;
308 fromSet.insert(from);
315 cerr <<
"doInit wrong value\n";
325 if (oldEdgesSize == 0) {
333 for (
size_t i = 0; i < nodes.size(); ++i) {
342 cout <<
"BEGIN" << endl;
344 if (nodes.size() == 0) {
345 for (OptimizableGraph::VertexIDMap::const_iterator it =
353 for (
size_t i = 0; i < nodes.size(); ++i) {
359 cout <<
"END" << endl << flush;
366 return state !=
ERROR;
370 if (dimension == 3) {
375 }
else if (dimension == 6) {
386 static char buffer[10000];
391 memcpy(s,
"VERTEX_XYT ", 11);
401 cout.write(buffer, s - buffer);
403 }
else if (vdim == 6) {
406 Vector3d eulerAngles =
408 const double& roll = eulerAngles(0);
409 const double& pitch = eulerAngles(1);
410 const double& yaw = eulerAngles(2);
411 memcpy(s,
"VERTEX_XYZRPY ", 14);
427 cout.write(buffer, s - buffer);
446 cerr <<
"initialization failed" << endl;
451 cerr <<
"updating initialization failed" << endl;
void setInformation(const InformationType &information)
virtual double initialEstimatePossible(const OptimizableGraph::VertexSet &, OptimizableGraph::Vertex *)
virtual void setMeasurement(const SE2 &m)
virtual double initialEstimatePossible(const OptimizableGraph::VertexSet &, OptimizableGraph::Vertex *)
virtual void setMeasurement(const Isometry3 &m)
void setBatchSolveEachN(int n)
void setUpdateGraphEachN(int n)
bool printVertex(OptimizableGraph::Vertex *v)
HyperGraph::EdgeSet _edgesAdded
bool fixNode(const std::vector< int > &nodes)
bool queryState(const std::vector< int > &nodes)
G2oSlamInterface(SparseOptimizerOnline *optimizer)
bool addEdge(const std::string &tag, int id, int dimension, int v1, int v2, const std::vector< double > &measurement, const std::vector< double > &information)
bool addNode(const std::string &tag, int id, int dimension, const std::vector< double > &values)
OptimizableGraph::Vertex * addVertex(int dimension, int id)
SparseOptimizerOnline * _optimizer
HyperGraph::VertexSet _verticesAdded
const VertexContainer & vertices() const
abstract Vertex, your types must derive from that one
int id() const
returns the id
std::set< Vertex * > VertexSet
const EdgeSet & edges() const
const VertexIDMap & vertices() const
void initialEstimate(const OptimizableGraph::VertexSet &from, OptimizableGraph::Vertex *)
void initialEstimate(const OptimizableGraph::VertexSet &from, OptimizableGraph::Vertex *)
VertexSE2::EstimateType updatedEstimate
VertexSE3::EstimateType updatedEstimate
A general case Vertex for optimization.
int dimension() const
dimension of the estimated state belonging to this node
virtual void setId(int id)
void setFixed(bool fixed)
true => this node should be considered fixed during the optimization
const Vector2 & translation() const
translational component
const Rotation2D & rotation() const
rotational component
virtual bool initSolver(int dimension, int batchEveryN)
int optimize(int iterations, bool online=false)
virtual bool updateInitialization(HyperGraph::VertexSet &vset, HyperGraph::EdgeSet &eset)
virtual bool initializeOptimization(HyperGraph::EdgeSet &eset)
int modp_itoa10(int32_t value, char *str)
int modp_dtoa(double value, char *str, int prec)
#define __PRETTY_FUNCTION__
Jet< T, N > atan2(const Jet< T, N > &g, const Jet< T, N > &f)
Jet< T, N > asin(const Jet< T, N > &f)
Isometry3 fromVectorQT(const Vector7 &v)
Vector3 toEuler(const Matrix3 &R)
Isometry3 fromVectorET(const Vector6 &v)
static void jac_quat3_euler3(Eigen::Matrix< double, 6, 6, Eigen::ColMajor > &J, const Isometry3 &t)
JacobianWorkspace & jacobianWorkspace()
the workspace for storing the Jacobians of the graph
virtual bool addEdge(HyperGraph::Edge *e)
virtual bool addVertex(HyperGraph::Vertex *v, Data *userData)
Vertex * vertex(int id)
returns the vertex number id appropriately casted