Go to the documentation of this file.00001
00002
00003
00004
00005
00006
00007
00008
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
00035
00036
00037
00038
00039
00040
00041
00042
00043
00044
00045
00046
00047
00048 return false;
00049
00050 }
00051
00052 bool EdgeSE3Switchable::write(std::ostream& os) const
00053 {
00054
00055
00056
00057
00058
00059
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
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
00099
00100
00101
00102
00103
00104
00105
00106
00107
00108
00109
00110
00111
00112
00113
00114
00115
00116
00117
00118
00119
00120
00121
00122
00123
00124