Go to the documentation of this file.00001
00002
00003
00004
00005
00006
00007
00008
00009
00010
00011 #include "vertigo/g2o/edge_se2Switchable.h"
00012 #include "vertigo/g2o/vertex_switchLinear.h"
00013
00014 using namespace std;
00015 using namespace Eigen;
00016
00017
00018
00019 EdgeSE2Switchable::EdgeSE2Switchable() : g2o::BaseMultiEdge<3, g2o::SE2>()
00020 {
00021 resize(3);
00022 _jacobianOplus.clear();
00023 _jacobianOplus.push_back(JacobianType(0, 3, 3));
00024 _jacobianOplus.push_back(JacobianType(0, 3, 3));
00025 _jacobianOplus.push_back(JacobianType(0, 3, 1));
00026
00027 }
00028
00029 bool EdgeSE2Switchable::read(std::istream& is)
00030 {
00031 Vector3d p;
00032 is >> p[0] >> p[1] >> p[2];
00033 setMeasurement(g2o::SE2(p));
00034 _inverseMeasurement = measurement().inverse();
00035
00036 for (int i = 0; i < 3; ++i)
00037 for (int j = i; j < 3; ++j) {
00038 is >> information()(i, j);
00039 if (i != j)
00040 information()(j, i) = information()(i, j);
00041 }
00042 return true;
00043 }
00044
00045 bool EdgeSE2Switchable::write(std::ostream& os) const
00046 {
00047 Vector3d p = measurement().toVector();
00048 os << p.x() << " " << p.y() << " " << p.z();
00049 for (int i = 0; i < 3; ++i)
00050 for (int j = i; j < 3; ++j)
00051 os << " " << information()(i, j);
00052 return os.good();
00053 }
00054
00055
00056 void EdgeSE2Switchable::linearizeOplus()
00057 {
00058
00059 const g2o::VertexSE2* vi = static_cast<const g2o::VertexSE2*>(_vertices[0]);
00060 const g2o::VertexSE2* vj = static_cast<const g2o::VertexSE2*>(_vertices[1]);
00061 const VertexSwitchLinear* vSwitch = static_cast<const VertexSwitchLinear*>(_vertices[2]);
00062
00063 double thetai = vi->estimate().rotation().angle();
00064
00065 Vector2d dt = vj->estimate().translation() - vi->estimate().translation();
00066 double si=sin(thetai), ci=cos(thetai);
00067
00068 _jacobianOplus[0](0, 0) = -ci; _jacobianOplus[0](0, 1) = -si; _jacobianOplus[0](0, 2) = -si*dt.x()+ci*dt.y();
00069 _jacobianOplus[0](1, 0) = si; _jacobianOplus[0](1, 1) = -ci; _jacobianOplus[0](1, 2) = -ci*dt.x()-si*dt.y();
00070 _jacobianOplus[0](2, 0) = 0; _jacobianOplus[0](2, 1) = 0; _jacobianOplus[0](2, 2) = -1;
00071
00072 _jacobianOplus[1](0, 0) = ci; _jacobianOplus[1](0, 1)= si; _jacobianOplus[1](0, 2)= 0;
00073 _jacobianOplus[1](1, 0) =-si; _jacobianOplus[1](1, 1)= ci; _jacobianOplus[1](1, 2)= 0;
00074 _jacobianOplus[1](2, 0) = 0; _jacobianOplus[1](2, 1)= 0; _jacobianOplus[1](2, 2)= 1;
00075
00076 const g2o::SE2& rmean = _inverseMeasurement;
00077 Matrix3d z = Matrix3d::Zero();
00078 z.block<2, 2>(0, 0) = rmean.rotation().toRotationMatrix();
00079 z(2, 2) = 1.;
00080 _jacobianOplus[0] = z * _jacobianOplus[0];
00081 _jacobianOplus[1] = z * _jacobianOplus[1];
00082
00083
00084 _jacobianOplus[0]*=vSwitch->estimate();
00085 _jacobianOplus[1]*=vSwitch->estimate();
00086
00087
00088
00089 _jacobianOplus[2].setZero();
00090 g2o::SE2 delta = _inverseMeasurement * (vi->estimate().inverse()*vj->estimate());
00091 _jacobianOplus[2] = delta.toVector() * vSwitch->gradient();
00092 }
00093
00094
00095 void EdgeSE2Switchable::computeError()
00096 {
00097 const g2o::VertexSE2* v1 = static_cast<const g2o::VertexSE2*>(_vertices[0]);
00098 const g2o::VertexSE2* v2 = static_cast<const g2o::VertexSE2*>(_vertices[1]);
00099 const VertexSwitchLinear* v3 = static_cast<const VertexSwitchLinear*>(_vertices[2]);
00100
00101 g2o::SE2 delta = _inverseMeasurement * (v1->estimate().inverse()*v2->estimate());
00102 _error = delta.toVector() * v3->estimate();
00103 }
00104
00105
00106
00107
00108
00109
00110
00111
00112
00113
00114
00115
00116
00117
00118
00119
00120
00121
00122
00123
00124
00125
00126
00127
00128
00129
00130
00131
00132