30 #ifdef G2O_HAVE_OPENGL 36 #ifdef G2O_HAVE_OPENGL 48 J.block<3,3>(0,0) = -Matrix3D::Identity();
69 for (
int i=0; i<3; i++) is >> meas[i];
75 for (
int i=0; i<
information().rows() && is.good(); i++)
76 for (
int j=i; j<
information().cols() && is.good(); j++){
90 for (
int i=0; i<3; i++) os <<
measurement()[i] <<
" ";
130 J.block<3,3>(0,6) =
cache->
w2l().rotation();
163 assert(from.size() == 1 && from.count(
_vertices[0]) == 1 &&
"Can not initialize VertexDepthCam position by VertexTrackXYZ");
176 #ifdef G2O_HAVE_OPENGL 181 if (
typeid(*element).name()!=_typeName)
183 refreshPropertyPtrs(params_);
184 if (! _previousParams)
187 if (_show && !_show->value())
193 if (! fromEdge || ! toEdge)
197 glPushAttrib(GL_ENABLE_BIT);
198 glDisable(GL_LIGHTING);
200 glVertex3f((
float)fromTransform.translation().x(),(float)fromTransform.translation().y(),(float)fromTransform.translation().z());
Eigen::Matrix< double, 3, 9, Eigen::ColMajor > J
bool installParameter(ParameterType *&p, size_t argNo, int paramId=-1)
const Vertex * vertex(size_t i) const
const Isometry3D & w2l() const
Eigen::Matrix< double, 3, 1, Eigen::ColMajor > Vector3D
const ParameterSE3Offset * offsetParameter()
Abstract action that operates on a graph entity.
std::set< Vertex * > VertexSet
g2o edge from a track to a point node
const Isometry3D & offset() const
rotation of the offset as 3x3 rotation matrix
const Isometry3D & w2n() const
virtual void initialEstimate(const OptimizableGraph::VertexSet &from, OptimizableGraph::Vertex *to)
EIGEN_MAKE_ALIGNED_OPERATOR_NEW EdgeSE3PointXYZ()
const Isometry3D & inverseOffset() const
rotation of the inverse offset as 3x3 rotation matrix
JacobianXiOplusType _jacobianOplusXi
virtual bool setMeasurementFromState()
bool setParameterId(int argNum, int paramId)
virtual bool resolveCaches()
#define LANDMARK_EDGE_COLOR
virtual void setMeasurement(const Vector3D &m)
void resolveCache(CacheType *&cache, OptimizableGraph::Vertex *, const std::string &_type, const ParameterVector ¶meters)
std::vector< Parameter * > ParameterVector
Eigen::Transform< double, 3, Eigen::Isometry, Eigen::ColMajor > Isometry3D
ParameterSE3Offset * offsetParam
Vertex for a tracked point in space.
virtual void linearizeOplus()
void setEstimate(const EstimateType &et)
set the estimate for the vertex also calls updateCache()
A general case Vertex for optimization.
void resizeParameters(size_t newSize)
EIGEN_STRONG_INLINE const InformationType & information() const
information matrix of the constraint
virtual bool write(std::ostream &os) const
write the vertex to a stream
virtual bool read(std::istream &is)
read the vertex from a stream, i.e., the internal state of the vertex
const EstimateType & estimate() const
return the current estimate of the vertex
3D pose Vertex, represented as an Isometry3D
JacobianXjOplusType _jacobianOplusXj
EIGEN_STRONG_INLINE const Measurement & measurement() const
accessor functions for the measurement represented by the edge
VertexContainer _vertices