g2o(6)2d-3d 重投影

发布时间 2023-11-17 03:54:54作者: MKT-porter

 

 

1节点

1-1位姿节点

 vertex_se3_expmap.h

// g2o - General Graph Optimization


#ifndef G2O_SBA_VERTEXSE3EXPMAP_H
#define G2O_SBA_VERTEXSE3EXPMAP_H

#include "g2o/core/base_vertex.h"
#include "g2o/types/slam3d/se3quat.h"
#include "g2o_types_sba_api.h"

namespace g2o {

/**
 * \brief SE3 Vertex parameterized internally with a transformation matrix
 * and externally with its exponential map
 */
class G2O_TYPES_SBA_API VertexSE3Expmap : public BaseVertex<6, SE3Quat> {
 public:
  EIGEN_MAKE_ALIGNED_OPERATOR_NEW

  VertexSE3Expmap();

  bool read(std::istream& is);
  bool write(std::ostream& os) const;
  void setToOriginImpl();
  void oplusImpl(const double* update_);
};

}  // namespace g2o

#endif

  

vertex_se3_expmap.cpp

// g2o - General Graph Optimization


#include "vertex_se3_expmap.h"

#include "g2o/stuff/misc.h"

namespace g2o {

VertexSE3Expmap::VertexSE3Expmap() : BaseVertex<6, SE3Quat>() {}

bool VertexSE3Expmap::read(std::istream& is) {
  Vector7 est;
  internal::readVector(is, est);
  setEstimate(SE3Quat(est).inverse());
  return true;
}

bool VertexSE3Expmap::write(std::ostream& os) const {
  return internal::writeVector(os, estimate().inverse().toVector());
}

void VertexSE3Expmap::setToOriginImpl() { _estimate = SE3Quat(); }

void VertexSE3Expmap::oplusImpl(const double* update_) {
  Eigen::Map<const Vector6> update(update_);
  setEstimate(SE3Quat::exp(update) * estimate());
}

}  // namespace g2o

  

1-2 地图点

简化版本 以前的api

 class G2O_TYPES_SBA_API VertexSBAPointXYZ : public BaseVertex<3, Vector3>
{
  public:
    EIGEN_MAKE_ALIGNED_OPERATOR_NEW    
    VertexSBAPointXYZ();
    virtual bool read(std::istream& is);
    virtual bool write(std::ostream& os) const;
    virtual void setToOriginImpl() {
      _estimate.fill(0);
    }

    virtual void oplusImpl(const number_t* update)
    {
      Eigen::Map<const Vector3> v(update);
      _estimate += v;
    }
};

  

复杂版本 最新的api

 

vertex_pointxyz.h

// g2o - General Graph Optimization


#ifndef G2O_VERTEX_TRACKXYZ_H_
#define G2O_VERTEX_TRACKXYZ_H_

#include "g2o/core/base_vertex.h"
#include "g2o/core/hyper_graph_action.h"
#include "g2o_types_slam3d_api.h"

namespace g2o {
/**
 * \brief Vertex for a tracked point in space
 */
class G2O_TYPES_SLAM3D_API VertexPointXYZ : public BaseVertex<3, Vector3> {
 public:
  EIGEN_MAKE_ALIGNED_OPERATOR_NEW;
  VertexPointXYZ() {}
  virtual bool read(std::istream& is);
  virtual bool write(std::ostream& os) const;

  virtual void setToOriginImpl() { _estimate.fill(0.); }

  virtual void oplusImpl(const double* update_) {
    Eigen::Map<const Vector3> update(update_);
    _estimate += update;
  }

  virtual bool setEstimateDataImpl(const double* est) {
    Eigen::Map<const Vector3> estMap(est);
    _estimate = estMap;
    return true;
  }

  virtual bool getEstimateData(double* est) const {
    Eigen::Map<Vector3> estMap(est);
    estMap = _estimate;
    return true;
  }

  virtual int estimateDimension() const { return Dimension; }

  virtual bool setMinimalEstimateDataImpl(const double* est) {
    _estimate = Eigen::Map<const Vector3>(est);
    return true;
  }

  virtual bool getMinimalEstimateData(double* est) const {
    Eigen::Map<Vector3> v(est);
    v = _estimate;
    return true;
  }

  virtual int minimalEstimateDimension() const { return Dimension; }
};

class G2O_TYPES_SLAM3D_API VertexPointXYZWriteGnuplotAction
    : public WriteGnuplotAction {
 public:
  VertexPointXYZWriteGnuplotAction();
  virtual HyperGraphElementAction* operator()(
      HyperGraph::HyperGraphElement* element,
      HyperGraphElementAction::Parameters* params_);
};

#ifdef G2O_HAVE_OPENGL
/**
 * \brief visualize a 3D point
 */
class VertexPointXYZDrawAction : public DrawAction {
 public:
  VertexPointXYZDrawAction();
  virtual HyperGraphElementAction* operator()(
      HyperGraph::HyperGraphElement* element,
      HyperGraphElementAction::Parameters* params_);

 protected:
  FloatProperty* _pointSize;
  virtual bool refreshPropertyPtrs(
      HyperGraphElementAction::Parameters* params_);
};
#endif

}  // namespace g2o
#endif

  

vertex_pointxyz.cpp

// g2o - General Graph Optimization


#include "vertex_pointxyz.h"

#include <stdio.h>

#ifdef G2O_HAVE_OPENGL
#include "g2o/stuff/opengl_primitives.h"
#include "g2o/stuff/opengl_wrapper.h"
#endif

#include <typeinfo>

namespace g2o {

bool VertexPointXYZ::read(std::istream& is) {
  return internal::readVector(is, _estimate);
}

bool VertexPointXYZ::write(std::ostream& os) const {
  return internal::writeVector(os, estimate());
}

#ifdef G2O_HAVE_OPENGL
VertexPointXYZDrawAction::VertexPointXYZDrawAction()
    : DrawAction(typeid(VertexPointXYZ).name()), _pointSize(nullptr) {}

bool VertexPointXYZDrawAction::refreshPropertyPtrs(
    HyperGraphElementAction::Parameters* params_) {
  if (!DrawAction::refreshPropertyPtrs(params_)) return false;
  if (_previousParams) {
    _pointSize = _previousParams->makeProperty<FloatProperty>(
        _typeName + "::POINT_SIZE", 1.);
  } else {
    _pointSize = nullptr;
  }
  return true;
}

HyperGraphElementAction* VertexPointXYZDrawAction::operator()(
    HyperGraph::HyperGraphElement* element,
    HyperGraphElementAction::Parameters* params) {
  if (typeid(*element).name() != _typeName) return nullptr;
  initializeDrawActionsCache();
  refreshPropertyPtrs(params);
  if (!_previousParams) return this;

  if (_show && !_show->value()) return this;
  VertexPointXYZ* that = static_cast<VertexPointXYZ*>(element);

  glPushMatrix();
  glPushAttrib(GL_ENABLE_BIT | GL_POINT_BIT);
  glDisable(GL_LIGHTING);
  glColor3f(LANDMARK_VERTEX_COLOR);
  float ps = _pointSize ? _pointSize->value() : 1.f;
  glTranslatef((float)that->estimate()(0), (float)that->estimate()(1),
               (float)that->estimate()(2));
  opengl::drawPoint(ps);
  glPopAttrib();
  drawCache(that->cacheContainer(), params);
  drawUserData(that->userData(), params);
  glPopMatrix();
  return this;
}
#endif

VertexPointXYZWriteGnuplotAction::VertexPointXYZWriteGnuplotAction()
    : WriteGnuplotAction(typeid(VertexPointXYZ).name()) {}

HyperGraphElementAction* VertexPointXYZWriteGnuplotAction::operator()(
    HyperGraph::HyperGraphElement* element,
    HyperGraphElementAction::Parameters* params_) {
  if (typeid(*element).name() != _typeName) return nullptr;
  WriteGnuplotAction::Parameters* params =
      static_cast<WriteGnuplotAction::Parameters*>(params_);
  if (!params->os) {
    return nullptr;
  }

  VertexPointXYZ* v = static_cast<VertexPointXYZ*>(element);
  *(params->os) << v->estimate().x() << " " << v->estimate().y() << " "
                << v->estimate().z() << " " << std::endl;
  return this;
}

}  // namespace g2o

  

 

二元边

 

edge_project_xyz2uv.h

// g2o - General Graph Optimization


#ifndef G2O_SBA_EDGEPROJECTXYZ2UV_H
#define G2O_SBA_EDGEPROJECTXYZ2UV_H

#include "g2o/core/base_binary_edge.h"
#include "g2o/types/slam3d/vertex_pointxyz.h"
#include "g2o_types_sba_api.h"
#include "parameter_cameraparameters.h"
#include "vertex_se3_expmap.h"

namespace g2o {

class G2O_TYPES_SBA_API EdgeProjectXYZ2UV
    : public BaseBinaryEdge<2, Vector2, VertexPointXYZ, VertexSE3Expmap> {
 public:
  EIGEN_MAKE_ALIGNED_OPERATOR_NEW;

  EdgeProjectXYZ2UV();
  bool read(std::istream& is);
  bool write(std::ostream& os) const;
  void computeError();
  virtual void linearizeOplus();

 public:
  CameraParameters* _cam;  // TODO make protected member?
};

}  // namespace g2o

#endif

  

edge_project_xyz2uv.cpp

// g2o - General Graph Optimization


#include "edge_project_xyz2uv.h"

namespace g2o {

EdgeProjectXYZ2UV::EdgeProjectXYZ2UV()
    : BaseBinaryEdge<2, Vector2, VertexPointXYZ, VertexSE3Expmap>() {
  _cam = 0;
  resizeParameters(1);
  installParameter(_cam, 0);
}

bool EdgeProjectXYZ2UV::read(std::istream& is) {
  readParamIds(is);
  internal::readVector(is, _measurement);
  return readInformationMatrix(is);
}

bool EdgeProjectXYZ2UV::write(std::ostream& os) const {
  writeParamIds(os);
  internal::writeVector(os, measurement());
  return writeInformationMatrix(os);
}

void EdgeProjectXYZ2UV::computeError() {
  const VertexSE3Expmap* v1 = static_cast<const VertexSE3Expmap*>(_vertices[1]);
  const VertexPointXYZ* v2 = static_cast<const VertexPointXYZ*>(_vertices[0]);
  const CameraParameters* cam =
      static_cast<const CameraParameters*>(parameter(0));
  _error = measurement() - cam->cam_map(v1->estimate().map(v2->estimate()));
}

void EdgeProjectXYZ2UV::linearizeOplus() {
  VertexSE3Expmap* vj = static_cast<VertexSE3Expmap*>(_vertices[1]);
  SE3Quat T(vj->estimate());
  VertexPointXYZ* vi = static_cast<VertexPointXYZ*>(_vertices[0]);
  Vector3 xyz = vi->estimate();
  Vector3 xyz_trans = T.map(xyz);

  double x = xyz_trans[0];
  double y = xyz_trans[1];
  double z = xyz_trans[2];
  double z_2 = z * z;

  const CameraParameters* cam =
      static_cast<const CameraParameters*>(parameter(0));

  Eigen::Matrix<double, 2, 3, Eigen::ColMajor> tmp;
  tmp(0, 0) = cam->focal_length;
  tmp(0, 1) = 0;
  tmp(0, 2) = -x / z * cam->focal_length;

  tmp(1, 0) = 0;
  tmp(1, 1) = cam->focal_length;
  tmp(1, 2) = -y / z * cam->focal_length;

  _jacobianOplusXi = -1. / z * tmp * T.rotation().toRotationMatrix();

  _jacobianOplusXj(0, 0) = x * y / z_2 * cam->focal_length;
  _jacobianOplusXj(0, 1) = -(1 + (x * x / z_2)) * cam->focal_length;
  _jacobianOplusXj(0, 2) = y / z * cam->focal_length;
  _jacobianOplusXj(0, 3) = -1. / z * cam->focal_length;
  _jacobianOplusXj(0, 4) = 0;
  _jacobianOplusXj(0, 5) = x / z_2 * cam->focal_length;

  _jacobianOplusXj(1, 0) = (1 + y * y / z_2) * cam->focal_length;
  _jacobianOplusXj(1, 1) = -x * y / z_2 * cam->focal_length;
  _jacobianOplusXj(1, 2) = -x / z * cam->focal_length;
  _jacobianOplusXj(1, 3) = 0;
  _jacobianOplusXj(1, 4) = -1. / z * cam->focal_length;
  _jacobianOplusXj(1, 5) = y / z_2 * cam->focal_length;
}

}  // namespace g2o