39 using namespace Eigen;
44 void quat_to_euler(
const Eigen::Quaterniond& q,
double& yaw,
double& pitch,
double& roll)
46 const double& q0 = q.w();
47 const double& q1 = q.x();
48 const double& q2 = q.y();
49 const double& q3 = q.z();
50 roll = atan2(2*(q0*q1+q2*q3), 1-2*(q1*q1+q2*q2));
51 pitch = asin(2*(q0*q2-q3*q1));
52 yaw = atan2(2*(q0*q3+q1*q2), 1-2*(q2*q2+q3*q3));
57 const Vector3d& tr0 = t.translation();
58 const Quaterniond& q0 = t.rotation();
61 double idelta= 1. / (2. * delta);
63 for (
int i=0; i<6; i++){
70 ta = SE3Quat(q0, tra);
71 tb = SE3Quat(q0, trb);
89 ta = SE3Quat(qa, tr0);
90 tb = SE3Quat(qb, tr0);
93 Vector3d dtr = (tb.translation() - ta.translation())*idelta;
94 Vector3d taAngles, tbAngles;
95 quat_to_euler(ta.rotation(), taAngles(2), taAngles(1), taAngles(0));
96 quat_to_euler(tb.rotation(), tbAngles(2), tbAngles(1), tbAngles(0));
97 Vector3d da = (tbAngles - taAngles) * idelta;
99 for (
int j=0; j<6; j++){
111 _optimizer(optimizer), _firstOptimization(true), _nodesAdded(0),
112 _incIterations(1), _updateGraphEachN(10), _batchEveryN(100),
113 _lastBatchStep(0), _initSolverDone(false)
133 bool G2oSlamInterface::addEdge(
const std::string& tag,
int id,
int dimension,
int v1Id,
int v2Id,
const std::vector<double>& measurement,
const std::vector<double>& information)
139 if (dimension == 3) {
141 SE2 transf(measurement[0], measurement[1], measurement[2]);
142 Eigen::Matrix3d infMat;
144 for (
int r = 0; r < 3; ++r)
145 for (
int c = r; c < 3; ++c, ++idx) {
146 assert(idx < (
int)information.size());
147 infMat(r,c) = infMat(c,r) = information[idx];
169 cerr <<
"FIRST EDGE ";
170 if (v1->
id() < v2->
id()) {
171 cerr <<
"fixing " << v1->
id() << endl;
175 cerr <<
"fixing " << v2->
id() << endl;
204 fromSet.insert(from);
210 default: cerr <<
"doInit wrong value\n";
215 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)
223 meas(i) = measurement[i];
225 Vector4d::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++];
232 infMat(j,i)=infMat(i,j);
236 aux << measurement[0], measurement[1], measurement[2],measurement[3], 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>(), transf.translation());
249 infMat.noalias() = J.transpose() * infMatEuler * J;
272 cerr <<
"FIRST EDGE ";
273 if (v1->
id() < v2->
id()) {
274 cerr <<
"fixing " << v1->
id() << endl;
278 cerr <<
"fixing " << v2->
id() << endl;
307 fromSet.insert(from);
313 default: cerr <<
"doInit wrong value\n";
323 if (oldEdgesSize == 0) {
332 for (
size_t i = 0; i < nodes.size(); ++i) {
343 cout <<
"BEGIN" << endl;
345 if (nodes.size() == 0) {
351 for (
size_t i = 0; i < nodes.size(); ++i) {
358 cout <<
"END" << endl << flush;
366 return state !=
ERROR;
371 if (dimension == 3) {
377 else if (dimension == 6) {
390 static char buffer[10000];
395 memcpy(s,
"VERTEX_XYT ", 11);
405 cout.write(buffer, s - buffer);
408 else if (vdim == 6) {
412 const double& roll = eulerAngles(0);
413 const double& pitch = eulerAngles(1);
414 const double& yaw = eulerAngles(2);
415 memcpy(s,
"VERTEX_XYZRPY ", 14);
431 cout.write(buffer, s - buffer);
455 cerr <<
"initialization failed" << endl;
460 cerr <<
"updating initialization failed" << endl;
Vector3D toEuler(const Matrix3D &R)
int id() const
returns the id
#define __PRETTY_FUNCTION__
bool addEdge(const std::string &tag, int id, int dimension, int v1, int v2, const std::vector< double > &measurement, const std::vector< double > &information)
void setUpdateGraphEachN(int n)
virtual void setMeasurement(const SE2 &m)
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 values
Isometry3D fromVectorQT(const Vector7d &v)
bool addNode(const std::string &tag, int id, int dimension, const std::vector< double > &values)
virtual double initialEstimatePossible(const OptimizableGraph::VertexSet &, OptimizableGraph::Vertex *)
HyperGraph::VertexSet _verticesAdded
std::set< Vertex * > VertexSet
void initialEstimate(const OptimizableGraph::VertexSet &from, OptimizableGraph::Vertex *)
int modp_itoa10(int32_t value, char *str)
Eigen::Matrix< double, 7, 1 > Vector7d
const VertexIDMap & vertices() const
Vertex * vertex(int id)
returns the vertex number id appropriately casted
JacobianWorkspace & jacobianWorkspace()
the workspace for storing the Jacobians of the graph
bool printVertex(OptimizableGraph::Vertex *v)
bool queryState(const std::vector< int > &nodes)
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 ...
int optimize(int iterations, bool online=false)
void quat_to_euler(const Eigen::Quaterniond &q, double &yaw, double &pitch, double &roll)
int dimension() const
dimension of the estimated state belonging to this node
void initialEstimate(const OptimizableGraph::VertexSet &from, OptimizableGraph::Vertex *)
const VertexContainer & vertices() const
const Eigen::Rotation2Dd & rotation() const
rotational component
const EdgeSet & edges() const
virtual void setMeasurement(const Isometry3D &m)
EIGEN_STRONG_INLINE void setInformation(const InformationType &information)
Eigen::Quaterniond & normalize(Eigen::Quaterniond &q)
SparseOptimizerOnline * _optimizer
A general case Vertex for optimization.
abstract Vertex, your types must derive from that one
static void jac_quat3_euler3(Eigen::Matrix< double, 6, 6, Eigen::ColMajor > &J, const Isometry3D &t)
bool fixNode(const std::vector< int > &nodes)
void jac_quat3_euler3(Eigen::Matrix< double, 6, 6 > &J, const SE3Quat &t)
virtual double initialEstimatePossible(const OptimizableGraph::VertexSet &, OptimizableGraph::Vertex *)
void setBatchSolveEachN(int n)
VertexSE2::EstimateType updatedEstimate
void setFixed(bool fixed)
true => this node should be considered fixed during the optimization
virtual bool initSolver(int dimension, int batchEveryN)
OptimizableGraph::Vertex * addVertex(int dimension, int id)
virtual bool initializeOptimization(HyperGraph::EdgeSet &eset)
const Vector2D & translation() const
translational component
virtual bool addEdge(HyperGraph::Edge *e)
virtual bool updateInitialization(HyperGraph::VertexSet &vset, HyperGraph::EdgeSet &eset)
HyperGraph::EdgeSet _edgesAdded
virtual bool addVertex(HyperGraph::Vertex *v, Data *userData)
VertexSE3::EstimateType updatedEstimate
int modp_dtoa(double value, char *str, int prec)
Isometry3D fromVectorET(const Vector6d &v)
Matrix< double, 6, 1, Eigen::ColMajor > Vector6d