48 Vector4::MapType(meas.data() + 3).normalize();
50 if (is.bad())
return false;
52 return is.good() || is.eof();
95 if (from_.count(from) > 0) {
107 if (
typeid(*element).name() !=
_typeName)
return nullptr;
120 for (
int i = 0; i < 6; i++) {
121 *(params->
os) << fromV[i] <<
" ";
123 for (
int i = 0; i < 6; i++) {
124 *(params->
os) << toV[i] <<
" ";
126 *(params->
os) << std::endl;
130#ifdef G2O_HAVE_OPENGL
133HyperGraphElementAction* EdgeSE3DrawAction::operator()(
134 HyperGraph::HyperGraphElement* element,
135 HyperGraphElementAction::Parameters* params_) {
136 if (
typeid(*element).name() != _typeName)
return nullptr;
137 refreshPropertyPtrs(params_);
138 if (!_previousParams)
return this;
140 if (_show && !_show->value())
return this;
142 EdgeSE3* e =
static_cast<EdgeSE3*
>(element);
143 VertexSE3* fromEdge =
static_cast<VertexSE3*
>(e->vertices()[0]);
144 VertexSE3* toEdge =
static_cast<VertexSE3*
>(e->vertices()[1]);
145 if (!fromEdge || !toEdge)
return this;
147 glPushAttrib(GL_ENABLE_BIT);
148 glDisable(GL_LIGHTING);
150 glVertex3f((
float)fromEdge->estimate().translation().x(),
151 (
float)fromEdge->estimate().translation().y(),
152 (
float)fromEdge->estimate().translation().z());
153 glVertex3f((
float)toEdge->estimate().translation().x(),
154 (
float)toEdge->estimate().translation().y(),
155 (
float)toEdge->estimate().translation().z());
BaseFixedSizedEdge< D, Isometry3, VertexSE3, VertexSE3 >::template JacobianType< D, VertexXj::Dimension > & _jacobianOplusXj
BaseFixedSizedEdge< D, Isometry3, VertexSE3, VertexSE3 >::template JacobianType< D, VertexXi::Dimension > & _jacobianOplusXi
bool writeInformationMatrix(std::ostream &os) const
write the upper trinagular part of the information matrix into the stream
bool readInformationMatrix(std::istream &is)
EIGEN_STRONG_INLINE const Measurement & measurement() const
accessor functions for the measurement represented by the edge
EIGEN_STRONG_INLINE const InformationType & information() const
information matrix of the constraint
Measurement _measurement
the measurement of the edge
const EstimateType & estimate() const
return the current estimate of the vertex
void setEstimate(const EstimateType &et)
set the estimate for the vertex also calls updateCache()
virtual HyperGraphElementAction * operator()(HyperGraph::HyperGraphElement *element, HyperGraphElementAction::Parameters *params_)
EdgeSE3WriteGnuplotAction()
Edge between two 3D pose vertices.
virtual void setMeasurement(const Isometry3 &m)
virtual bool read(std::istream &is)
read the vertex from a stream, i.e., the internal state of the vertex
virtual bool write(std::ostream &os) const
write the vertex to a stream
Isometry3 _inverseMeasurement
virtual void initialEstimate(const OptimizableGraph::VertexSet &from, OptimizableGraph::Vertex *to)
virtual bool setMeasurementFromState()
Abstract action that operates on a graph entity.
const VertexContainer & vertices() const
VertexContainer _vertices
std::set< Vertex * > VertexSet
A general case Vertex for optimization.
3D pose Vertex, represented as an Isometry3
Isometry3 fromVectorQT(const Vector7 &v)
Vector6 toVectorMQT(const Isometry3 &t)
void computeEdgeSE3Gradient(Isometry3 &E, Eigen::MatrixBase< Derived > const &JiConstRef, Eigen::MatrixBase< Derived > const &JjConstRef, const Isometry3 &Z, const Isometry3 &Xi, const Isometry3 &Xj, const Isometry3 &Pi, const Isometry3 &Pj)
bool writeVector(std::ostream &os, const Eigen::DenseBase< Derived > &b)
bool readVector(std::istream &is, Eigen::DenseBase< Derived > &b)
Vector7 toVectorQT(const Isometry3 &t)
Eigen::Transform< double, 3, Eigen::Isometry, Eigen::ColMajor > Isometry3