g2o
Public Member Functions | Public Attributes | Static Public Attributes | List of all members
g2o::Edge_V_V_GICP Class Reference

#include <types_icp.h>

Inheritance diagram for g2o::Edge_V_V_GICP:
Inheritance graph
[legend]
Collaboration diagram for g2o::Edge_V_V_GICP:
Collaboration graph
[legend]

Public Member Functions

 Edge_V_V_GICP ()
 
 Edge_V_V_GICP (const Edge_V_V_GICP *e)
 
virtual bool read (std::istream &is)
 read the vertex from a stream, i.e., the internal state of the vertex More...
 
virtual bool write (std::ostream &os) const
 write the vertex to a stream More...
 
void computeError ()
 
virtual void linearizeOplus ()
 
- Public Member Functions inherited from g2o::BaseBinaryEdge< 3, EdgeGICP, VertexSE3, VertexSE3 >
 BaseBinaryEdge ()
 
virtual OptimizableGraph::VertexcreateFrom ()
 
virtual OptimizableGraph::VertexcreateTo ()
 
virtual OptimizableGraph::VertexcreateVertex (int i)
 
virtual void resize (size_t size)
 
virtual bool allVerticesFixed () const
 
virtual void linearizeOplus (JacobianWorkspace &jacobianWorkspace)
 
const JacobianXiOplusTypejacobianOplusXi () const
 returns the result of the linearization in the manifold space for the node xi More...
 
const JacobianXjOplusTypejacobianOplusXj () const
 returns the result of the linearization in the manifold space for the node xj More...
 
virtual void constructQuadraticForm ()
 
virtual void mapHessianMemory (double *d, int i, int j, bool rowMajor)
 
- Public Member Functions inherited from g2o::BaseEdge< D, EdgeGICP >
 BaseEdge ()
 
virtual ~BaseEdge ()
 
virtual double chi2 () const
 computes the chi2 based on the cached error value, only valid after computeError has been called. More...
 
virtual const double * errorData () const
 returns the error vector cached after calling the computeError; More...
 
virtual double * errorData ()
 
const ErrorVectorerror () const
 
ErrorVectorerror ()
 
EIGEN_STRONG_INLINE const InformationTypeinformation () const
 information matrix of the constraint More...
 
EIGEN_STRONG_INLINE InformationTypeinformation ()
 
EIGEN_STRONG_INLINE void setInformation (const InformationType &information)
 
virtual const double * informationData () const
 returns the memory of the information matrix, usable for example with a Eigen::Map<MatrixXD> More...
 
virtual double * informationData ()
 
EIGEN_STRONG_INLINE const Measurementmeasurement () const
 accessor functions for the measurement represented by the edge More...
 
virtual void setMeasurement (const Measurement &m)
 
virtual int rank () const
 
virtual void initialEstimate (const OptimizableGraph::VertexSet &, OptimizableGraph::Vertex *)
 
- Public Member Functions inherited from g2o::OptimizableGraph::Edge
 Edge ()
 
virtual ~Edge ()
 
virtual Edgeclone () const
 
virtual bool setMeasurementData (const double *m)
 
virtual bool getMeasurementData (double *m) const
 
virtual int measurementDimension () const
 
virtual bool setMeasurementFromState ()
 
RobustKernelrobustKernel () const
 if NOT NULL, error of this edge will be robustifed with the kernel More...
 
void setRobustKernel (RobustKernel *ptr)
 
virtual double initialEstimatePossible (const OptimizableGraph::VertexSet &from, OptimizableGraph::Vertex *to)
 
int level () const
 returns the level of the edge More...
 
void setLevel (int l)
 sets the level of the edge More...
 
int dimension () const
 returns the dimensions of the error function More...
 
 G2O_ATTRIBUTE_DEPRECATED (virtual Vertex *createFrom())
 
 G2O_ATTRIBUTE_DEPRECATED (virtual Vertex *createTo())
 
long long internalId () const
 the internal ID of the edge More...
 
OptimizableGraphgraph ()
 
const OptimizableGraphgraph () const
 
bool setParameterId (int argNum, int paramId)
 
const Parameterparameter (int argNo) const
 
size_t numParameters () const
 
void resizeParameters (size_t newSize)
 
- Public Member Functions inherited from g2o::HyperGraph::Edge
 Edge (int id=InvalidId)
 creates and empty edge with no vertices More...
 
const VertexContainervertices () const
 
VertexContainervertices ()
 
const Vertexvertex (size_t i) const
 
Vertexvertex (size_t i)
 
void setVertex (size_t i, Vertex *v)
 
int id () const
 
void setId (int id)
 
virtual HyperGraphElementType elementType () const
 
int numUndefinedVertices () const
 
- Public Member Functions inherited from g2o::HyperGraph::HyperGraphElement
virtual ~HyperGraphElement ()
 
HyperGraphElementclone () const
 
- Public Member Functions inherited from g2o::HyperGraph::DataContainer
 DataContainer ()
 
virtual ~DataContainer ()
 
const DatauserData () const
 the user data associated with this vertex More...
 
DatauserData ()
 
void setUserData (Data *obs)
 
void addUserData (Data *obs)
 

Public Attributes

 EIGEN_MAKE_ALIGNED_OPERATOR_NEW
 
bool pl_pl
 
Matrix3D cov0
 
Matrix3D cov1
 

Static Public Attributes

static Matrix3D dRidx
 
static Matrix3D dRidy
 
static Matrix3D dRidz
 
- Static Public Attributes inherited from g2o::BaseBinaryEdge< 3, EdgeGICP, VertexSE3, VertexSE3 >
static const int Di
 
static const int Dj
 
static const int Dimension
 
- Static Public Attributes inherited from g2o::BaseEdge< D, EdgeGICP >
static const int Dimension
 

Additional Inherited Members

- Public Types inherited from g2o::BaseBinaryEdge< 3, EdgeGICP, VertexSE3, VertexSE3 >
typedef VertexSE3 VertexXiType
 
typedef VertexSE3 VertexXjType
 
typedef BaseEdge< D, EdgeGICP >::Measurement Measurement
 
typedef Eigen::Matrix< double, D, Di, D==1?Eigen::RowMajor:Eigen::ColMajor >::AlignedMapType JacobianXiOplusType
 
typedef Eigen::Matrix< double, D, Dj, D==1?Eigen::RowMajor:Eigen::ColMajor >::AlignedMapType JacobianXjOplusType
 
typedef BaseEdge< D, EdgeGICP >::ErrorVector ErrorVector
 
typedef BaseEdge< D, EdgeGICP >::InformationType InformationType
 
typedef Eigen::Map< Eigen::Matrix< double, Di, Dj, Di==1?Eigen::RowMajor:Eigen::ColMajor >, Eigen::Matrix< double, Di, Dj, Di==1?Eigen::RowMajor:Eigen::ColMajor >::Flags &Eigen::AlignedBit?Eigen::Aligned:Eigen::Unaligned > HessianBlockType
 
typedef Eigen::Map< Eigen::Matrix< double, Dj, Di, Dj==1?Eigen::RowMajor:Eigen::ColMajor >, Eigen::Matrix< double, Dj, Di, Dj==1?Eigen::RowMajor:Eigen::ColMajor >::Flags &Eigen::AlignedBit?Eigen::Aligned:Eigen::Unaligned > HessianBlockTransposedType
 
- Public Types inherited from g2o::BaseEdge< D, EdgeGICP >
typedef EdgeGICP Measurement
 
typedef Eigen::Matrix< double, D, 1, Eigen::ColMajor > ErrorVector
 
typedef Eigen::Matrix< double, D, D, Eigen::ColMajor > InformationType
 
- Protected Member Functions inherited from g2o::BaseEdge< D, EdgeGICP >
InformationType robustInformation (const Vector3D &rho)
 
- Protected Member Functions inherited from g2o::OptimizableGraph::Edge
template<typename ParameterType >
bool installParameter (ParameterType *&p, size_t argNo, int paramId=-1)
 
template<typename CacheType >
void resolveCache (CacheType *&cache, OptimizableGraph::Vertex *, const std::string &_type, const ParameterVector &parameters)
 
bool resolveParameters ()
 
virtual bool resolveCaches ()
 
- Protected Attributes inherited from g2o::BaseBinaryEdge< 3, EdgeGICP, VertexSE3, VertexSE3 >
bool _hessianRowMajor
 
HessianBlockType _hessian
 
HessianBlockTransposedType _hessianTransposed
 
JacobianXiOplusType _jacobianOplusXi
 
JacobianXjOplusType _jacobianOplusXj
 
- Protected Attributes inherited from g2o::BaseEdge< D, EdgeGICP >
Measurement _measurement
 
InformationType _information
 
ErrorVector _error
 
- Protected Attributes inherited from g2o::OptimizableGraph::Edge
int _dimension
 
int _level
 
RobustKernel_robustKernel
 
long long _internalId
 
std::vector< int > _cacheIds
 
std::vector< std::string > _parameterTypes
 
std::vector< Parameter ** > _parameters
 
std::vector< int > _parameterIds
 
- Protected Attributes inherited from g2o::HyperGraph::Edge
VertexContainer _vertices
 
int _id
 unique id More...
 
- Protected Attributes inherited from g2o::HyperGraph::DataContainer
Data_userData
 

Detailed Description

Definition at line 164 of file types_icp.h.

Constructor & Destructor Documentation

g2o::Edge_V_V_GICP::Edge_V_V_GICP ( )
inline

Definition at line 168 of file types_icp.h.

168 : pl_pl(false) {}
g2o::Edge_V_V_GICP::Edge_V_V_GICP ( const Edge_V_V_GICP e)

Definition at line 93 of file types_icp.cpp.

References g2o::BaseEdge< D, EdgeGICP >::_measurement, g2o::HyperGraph::Edge::_vertices, cov0, cov1, g2o::BaseEdge< D, E >::measurement(), g2o::EdgeGICP::normal0, g2o::EdgeGICP::normal1, pl_pl, g2o::EdgeGICP::pos0, g2o::EdgeGICP::pos1, g2o::EdgeGICP::R0, g2o::EdgeGICP::R1, and g2o::HyperGraph::Edge::vertex().

94  : BaseBinaryEdge<3, EdgeGICP, VertexSE3, VertexSE3>()
95  {
96 
97  // Temporary hack - TODO, sort out const-ness properly
98  _vertices[0] = const_cast<HyperGraph::Vertex*> (e->vertex(0));
99  _vertices[1] = const_cast<HyperGraph::Vertex*> (e->vertex(1));
100 
101  _measurement.pos0 = e->measurement().pos0;
102  _measurement.pos1 = e->measurement().pos1;
103  _measurement.normal0 = e->measurement().normal0;
104  _measurement.normal1 = e->measurement().normal1;
105  _measurement.R0 = e->measurement().R0;
106  _measurement.R1 = e->measurement().R1;
107 
108  pl_pl = e->pl_pl;
109  cov0 = e->cov0;
110  cov1 = e->cov1;
111 
112  // TODO the robust kernel is not correctly copied
113  //_robustKernel = e->_robustKernel;
114  }
Matrix3D R0
Definition: types_icp.h:72
Vector3D normal0
Definition: types_icp.h:69
Vector3D pos1
Definition: types_icp.h:66
class G2O_CORE_API Vertex
Definition: hyper_graph.h:78
Vector3D normal1
Definition: types_icp.h:69
Matrix3D R1
Definition: types_icp.h:72
Vector3D pos0
Definition: types_icp.h:66
VertexContainer _vertices
Definition: hyper_graph.h:202

Member Function Documentation

void g2o::Edge_V_V_GICP::computeError ( )
inlinevirtual

Implements g2o::OptimizableGraph::Edge.

Definition at line 180 of file types_icp.h.

References g2o::BaseVertex< D, T >::estimate(), and transform().

181  {
182  // from <ViewPoint> to <Point>
183  const VertexSE3 *vp0 = static_cast<const VertexSE3*>(_vertices[0]);
184  const VertexSE3 *vp1 = static_cast<const VertexSE3*>(_vertices[1]);
185 
186  // get vp1 point into vp0 frame
187  // could be more efficient if we computed this transform just once
188  Vector3D p1;
189 
190 #if 0
191  if (_cnum >= 0 && 0) // using global cache
192  {
193  if (_tainted[_cnum]) // set up transform
194  {
195  _transforms[_cnum] = vp0->estimate().inverse() * vp1->estimate();
196  _tainted[_cnum] = 0;
197  cout << _transforms[_cnum] << endl;
198  }
199  p1 = _transforms[_cnum].map(measurement().pos1); // do the transform
200  }
201  else
202 #endif
203  {
204  p1 = vp1->estimate() * measurement().pos1;
205  p1 = vp0->estimate().inverse() * p1;
206  }
207 
208  // cout << endl << "Error computation; points are: " << endl;
209  // cout << p0.transpose() << endl;
210  // cout << p1.transpose() << endl;
211 
212  // get their difference
213  // this is simple Euclidean distance, for now
214  _error = p1 - measurement().pos0;
215 
216 #if 0
217  cout << "vp0" << endl << vp0->estimate() << endl;
218  cout << "vp1" << endl << vp1->estimate() << endl;
219  cout << "e Jac Xj" << endl << _jacobianOplusXj << endl << endl;
220  cout << "e Jac Xi" << endl << _jacobianOplusXi << endl << endl;
221 #endif
222 
223  if (!pl_pl) return;
224 
225  // re-define the information matrix
226  // topLeftCorner<3,3>() is the rotation()
227  const Matrix3D transform = ( vp0->estimate().inverse() * vp1->estimate() ).matrix().topLeftCorner<3,3>();
228  information() = ( cov0 + transform * cov1 * transform.transpose() ).inverse();
229 
230  }
Eigen::Matrix< double, 3, 1, Eigen::ColMajor > Vector3D
Definition: eigen_types.h:46
void transform(PlaneList &l, const SE3Quat &t)
Definition: plane_test.cpp:17
Vector3D pos1
Definition: types_icp.h:66
Eigen::Matrix< double, 3, 3, Eigen::ColMajor > Matrix3D
Definition: eigen_types.h:61
EIGEN_STRONG_INLINE const InformationType & information() const
information matrix of the constraint
Definition: base_edge.h:67
EIGEN_STRONG_INLINE const Measurement & measurement() const
accessor functions for the measurement represented by the edge
Definition: base_edge.h:75
Vector3D pos0
Definition: types_icp.h:66
VertexContainer _vertices
Definition: hyper_graph.h:202
void g2o::Edge_V_V_GICP::linearizeOplus ( )
virtual

Linearizes the oplus operator in the vertex, and stores the result in temporary variables _jacobianOplusXi and _jacobianOplusXj

Reimplemented from g2o::BaseBinaryEdge< 3, EdgeGICP, VertexSE3, VertexSE3 >.

Definition at line 175 of file types_icp.cpp.

References g2o::BaseBinaryEdge< 3, EdgeGICP, VertexSE3, VertexSE3 >::_jacobianOplusXi, g2o::BaseBinaryEdge< 3, EdgeGICP, VertexSE3, VertexSE3 >::_jacobianOplusXj, g2o::HyperGraph::Edge::_vertices, dRidx, dRidy, dRidz, g2o::BaseVertex< D, T >::estimate(), g2o::OptimizableGraph::Vertex::fixed(), g2o::BaseEdge< D, EdgeGICP >::measurement(), and g2o::EdgeGICP::pos1.

176  {
177  VertexSE3* vp0 = static_cast<VertexSE3*>(_vertices[0]);
178  VertexSE3* vp1 = static_cast<VertexSE3*>(_vertices[1]);
179 
180  // topLeftCorner<3,3>() is the rotation matrix
181  Matrix3D R0T = vp0->estimate().matrix().topLeftCorner<3,3>().transpose();
182  Vector3D p1 = measurement().pos1;
183 
184  // this could be more efficient
185  if (!vp0->fixed())
186  {
187  Isometry3D T01 = vp0->estimate().inverse() * vp1->estimate();
188  Vector3D p1t = T01 * p1;
189  _jacobianOplusXi.block<3,3>(0,0) = -Matrix3D::Identity();
190  _jacobianOplusXi.block<3,1>(0,3) = dRidx*p1t;
191  _jacobianOplusXi.block<3,1>(0,4) = dRidy*p1t;
192  _jacobianOplusXi.block<3,1>(0,5) = dRidz*p1t;
193  }
194 
195  if (!vp1->fixed())
196  {
197  Matrix3D R1 = vp1->estimate().matrix().topLeftCorner<3,3>();
198  R0T = R0T*R1;
199  _jacobianOplusXj.block<3,3>(0,0) = R0T;
200  _jacobianOplusXj.block<3,1>(0,3) = R0T*dRidx.transpose()*p1;
201  _jacobianOplusXj.block<3,1>(0,4) = R0T*dRidy.transpose()*p1;
202  _jacobianOplusXj.block<3,1>(0,5) = R0T*dRidz.transpose()*p1;
203  }
204  }
Eigen::Matrix< double, 3, 1, Eigen::ColMajor > Vector3D
Definition: eigen_types.h:46
static Matrix3D dRidz
Definition: types_icp.h:240
static Matrix3D dRidy
Definition: types_icp.h:239
Vector3D pos1
Definition: types_icp.h:66
static Matrix3D dRidx
Definition: types_icp.h:238
Eigen::Transform< double, 3, Eigen::Isometry, Eigen::ColMajor > Isometry3D
Definition: eigen_types.h:66
Eigen::Matrix< double, 3, 3, Eigen::ColMajor > Matrix3D
Definition: eigen_types.h:61
EIGEN_STRONG_INLINE const Measurement & measurement() const
accessor functions for the measurement represented by the edge
Definition: base_edge.h:75
VertexContainer _vertices
Definition: hyper_graph.h:202
bool g2o::Edge_V_V_GICP::read ( std::istream &  is)
virtual

read the vertex from a stream, i.e., the internal state of the vertex

Implements g2o::OptimizableGraph::Edge.

Definition at line 126 of file types_icp.cpp.

References g2o::BaseEdge< D, EdgeGICP >::_measurement, g2o::BaseEdge< D, EdgeGICP >::information(), g2o::EdgeGICP::makeRot0(), g2o::BaseEdge< D, EdgeGICP >::measurement(), g2o::EdgeGICP::normal0, g2o::EdgeGICP::normal1, g2o::EdgeGICP::pos0, g2o::EdgeGICP::pos1, and g2o::EdgeGICP::R0.

127  {
128  // measured point and normal
129  for (int i=0; i<3; i++)
130  is >> _measurement.pos0[i];
131  for (int i=0; i<3; i++)
132  is >> _measurement.normal0[i];
133 
134  // measured point and normal
135  for (int i=0; i<3; i++)
136  is >> _measurement.pos1[i];
137  for (int i=0; i<3; i++)
138  is >> _measurement.normal1[i];
139 
140  // don't need this if we don't use it in error calculation (???)
141  // inverseMeasurement() = -measurement();
142 
143  _measurement.makeRot0(); // set up rotation matrices
144 
145  // GICP info matrices
146 
147  // point-plane only
148  Matrix3D prec;
149  double v = .01;
150  prec << v, 0, 0,
151  0, v, 0,
152  0, 0, 1;
153  const Matrix3D &R = measurement().R0; // plane of the point in vp0
154  information() = R.transpose()*prec*R;
155 
156  // information().setIdentity();
157 
158  // setRobustKernel(true);
159  //setHuberWidth(0.01); // units? m?
160 
161  return true;
162  }
Matrix3D R0
Definition: types_icp.h:72
Vector3D normal0
Definition: types_icp.h:69
Vector3D pos1
Definition: types_icp.h:66
Eigen::Matrix< double, 3, 3, Eigen::ColMajor > Matrix3D
Definition: eigen_types.h:61
Vector3D normal1
Definition: types_icp.h:69
EIGEN_STRONG_INLINE const InformationType & information() const
information matrix of the constraint
Definition: base_edge.h:67
void makeRot0()
Definition: types_icp.h:87
EIGEN_STRONG_INLINE const Measurement & measurement() const
accessor functions for the measurement represented by the edge
Definition: base_edge.h:75
Vector3D pos0
Definition: types_icp.h:66
bool g2o::Edge_V_V_GICP::write ( std::ostream &  os) const
virtual

write the vertex to a stream

Implements g2o::OptimizableGraph::Edge.

Definition at line 208 of file types_icp.cpp.

References g2o::BaseEdge< D, EdgeGICP >::measurement(), g2o::EdgeGICP::normal0, g2o::EdgeGICP::normal1, g2o::EdgeGICP::pos0, and g2o::EdgeGICP::pos1.

209  {
210  // first point
211  for (int i=0; i<3; i++)
212  os << measurement().pos0[i] << " ";
213  for (int i=0; i<3; i++)
214  os << measurement().normal0[i] << " ";
215 
216  // second point
217  for (int i=0; i<3; i++)
218  os << measurement().pos1[i] << " ";
219  for (int i=0; i<3; i++)
220  os << measurement().normal1[i] << " ";
221 
222 
223  return os.good();
224  }
Vector3D normal0
Definition: types_icp.h:69
Vector3D pos1
Definition: types_icp.h:66
Vector3D normal1
Definition: types_icp.h:69
EIGEN_STRONG_INLINE const Measurement & measurement() const
accessor functions for the measurement represented by the edge
Definition: base_edge.h:75
Vector3D pos0
Definition: types_icp.h:66

Member Data Documentation

Matrix3D g2o::Edge_V_V_GICP::cov0

Definition at line 173 of file types_icp.h.

Referenced by Edge_V_V_GICP().

Matrix3D g2o::Edge_V_V_GICP::cov1

Definition at line 173 of file types_icp.h.

Referenced by Edge_V_V_GICP().

Matrix3D g2o::Edge_V_V_GICP::dRidx
static

Definition at line 238 of file types_icp.h.

Referenced by linearizeOplus().

Matrix3D g2o::Edge_V_V_GICP::dRidy
static

Definition at line 239 of file types_icp.h.

Referenced by linearizeOplus().

Matrix3D g2o::Edge_V_V_GICP::dRidz
static

Definition at line 240 of file types_icp.h.

Referenced by linearizeOplus().

g2o::Edge_V_V_GICP::EIGEN_MAKE_ALIGNED_OPERATOR_NEW

Definition at line 167 of file types_icp.h.

bool g2o::Edge_V_V_GICP::pl_pl

Definition at line 172 of file types_icp.h.

Referenced by Edge_V_V_GICP().


The documentation for this class was generated from the following files: