edge_plane_prior.hpp 3.9 KB

123456789101112131415161718192021222324252627282930313233343536373839404142434445464748495051525354555657585960616263646566676869707172737475767778798081828384858687888990919293949596979899100101102103104105106107
  1. // g2o - General Graph Optimization
  2. // Copyright (C) 2011 R. Kuemmerle, G. Grisetti, W. Burgard
  3. // All rights reserved.
  4. //
  5. // Redistribution and use in source and binary forms, with or without
  6. // modification, are permitted provided that the following conditions are
  7. // met:
  8. //
  9. // * Redistributions of source code must retain the above copyright notice,
  10. // this list of conditions and the following disclaimer.
  11. // * Redistributions in binary form must reproduce the above copyright
  12. // notice, this list of conditions and the following disclaimer in the
  13. // documentation and/or other materials provided with the distribution.
  14. //
  15. // THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS
  16. // IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED
  17. // TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A
  18. // PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT
  19. // HOLDER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, INCIDENTAL,
  20. // SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, BUT NOT LIMITED
  21. // TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS OF USE, DATA, OR
  22. // PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED AND ON ANY THEORY OF
  23. // LIABILITY, WHETHER IN CONTRACT, STRICT LIABILITY, OR TORT (INCLUDING
  24. // NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY OUT OF THE USE OF THIS
  25. // SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE.
  26. #ifndef EDGE_PLANE_PRIOR_HPP
  27. #define EDGE_PLANE_PRIOR_HPP
  28. #include <Eigen/Dense>
  29. #include <g2o/core/base_unary_edge.h>
  30. #include <g2o/types/slam3d_addons/vertex_plane.h>
  31. namespace g2o {
  32. class EdgePlanePriorNormal : public g2o::BaseUnaryEdge<3, Eigen::Vector3d, g2o::VertexPlane> {
  33. public:
  34. EIGEN_MAKE_ALIGNED_OPERATOR_NEW
  35. EdgePlanePriorNormal() : g2o::BaseUnaryEdge<3, Eigen::Vector3d, g2o::VertexPlane>() {}
  36. void computeError() override {
  37. const g2o::VertexPlane* v1 = static_cast<const g2o::VertexPlane*>(_vertices[0]);
  38. Eigen::Vector3d normal = v1->estimate().normal();
  39. if(normal.dot(_measurement) < 0.0) {
  40. normal = -normal;
  41. }
  42. _error = normal - _measurement;
  43. }
  44. void setMeasurement(const Eigen::Vector3d& m) override {
  45. _measurement = m;
  46. }
  47. virtual bool read(std::istream& is) override {
  48. Eigen::Vector3d v;
  49. is >> v(0) >> v(1) >> v(2);
  50. setMeasurement(v);
  51. for(int i = 0; i < information().rows(); ++i)
  52. for(int j = i; j < information().cols(); ++j) {
  53. is >> information()(i, j);
  54. if(i != j) information()(j, i) = information()(i, j);
  55. }
  56. return true;
  57. }
  58. virtual bool write(std::ostream& os) const override {
  59. Eigen::Vector3d v = _measurement;
  60. os << v(0) << " " << v(1) << " " << v(2) << " ";
  61. for(int i = 0; i < information().rows(); ++i)
  62. for(int j = i; j < information().cols(); ++j) os << " " << information()(i, j);
  63. return os.good();
  64. }
  65. };
  66. class EdgePlanePriorDistance : public g2o::BaseUnaryEdge<1, double, g2o::VertexPlane> {
  67. public:
  68. EIGEN_MAKE_ALIGNED_OPERATOR_NEW
  69. EdgePlanePriorDistance() : g2o::BaseUnaryEdge<1, double, g2o::VertexPlane>() {}
  70. void computeError() override {
  71. const g2o::VertexPlane* v1 = static_cast<const g2o::VertexPlane*>(_vertices[0]);
  72. _error[0] = _measurement - v1->estimate().distance();
  73. }
  74. void setMeasurement(const double& m) override {
  75. _measurement = m;
  76. }
  77. virtual bool read(std::istream& is) override {
  78. is >> _measurement;
  79. for(int i = 0; i < information().rows(); ++i)
  80. for(int j = i; j < information().cols(); ++j) {
  81. is >> information()(i, j);
  82. if(i != j) information()(j, i) = information()(i, j);
  83. }
  84. return true;
  85. }
  86. virtual bool write(std::ostream& os) const override {
  87. os << _measurement;
  88. for(int i = 0; i < information().rows(); ++i)
  89. for(int j = i; j < information().cols(); ++j) os << " " << information()(i, j);
  90. return os.good();
  91. }
  92. };
  93. } // namespace g2o
  94. #endif // EDGE_SE3_PRIORXY_HPP