g2o
Public Member Functions | Private Member Functions | Private Attributes | List of all members
g2o::EdgeSE3PointXYZDepth Class Reference

#include <edge_se3_pointxyz_depth.h>

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

Public Member Functions

EIGEN_MAKE_ALIGNED_OPERATOR_NEW EdgeSE3PointXYZDepth ()
 
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 ()
 
virtual void setMeasurement (const Vector3D &m)
 
virtual bool setMeasurementData (const double *d)
 
virtual bool getMeasurementData (double *d) const
 
virtual int measurementDimension () const
 
virtual bool setMeasurementFromState ()
 
virtual double initialEstimatePossible (const OptimizableGraph::VertexSet &from, OptimizableGraph::Vertex *to)
 
virtual void initialEstimate (const OptimizableGraph::VertexSet &from, OptimizableGraph::Vertex *to)
 
- Public Member Functions inherited from g2o::BaseBinaryEdge< 3, Vector3D, VertexSE3, VertexPointXYZ >
 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, Vector3D >
 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 int rank () const
 
- Public Member Functions inherited from g2o::OptimizableGraph::Edge
 Edge ()
 
virtual ~Edge ()
 
virtual Edgeclone () const
 
RobustKernelrobustKernel () const
 if NOT NULL, error of this edge will be robustifed with the kernel More...
 
void setRobustKernel (RobustKernel *ptr)
 
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)
 

Private Member Functions

virtual bool resolveCaches ()
 

Private Attributes

Eigen::Matrix< double, 3, 9, Eigen::ColMajor > J
 
ParameterCameraparams
 
CacheCameracache
 

Additional Inherited Members

- Public Types inherited from g2o::BaseBinaryEdge< 3, Vector3D, VertexSE3, VertexPointXYZ >
typedef VertexSE3 VertexXiType
 
typedef VertexPointXYZ VertexXjType
 
typedef BaseEdge< D, Vector3D >::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, Vector3D >::ErrorVector ErrorVector
 
typedef BaseEdge< D, Vector3D >::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, Vector3D >
typedef Vector3D Measurement
 
typedef Eigen::Matrix< double, D, 1, Eigen::ColMajor > ErrorVector
 
typedef Eigen::Matrix< double, D, D, Eigen::ColMajor > InformationType
 
- Static Public Attributes inherited from g2o::BaseBinaryEdge< 3, Vector3D, VertexSE3, VertexPointXYZ >
static const int Di
 
static const int Dj
 
static const int Dimension
 
- Static Public Attributes inherited from g2o::BaseEdge< D, Vector3D >
static const int Dimension
 
- Protected Member Functions inherited from g2o::BaseEdge< D, Vector3D >
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 ()
 
- Protected Attributes inherited from g2o::BaseBinaryEdge< 3, Vector3D, VertexSE3, VertexPointXYZ >
bool _hessianRowMajor
 
HessianBlockType _hessian
 
HessianBlockTransposedType _hessianTransposed
 
JacobianXiOplusType _jacobianOplusXi
 
JacobianXjOplusType _jacobianOplusXj
 
- Protected Attributes inherited from g2o::BaseEdge< D, Vector3D >
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 42 of file edge_se3_pointxyz_depth.h.

Constructor & Destructor Documentation

g2o::EdgeSE3PointXYZDepth::EdgeSE3PointXYZDepth ( )

Definition at line 33 of file edge_se3_pointxyz_depth.cpp.

References g2o::BaseEdge< D, Vector3D >::information(), g2o::OptimizableGraph::Edge::installParameter(), J, params, and g2o::OptimizableGraph::Edge::resizeParameters().

36  information().setIdentity();
37  information()(2,2)=100;
38  J.fill(0);
39  J.block<3,3>(0,0) = -Matrix3D::Identity();
40  }
bool installParameter(ParameterType *&p, size_t argNo, int paramId=-1)
Eigen::Matrix< double, 3, 9, Eigen::ColMajor > J
void resizeParameters(size_t newSize)
EIGEN_STRONG_INLINE const InformationType & information() const
information matrix of the constraint
Definition: base_edge.h:67

Member Function Documentation

void g2o::EdgeSE3PointXYZDepth::computeError ( )
virtual

Implements g2o::OptimizableGraph::Edge.

Definition at line 91 of file edge_se3_pointxyz_depth.cpp.

References g2o::BaseEdge< D, Vector3D >::_error, g2o::BaseEdge< D, Vector3D >::_measurement, g2o::HyperGraph::Edge::_vertices, cache, g2o::BaseVertex< D, T >::estimate(), and g2o::CacheCamera::w2i().

91  {
92  // from cam to point (track)
93  //VertexSE3 *cam = static_cast<VertexSE3*>(_vertices[0]);
94  VertexPointXYZ *point = static_cast<VertexPointXYZ*>(_vertices[1]);
95 
96  Vector3D p = cache->w2i() * point->estimate();
97  Vector3D perr;
98  perr.head<2>() = p.head<2>()/p(2);
99  perr(2) = p(2);
100 
101  // error, which is backwards from the normal observed - calculated
102  // _measurement is the measured projection
103  _error = perr - _measurement;
104  // std::cout << _error << std::endl << std::endl;
105  }
const Affine3D & w2i() const
return the world to image transform
Eigen::Matrix< double, 3, 1, Eigen::ColMajor > Vector3D
Definition: eigen_types.h:46
Vertex for a tracked point in space.
const EstimateType & estimate() const
return the current estimate of the vertex
Definition: base_vertex.h:99
VertexContainer _vertices
Definition: hyper_graph.h:202
virtual bool g2o::EdgeSE3PointXYZDepth::getMeasurementData ( double *  m) const
inlinevirtual

writes the measurement to an array of double

Returns
true on success

Reimplemented from g2o::OptimizableGraph::Edge.

Definition at line 65 of file edge_se3_pointxyz_depth.h.

65  {
66  Eigen::Map<Vector3D> v(d);
67  v=_measurement;
68  return true;
69  }
void g2o::EdgeSE3PointXYZDepth::initialEstimate ( const OptimizableGraph::VertexSet ,
OptimizableGraph::Vertex  
)
virtual

set the estimate of the to vertex, based on the estimate of the from vertices in the edge.

Reimplemented from g2o::BaseEdge< D, Vector3D >.

Definition at line 157 of file edge_se3_pointxyz_depth.cpp.

References g2o::BaseEdge< D, Vector3D >::_measurement, g2o::HyperGraph::Edge::_vertices, g2o::ParameterCamera::invKcam(), g2o::ParameterSE3Offset::offset(), params, and g2o::BaseVertex< D, T >::setEstimate().

158  {
159  (void) from;
160  assert(from.size() == 1 && from.count(_vertices[0]) == 1 && "Can not initialize VertexDepthCam position by VertexTrackXYZ");
161 
162  VertexSE3 *cam = dynamic_cast<VertexSE3*>(_vertices[0]);
163  VertexPointXYZ *point = dynamic_cast<VertexPointXYZ*>(_vertices[1]);
164  const Eigen::Matrix<double, 3, 3, Eigen::ColMajor>& invKcam = params->invKcam();
165  Vector3D p;
166  p(2) = _measurement(2);
167  p.head<2>() = _measurement.head<2>()*p(2);
168  p=invKcam*p;
169  point->setEstimate(cam->estimate() * (params->offset() * p));
170  }
const Matrix3D & invKcam() const
Eigen::Matrix< double, 3, 1, Eigen::ColMajor > Vector3D
Definition: eigen_types.h:46
const Isometry3D & offset() const
rotation of the offset as 3x3 rotation matrix
Vertex for a tracked point in space.
void setEstimate(const EstimateType &et)
set the estimate for the vertex also calls updateCache()
Definition: base_vertex.h:101
3D pose Vertex, represented as an Isometry3D
Definition: vertex_se3.h:50
VertexContainer _vertices
Definition: hyper_graph.h:202
virtual double g2o::EdgeSE3PointXYZDepth::initialEstimatePossible ( const OptimizableGraph::VertexSet from,
OptimizableGraph::Vertex to 
)
inlinevirtual

override in your class if it's possible to initialize the vertices in certain combinations. The return value may correspond to the cost for initiliaizng the vertex but should be positive if the initialization is possible and negative if not possible.

Reimplemented from g2o::OptimizableGraph::Edge.

Definition at line 75 of file edge_se3_pointxyz_depth.h.

76  {
77  (void) to;
78  return (from.count(_vertices[0]) == 1 ? 1.0 : -1.0);
79  }
VertexContainer _vertices
Definition: hyper_graph.h:202
void g2o::EdgeSE3PointXYZDepth::linearizeOplus ( )
virtual

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

Reimplemented from g2o::BaseBinaryEdge< 3, Vector3D, VertexSE3, VertexPointXYZ >.

Definition at line 107 of file edge_se3_pointxyz_depth.cpp.

References g2o::BaseBinaryEdge< 3, Vector3D, VertexSE3, VertexPointXYZ >::_jacobianOplusXi, g2o::BaseBinaryEdge< 3, Vector3D, VertexSE3, VertexPointXYZ >::_jacobianOplusXj, g2o::HyperGraph::Edge::_vertices, cache, g2o::BaseVertex< D, T >::estimate(), J, g2o::ParameterCamera::Kcam_inverseOffsetR(), params, g2o::CacheCamera::w2i(), and g2o::CacheSE3Offset::w2l().

107  {
108  //VertexSE3 *cam = static_cast<VertexSE3 *>(_vertices[0]);
109  VertexPointXYZ *vp = static_cast<VertexPointXYZ *>(_vertices[1]);
110 
111  const Vector3D& pt = vp->estimate();
112 
113  Vector3D Zcam = cache->w2l() * pt;
114 
115  // J(0,3) = -0.0;
116  J(0,4) = -2*Zcam(2);
117  J(0,5) = 2*Zcam(1);
118 
119  J(1,3) = 2*Zcam(2);
120  // J(1,4) = -0.0;
121  J(1,5) = -2*Zcam(0);
122 
123  J(2,3) = -2*Zcam(1);
124  J(2,4) = 2*Zcam(0);
125  // J(2,5) = -0.0;
126 
127  J.block<3,3>(0,6) = cache->w2l().rotation();
128 
129  Eigen::Matrix<double,3,9,Eigen::ColMajor> Jprime = params->Kcam_inverseOffsetR() * J;
130  Vector3D Zprime = cache->w2i() * pt;
131 
132  Eigen::Matrix<double,3,9,Eigen::ColMajor> Jhom;
133  Jhom.block<2,9>(0,0) = 1/(Zprime(2)*Zprime(2)) * (Jprime.block<2,9>(0,0)*Zprime(2) - Zprime.head<2>() * Jprime.block<1,9>(2,0));
134  Jhom.block<1,9>(2,0) = Jprime.block<1,9>(2,0);
135 
136  _jacobianOplusXi = Jhom.block<3,6>(0,0);
137  _jacobianOplusXj = Jhom.block<3,3>(0,6);
138  }
const Affine3D & w2i() const
return the world to image transform
Eigen::Matrix< double, 3, 9, Eigen::ColMajor > J
const Isometry3D & w2l() const
Eigen::Matrix< double, 3, 1, Eigen::ColMajor > Vector3D
Definition: eigen_types.h:46
Vertex for a tracked point in space.
const EstimateType & estimate() const
return the current estimate of the vertex
Definition: base_vertex.h:99
const Matrix3D & Kcam_inverseOffsetR() const
VertexContainer _vertices
Definition: hyper_graph.h:202
virtual int g2o::EdgeSE3PointXYZDepth::measurementDimension ( ) const
inlinevirtual

returns the dimension of the measurement in the extended representation which is used by get/setMeasurement;

Reimplemented from g2o::OptimizableGraph::Edge.

Definition at line 71 of file edge_se3_pointxyz_depth.h.

71 {return 3;}
bool g2o::EdgeSE3PointXYZDepth::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 52 of file edge_se3_pointxyz_depth.cpp.

References g2o::BaseEdge< D, Vector3D >::_measurement, g2o::BaseEdge< D, Vector3D >::information(), setMeasurement(), and g2o::OptimizableGraph::Edge::setParameterId().

52  {
53  int pid;
54  is >> pid;
55  setParameterId(0,pid);
56 
57  // measured keypoint
58  Vector3D meas;
59  for (int i=0; i<3; i++) is >> meas[i];
60  setMeasurement(meas);
61  // don't need this if we don't use it in error calculation (???)
62  // information matrix is the identity for features, could be changed to allow arbitrary covariances
63  if (is.bad()) {
64  return false;
65  }
66  for ( int i=0; i<information().rows() && is.good(); i++)
67  for (int j=i; j<information().cols() && is.good(); j++){
68  is >> information()(i,j);
69  if (i!=j)
70  information()(j,i)=information()(i,j);
71  }
72  if (is.bad()) {
73  // we overwrite the information matrix
74  information().setIdentity();
75  information()(2,2)=10/_measurement(2); // scale the info by the inverse of the measured depth
76  }
77  return true;
78  }
virtual void setMeasurement(const Vector3D &m)
Eigen::Matrix< double, 3, 1, Eigen::ColMajor > Vector3D
Definition: eigen_types.h:46
bool setParameterId(int argNum, int paramId)
EIGEN_STRONG_INLINE const InformationType & information() const
information matrix of the constraint
Definition: base_edge.h:67
bool g2o::EdgeSE3PointXYZDepth::resolveCaches ( )
privatevirtual

Reimplemented from g2o::OptimizableGraph::Edge.

Definition at line 42 of file edge_se3_pointxyz_depth.cpp.

References g2o::HyperGraph::Edge::_vertices, cache, params, and g2o::OptimizableGraph::Edge::resolveCache().

42  {
43  ParameterVector pv(1);
44  pv[0]=params;
45  resolveCache(cache, (OptimizableGraph::Vertex*)_vertices[0],"CACHE_CAMERA",pv);
46  return cache != 0;
47  }
void resolveCache(CacheType *&cache, OptimizableGraph::Vertex *, const std::string &_type, const ParameterVector &parameters)
Definition: cache.h:122
std::vector< Parameter * > ParameterVector
Definition: parameter.h:52
A general case Vertex for optimization.
VertexContainer _vertices
Definition: hyper_graph.h:202
virtual void g2o::EdgeSE3PointXYZDepth::setMeasurement ( const Vector3D m)
inlinevirtual

Reimplemented from g2o::BaseEdge< D, Vector3D >.

Definition at line 55 of file edge_se3_pointxyz_depth.h.

Referenced by g2o::SensorPointXYZDepth::addNoise(), and read().

55  {
56  _measurement = m;
57  }
virtual bool g2o::EdgeSE3PointXYZDepth::setMeasurementData ( const double *  m)
inlinevirtual

sets the measurement from an array of double

Returns
true on success

Reimplemented from g2o::OptimizableGraph::Edge.

Definition at line 59 of file edge_se3_pointxyz_depth.h.

59  {
60  Eigen::Map<const Vector3D> v(d);
61  _measurement = v;
62  return true;
63  }
bool g2o::EdgeSE3PointXYZDepth::setMeasurementFromState ( )
virtual

sets the estimate to have a zero error, based on the current value of the state variables returns false if not supported.

Reimplemented from g2o::OptimizableGraph::Edge.

Definition at line 141 of file edge_se3_pointxyz_depth.cpp.

References g2o::BaseEdge< D, Vector3D >::_measurement, g2o::HyperGraph::Edge::_vertices, cache, g2o::BaseVertex< D, T >::estimate(), and g2o::CacheCamera::w2i().

Referenced by g2o::SensorPointXYZDepth::sense().

141  {
142  //VertexSE3 *cam = static_cast<VertexSE3*>(_vertices[0]);
143  VertexPointXYZ *point = static_cast<VertexPointXYZ*>(_vertices[1]);
144 
145  // calculate the projection
146  const Vector3D& pt = point->estimate();
147 
148  Vector3D p = cache->w2i() * pt;
149  Vector3D perr;
150  perr.head<2>() = p.head<2>()/p(2);
151  perr(2) = p(2);
152  _measurement = perr;
153  return true;
154  }
const Affine3D & w2i() const
return the world to image transform
Eigen::Matrix< double, 3, 1, Eigen::ColMajor > Vector3D
Definition: eigen_types.h:46
Vertex for a tracked point in space.
const EstimateType & estimate() const
return the current estimate of the vertex
Definition: base_vertex.h:99
VertexContainer _vertices
Definition: hyper_graph.h:202
bool g2o::EdgeSE3PointXYZDepth::write ( std::ostream &  os) const
virtual

write the vertex to a stream

Implements g2o::OptimizableGraph::Edge.

Definition at line 80 of file edge_se3_pointxyz_depth.cpp.

References g2o::Parameter::id(), g2o::BaseEdge< D, Vector3D >::information(), g2o::BaseEdge< D, Vector3D >::measurement(), and params.

80  {
81  os << params->id() << " ";
82  for (int i=0; i<3; i++) os << measurement()[i] << " ";
83  for (int i=0; i<information().rows(); i++)
84  for (int j=i; j<information().cols(); j++) {
85  os << information()(i,j) << " ";
86  }
87  return os.good();
88  }
int id() const
Definition: parameter.h:45
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

Member Data Documentation

CacheCamera* g2o::EdgeSE3PointXYZDepth::cache
private
Eigen::Matrix<double,3,9,Eigen::ColMajor> g2o::EdgeSE3PointXYZDepth::J
private

Definition at line 84 of file edge_se3_pointxyz_depth.h.

Referenced by EdgeSE3PointXYZDepth(), and linearizeOplus().

ParameterCamera* g2o::EdgeSE3PointXYZDepth::params
private

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