edge_se3_priorquat.hpp 3.0 KB

123456789101112131415161718192021222324252627282930313233343536373839404142434445464748495051525354555657585960616263646566676869707172737475767778
  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 KKL_G2O_EDGE_SE3_PRIORQUAT_HPP
  27. #define KKL_G2O_EDGE_SE3_PRIORQUAT_HPP
  28. #include <g2o/types/slam3d/types_slam3d.h>
  29. #include <g2o/types/slam3d_addons/types_slam3d_addons.h>
  30. namespace g2o {
  31. class EdgeSE3PriorQuat : public g2o::BaseUnaryEdge<3, Eigen::Quaterniond, g2o::VertexSE3> {
  32. public:
  33. EIGEN_MAKE_ALIGNED_OPERATOR_NEW
  34. EdgeSE3PriorQuat() : g2o::BaseUnaryEdge<3, Eigen::Quaterniond, g2o::VertexSE3>() {}
  35. void computeError() override {
  36. const g2o::VertexSE3* v1 = static_cast<const g2o::VertexSE3*>(_vertices[0]);
  37. Eigen::Quaterniond estimate = Eigen::Quaterniond(v1->estimate().linear());
  38. if(_measurement.coeffs().dot(estimate.coeffs()) < 0.0) {
  39. estimate.coeffs() = -estimate.coeffs();
  40. }
  41. _error = estimate.vec() - _measurement.vec();
  42. }
  43. void setMeasurement(const Eigen::Quaterniond& m) override {
  44. _measurement = m;
  45. if(m.w() < 0.0) {
  46. _measurement.coeffs() = -m.coeffs();
  47. }
  48. }
  49. virtual bool read(std::istream& is) override {
  50. Eigen::Quaterniond q;
  51. is >> q.w() >> q.x() >> q.y() >> q.z();
  52. setMeasurement(q);
  53. for(int i = 0; i < information().rows(); ++i)
  54. for(int j = i; j < information().cols(); ++j) {
  55. is >> information()(i, j);
  56. if(i != j) information()(j, i) = information()(i, j);
  57. }
  58. return true;
  59. }
  60. virtual bool write(std::ostream& os) const override {
  61. Eigen::Quaterniond q = _measurement;
  62. os << q.w() << " " << q.x() << " " << q.y() << " " << q.z();
  63. for(int i = 0; i < information().rows(); ++i)
  64. for(int j = i; j < information().cols(); ++j) os << " " << information()(i, j);
  65. return os.good();
  66. }
  67. };
  68. } // namespace g2o
  69. #endif