edge_plane_parallel.hpp 4.7 KB

123456789101112131415161718192021222324252627282930313233343536373839404142434445464748495051525354555657585960616263646566676869707172737475767778798081828384858687888990919293949596979899100101102103104105106107108109110111112113114115116117118119120121122123124125126127128129130131132133134135136137138139140141142143144145146147148149150151152153154155156157158159
  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_PARALLEL_HPP
  27. #define EDGE_PLANE_PARALLEL_HPP
  28. #include <Eigen/Dense>
  29. #include <g2o/core/base_binary_edge.h>
  30. #include <g2o/types/slam3d_addons/vertex_plane.h>
  31. namespace g2o {
  32. class EdgePlaneParallel : public BaseBinaryEdge<3, Eigen::Vector3d, VertexPlane, VertexPlane> {
  33. public:
  34. EIGEN_MAKE_ALIGNED_OPERATOR_NEW
  35. EdgePlaneParallel() : BaseBinaryEdge<3, Eigen::Vector3d, VertexPlane, VertexPlane>() {
  36. _information.setIdentity();
  37. _error.setZero();
  38. }
  39. void computeError() override {
  40. const VertexPlane* v1 = static_cast<const VertexPlane*>(_vertices[0]);
  41. const VertexPlane* v2 = static_cast<const VertexPlane*>(_vertices[1]);
  42. Eigen::Vector3d normal1 = v1->estimate().normal();
  43. Eigen::Vector3d normal2 = v2->estimate().normal();
  44. if(normal1.dot(normal2) < 0.0) {
  45. normal2 = -normal2;
  46. }
  47. _error = (normal2 - normal1) - _measurement;
  48. }
  49. virtual bool read(std::istream& is) override {
  50. Eigen::Vector3d v;
  51. for(int i = 0; i < 3; ++i) {
  52. is >> v[i];
  53. }
  54. setMeasurement(v);
  55. for(int i = 0; i < information().rows(); ++i) {
  56. for(int j = i; j < information().cols(); ++j) {
  57. is >> information()(i, j);
  58. if(i != j) {
  59. information()(j, i) = information()(i, j);
  60. }
  61. }
  62. }
  63. return true;
  64. }
  65. virtual bool write(std::ostream& os) const override {
  66. for(int i = 0; i < 3; ++i) {
  67. os << _measurement[i] << " ";
  68. }
  69. for(int i = 0; i < information().rows(); ++i) {
  70. for(int j = i; j < information().cols(); ++j) {
  71. os << " " << information()(i, j);
  72. };
  73. }
  74. return os.good();
  75. }
  76. virtual void setMeasurement(const Eigen::Vector3d& m) override {
  77. _measurement = m;
  78. }
  79. virtual int measurementDimension() const override {
  80. return 3;
  81. }
  82. };
  83. class EdgePlanePerpendicular : public BaseBinaryEdge<1, Eigen::Vector3d, VertexPlane, VertexPlane> {
  84. public:
  85. EIGEN_MAKE_ALIGNED_OPERATOR_NEW
  86. EdgePlanePerpendicular() : BaseBinaryEdge<1, Eigen::Vector3d, VertexPlane, VertexPlane>() {
  87. _information.setIdentity();
  88. _error.setZero();
  89. }
  90. void computeError() override {
  91. const VertexPlane* v1 = static_cast<const VertexPlane*>(_vertices[0]);
  92. const VertexPlane* v2 = static_cast<const VertexPlane*>(_vertices[1]);
  93. Eigen::Vector3d normal1 = v1->estimate().normal().normalized();
  94. Eigen::Vector3d normal2 = v2->estimate().normal().normalized();
  95. _error[0] = normal1.dot(normal2);
  96. }
  97. virtual bool read(std::istream& is) override {
  98. Eigen::Vector3d v;
  99. for(int i = 0; i < 3; ++i) {
  100. is >> v[i];
  101. }
  102. setMeasurement(v);
  103. for(int i = 0; i < information().rows(); ++i) {
  104. for(int j = i; j < information().cols(); ++j) {
  105. is >> information()(i, j);
  106. if(i != j) {
  107. information()(j, i) = information()(i, j);
  108. }
  109. }
  110. }
  111. return true;
  112. }
  113. virtual bool write(std::ostream& os) const override {
  114. for(int i = 0; i < 3; ++i) {
  115. os << _measurement[i] << " ";
  116. }
  117. for(int i = 0; i < information().rows(); ++i) {
  118. for(int j = i; j < information().cols(); ++j) {
  119. os << " " << information()(i, j);
  120. };
  121. }
  122. return os.good();
  123. }
  124. virtual void setMeasurement(const Eigen::Vector3d& m) override {
  125. _measurement = m;
  126. }
  127. virtual int measurementDimension() const override {
  128. return 3;
  129. }
  130. };
  131. } // namespace g2o
  132. #endif // EDGE_PLANE_PARALLEL_HPP