32 using namespace Eigen;
35 namespace deprecated {
37 ParameterSE3Offset::ParameterSE3Offset(){
41 void ParameterSE3Offset::setOffset(
const SE3Quat& offset_){
43 _offsetMatrix= _offset.
rotation().toRotationMatrix();
44 _offsetMatrix.translation() = _offset.translation();
45 _inverseOffsetMatrix = _offsetMatrix.inverse();
48 bool ParameterSE3Offset::read(std::istream& is) {
50 for (
int i=0; i<7; i++) {
52 std::cerr << off[i] <<
" " ;
54 std::cerr << std::endl;
59 bool ParameterSE3Offset::write(std::ostream& os)
const {
61 for (
int i=0; i<7; i++)
66 CacheSE3Offset::CacheSE3Offset() :
98 #ifdef G2O_HAVE_OPENGL 101 refreshPropertyPtrs(0);
108 if (_previousParams){
109 _cubeSide = _previousParams->makeProperty<
FloatProperty>(_typeName +
"::CUBE_SIDE", .05f);
118 if (
typeid(*element).name()!=_typeName)
121 refreshPropertyPtrs(params);
122 if (! _previousParams)
125 if (_show && !_show->value())
131 glTranslatef((
float)offsetT.x(), (float)offsetT.y(), (float)offsetT.z());
132 glRotatef((
float)
RAD2DEG(aa.angle()),(
float)aa.axis().x(),(float)aa.axis().y(),(float)aa.axis().z());
caching the offset related to a vertex
ParameterVector _parameters
const SE3Quat & offset() const
return the offset as SE3Quat
Abstract action that operates on a graph entity.
void setOffsetParam(ParameterSE3Offset *offsetParam)
OptimizableGraph::Vertex * vertex()
Eigen::Matrix< double, 7, 1 > Vector7d
ParameterSE3Offset * _offsetParam
the parameter connected to the cache
Eigen::Isometry3d _w2l
world to local
const Eigen::Quaterniond & rotation() const
3D pose Vertex, (x,y,z,qw,qx,qy,qz) the parameterization for the increments constructed is a 6d vecto...
Eigen::Isometry3d _n2w
sensor to world
virtual bool resolveDependancies()
virtual void updateImpl()
redefine this to do the update
const EstimateType & estimate() const
return the current estimate of the vertex
virtual bool refreshPropertyPtrs(HyperGraphElementAction::Parameters *params_)
Eigen::Isometry3d _w2n
world to sensor transform
const ParameterSE3Offset * offsetParam() const
const Vector3D & translation() const