edge_se3Switchable.cpp
Go to the documentation of this file.
00001 /*
00002  * edge_se3Switchable.cpp
00003  *
00004  *  Created on: 17.10.2011
00005  *      Author: niko
00006  *
00007  *  Updated on: 14.01.2013
00008  *      Author: Christian Kerl <christian.kerl@in.tum.de>
00009  */
00010 
00011 #include "vertigo/g2o/edge_se3Switchable.h"
00012 #include "vertigo/g2o/vertex_switchLinear.h"
00013 #include "g2o/types/slam3d/vertex_se3.h"
00014 #include "g2o/types/slam3d/isometry3d_gradients.h"
00015 
00016 
00017 using namespace std;
00018 using namespace Eigen;
00019 
00020 
00021 // ================================================
00022 EdgeSE3Switchable::EdgeSE3Switchable() : g2o::BaseMultiEdge<6, Eigen::Isometry3d>()
00023 {
00024   resize(3);
00025   _jacobianOplus.clear();
00026   _jacobianOplus.push_back(JacobianType(0, 6, 6));
00027   _jacobianOplus.push_back(JacobianType(0, 6, 6));
00028   _jacobianOplus.push_back(JacobianType(0, 6, 1));
00029 
00030 }
00031 // ================================================
00032 bool EdgeSE3Switchable::read(std::istream& is)
00033   {    
00034  /*   g2o::Vector7d meas;
00035     for (int i=0; i<7; i++) 
00036       is >> meas[i];
00037     // normalize the quaternion to recover numerical precision lost by storing as human readable text
00038     Vector4d::MapType(meas.data()+3).normalize();
00039     setMeasurement(g2o::internal::fromVectorQT(meas));
00040 
00041     for (int i=0; i<6; i++)
00042       for (int j=i; j<6; j++) {
00043         is >> information()(i,j);
00044         if (i!=j)
00045           information()(j,i) = information()(i,j);
00046       }
00047     return true;*/
00048         return false;
00049 
00050   }
00051 // ================================================
00052 bool EdgeSE3Switchable::write(std::ostream& os) const
00053 {
00054    /* g2o::Vector7d meas = g2o::internal::toVectorQT(measurement());
00055     for (int i=0; i<7; i++) os  << meas[i] << " ";
00056     for (int i = 0; i < 6; ++i)
00057       for (int j = i; j < 6; ++j)
00058         os << " " << information()(i, j);
00059     return os.good();*/
00060         return false;
00061 }
00062 
00063 // ================================================
00064 void EdgeSE3Switchable::linearizeOplus()
00065 {
00066 
00067     g2o::VertexSE3* from = static_cast<g2o::VertexSE3*>(_vertices[0]);
00068     g2o::VertexSE3* to = static_cast<g2o::VertexSE3*>(_vertices[1]);
00069     const VertexSwitchLinear* vSwitch = static_cast<const VertexSwitchLinear*>(_vertices[2]);
00070 
00071     Eigen::Isometry3d E;
00072     const Eigen::Isometry3d& Xi=from->estimate();
00073     const Eigen::Isometry3d& Xj=to->estimate();
00074     const Eigen::Isometry3d& Z=_measurement;
00075     g2o::internal::computeEdgeSE3Gradient(E, _jacobianOplus[0], _jacobianOplus[1], Z, Xi, Xj);
00076 
00077     _jacobianOplus[0]*=vSwitch->estimate();
00078     _jacobianOplus[1]*=vSwitch->estimate();
00079 
00080     // derivative w.r.t switch vertex
00081     _jacobianOplus[2].setZero();
00082     _jacobianOplus[2] = g2o::internal::toVectorMQT(E) * vSwitch->gradient();
00083 }
00084 
00085 
00086 // ================================================
00087 void EdgeSE3Switchable::computeError()
00088 {
00089     const g2o::VertexSE3* v1 = dynamic_cast<const g2o::VertexSE3*>(_vertices[0]);
00090     const g2o::VertexSE3* v2 = dynamic_cast<const g2o::VertexSE3*>(_vertices[1]);
00091     const VertexSwitchLinear* v3 = static_cast<const VertexSwitchLinear*>(_vertices[2]);
00092 
00093     Eigen::Isometry3d delta = _inverseMeasurement * (v1->estimate().inverse()*v2->estimate());
00094     _error = g2o::internal::toVectorMQT(delta) * v3->estimate();
00095 }
00096 
00097 /*
00098 #include <GL/gl.h>
00099 #ifdef G2O_HAVE_OPENGL
00100   EdgeSE3SwitchableDrawAction::EdgeSE3SwitchableDrawAction(): DrawAction(typeid(EdgeSE3Switchable).name()){}
00101 
00102   g2o::HyperGraphElementAction* EdgeSE3SwitchableDrawAction::operator()(g2o::HyperGraph::HyperGraphElement* element,
00103                g2o::HyperGraphElementAction::Parameters* ){
00104     if (typeid(*element).name()!=_typeName)
00105       return 0;
00106     EdgeSE3Switchable* e =  static_cast<EdgeSE3Switchable*>(element);
00107 
00108 
00109     g2o::VertexSE3* fromEdge = static_cast<g2o::VertexSE3*>(e->vertices()[0]);
00110     g2o::VertexSE3* toEdge   = static_cast<g2o::VertexSE3*>(e->vertices()[1]);
00111     VertexSwitchLinear* s   = static_cast<VertexSwitchLinear*>(e->vertices()[2]);
00112 
00113     glColor3f(s->estimate()*1.0,s->estimate()*0.1,s->estimate()*0.1);
00114     glPushAttrib(GL_ENABLE_BIT);
00115     glDisable(GL_LIGHTING);
00116     glBegin(GL_LINES);
00117     glVertex3f(fromEdge->estimate().translation().x(),fromEdge->estimate().translation().y(),fromEdge->estimate().translation().z());
00118     glVertex3f(toEdge->estimate().translation().x(),toEdge->estimate().translation().y(),toEdge->estimate().translation().z());
00119     glEnd();
00120     glPopAttrib();
00121     return this;
00122   }
00123 #endif
00124 */


rtabmap
Author(s): Mathieu Labbe
autogenerated on Thu Jun 6 2019 21:59:19