33 information().setIdentity();
43 g2o::ParameterVector pv(1);
45 resolveCache(
_cache, (g2o::OptimizableGraph::Vertex*)_vertices[0],
"CACHE_SE3_OFFSET", pv);
53 if (!setParameterId(0, pid))
58 for (
int i = 0; i < 3; i++) is >> meas[i];
63 for (
int i = 0; i < 3; i++) {
64 for (
int j = i; j < 3; j++) {
65 is >> information()(i,j);
67 information()(j,i) = information()(i,j);
76 for (
int i = 0; i < 3; i++) os << measurement()[i] <<
" ";
77 for (
int i = 0; i < 3; i++) {
78 for (
int j = i; j < 3; j++) {
79 os << information()(i,j) <<
" ";
86 const g2o::VertexSE3* v =
static_cast<const g2o::VertexSE3*
>(_vertices[0]);
87 _error = v->estimate().translation() - _measurement;
91 const g2o::VertexSE3* v =
static_cast<const g2o::VertexSE3*
>(_vertices[0]);
92 _measurement = v->estimate().translation();
97 g2o::VertexSE3 *v =
static_cast<g2o::VertexSE3*
>(_vertices[0]);
98 assert(v &&
"Vertex for the Prior edge is not set");
100 Eigen::Isometry3d newEstimate =
_offsetParam->offset().inverse() * Eigen::Translation3d(measurement());
101 if (_information.block<3,3>(0,0).array().abs().sum() == 0){
102 newEstimate.translation() = v->estimate().translation();
104 v->setEstimate(newEstimate);
virtual bool read(std::istream &is)
g2o::ParameterSE3Offset * _offsetParam
virtual void setMeasurement(const Eigen::Vector3d &m)
virtual void initialEstimate(const g2o::OptimizableGraph::VertexSet &, g2o::OptimizableGraph::Vertex *)
g2o::CacheSE3Offset * _cache
virtual void computeError()
virtual bool write(std::ostream &os) const
EIGEN_MAKE_ALIGNED_OPERATOR_NEW EdgeSE3XYZPrior()
virtual bool resolveCaches()
virtual bool setMeasurementFromState()