27 #ifndef G2O_EDGE_SE3_PRIOR_XYZ_H 28 #define G2O_EDGE_SE3_PRIOR_XYZ_H 30 #include "g2o/types/slam3d/vertex_se3.h" 31 #include "g2o/core/base_unary_edge.h" 32 #include "g2o/types/slam3d/parameter_se3_offset.h" 36 using namespace Eigen;
44 EIGEN_MAKE_ALIGNED_OPERATOR_NEW
52 Map<const Vector3d> v(d);
65 virtual bool read(std::istream& is);
66 virtual bool write(std::ostream& os)
const;
67 virtual void computeError();
68 virtual bool setMeasurementFromState();
71 virtual void initialEstimate(
const OptimizableGraph::VertexSet& , OptimizableGraph::Vertex* );
76 virtual bool resolveCaches();
83 information().setIdentity();
93 ParameterVector pv(1);
95 resolveCache(
_cache, (OptimizableGraph::Vertex*)_vertices[0],
"CACHE_SE3_OFFSET", pv);
103 if (!setParameterId(0, pid))
108 for (
int i = 0; i < 3; i++) is >> meas[i];
113 for (
int i = 0; i < 3; i++) {
114 for (
int j = i; j < 3; j++) {
115 is >> information()(i,j);
117 information()(j,i) = information()(i,j);
126 for (
int i = 0; i < 3; i++) os << measurement()[i] <<
" ";
127 for (
int i = 0; i < 3; i++) {
128 for (
int j = i; j < 3; j++) {
129 os << information()(i,j) <<
" ";
136 const VertexSE3* v =
static_cast<const VertexSE3*
>(_vertices[0]);
137 _error = v->estimate().translation() - _measurement;
141 const VertexSE3* v =
static_cast<const VertexSE3*
>(_vertices[0]);
142 _measurement = v->estimate().translation();
147 VertexSE3 *v =
static_cast<VertexSE3*
>(_vertices[0]);
148 assert(v &&
"Vertex for the Prior edge is not set");
150 Isometry3d newEstimate =
_offsetParam->offset().inverse() * Translation3d(measurement());
151 if (_information.block<3,3>(0,0).array().abs().sum() == 0){
152 newEstimate.translation() = v->estimate().translation();
154 v->setEstimate(newEstimate);
EIGEN_MAKE_ALIGNED_OPERATOR_NEW EdgeSE3XYZPrior()
virtual void setMeasurement(const Vector3d &m)
virtual bool write(std::ostream &os) const
virtual void computeError()
virtual bool read(std::istream &is)
virtual bool resolveCaches()
virtual int measurementDimension() const
virtual bool setMeasurementFromState()
virtual bool getMeasurementData(double *d) const
const ParameterSE3Offset * offsetParameter()
virtual double initialEstimatePossible(const OptimizableGraph::VertexSet &, OptimizableGraph::Vertex *)
ParameterSE3Offset * _offsetParam
Prior for a 3D pose with constraints only in xyz direction.
virtual void initialEstimate(const OptimizableGraph::VertexSet &, OptimizableGraph::Vertex *)
virtual bool setMeasurementData(const double *d)