relative_pose_error.h 3.8 KB

123456789101112131415161718192021222324252627282930313233343536373839404142434445464748495051525354555657585960616263646566676869707172737475767778798081828384858687
  1. // Ceres Solver - A fast non-linear least squares minimizer
  2. // Copyright 2020 Google Inc. All rights reserved.
  3. // http://ceres-solver.org/
  4. //
  5. // Redistribution and use in source and binary forms, with or without
  6. // modification, are permitted provided that the following conditions are met:
  7. //
  8. // * Redistributions of source code must retain the above copyright notice,
  9. // this list of conditions and the following disclaimer.
  10. // * Redistributions in binary form must reproduce the above copyright notice,
  11. // this list of conditions and the following disclaimer in the documentation
  12. // and/or other materials provided with the distribution.
  13. // * Neither the name of Google Inc. nor the names of its contributors may be
  14. // used to endorse or promote products derived from this software without
  15. // specific prior written permission.
  16. //
  17. // THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS"
  18. // AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE
  19. // IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE
  20. // ARE DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT OWNER OR CONTRIBUTORS BE
  21. // LIABLE FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR
  22. // CONSEQUENTIAL DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF
  23. // SUBSTITUTE GOODS OR SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS
  24. // INTERRUPTION) HOWEVER CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN
  25. // CONTRACT, STRICT LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE)
  26. // ARISING IN ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
  27. // POSSIBILITY OF SUCH DAMAGE.
  28. //
  29. // Author: nikolaus@nikolaus-demmel.de (Nikolaus Demmel)
  30. //
  31. //
  32. #ifndef CERES_INTERNAL_AUTODIFF_BENCHMARK_RELATIVE_POSE_ERROR_H_
  33. #define CERES_INTERNAL_AUTODIFF_BENCHMARK_RELATIVE_POSE_ERROR_H_
  34. #include <Eigen/Dense>
  35. #include <utility>
  36. #include "ceres/rotation.h"
  37. namespace ceres {
  38. // Relative pose error as one might use in SE(3) pose graph optimization.
  39. // The measurement is a relative pose T_i_j, and the parameters are absolute
  40. // poses T_w_i and T_w_j. For the residual we use the log of the the residual
  41. // pose, in split representation SO(3) x R^3.
  42. struct RelativePoseError {
  43. RelativePoseError(Eigen::Quaterniond q_i_j, Eigen::Vector3d t_i_j)
  44. : meas_q_i_j_(std::move(q_i_j)), meas_t_i_j_(std::move(t_i_j)) {}
  45. template <typename T>
  46. inline bool operator()(const T* const pose_i_ptr,
  47. const T* const pose_j_ptr,
  48. T* residuals_ptr) const {
  49. Eigen::Map<const Eigen::Quaternion<T>> q_w_i(pose_i_ptr);
  50. Eigen::Map<const Eigen::Matrix<T, 3, 1>> t_w_i(pose_i_ptr + 4);
  51. Eigen::Map<const Eigen::Quaternion<T>> q_w_j(pose_j_ptr);
  52. Eigen::Map<const Eigen::Matrix<T, 3, 1>> t_w_j(pose_j_ptr + 4);
  53. Eigen::Map<Eigen::Matrix<T, 6, 1>> residuals(residuals_ptr);
  54. // Compute estimate of relative pose from i to j.
  55. const Eigen::Quaternion<T> est_q_j_i = q_w_j.conjugate() * q_w_i;
  56. const Eigen::Matrix<T, 3, 1> est_t_j_i =
  57. q_w_j.conjugate() * (t_w_i - t_w_j);
  58. // Compute residual pose.
  59. const Eigen::Quaternion<T> res_q = meas_q_i_j_.cast<T>() * est_q_j_i;
  60. const Eigen::Matrix<T, 3, 1> res_t =
  61. meas_q_i_j_.cast<T>() * est_t_j_i + meas_t_i_j_;
  62. // Convert quaternion to ceres convention (Eigen stores xyzw, Ceres wxyz).
  63. Eigen::Matrix<T, 4, 1> res_q_ceres;
  64. res_q_ceres << res_q.w(), res_q.vec();
  65. // Residual is log of pose. Use split representation SO(3) x R^3.
  66. QuaternionToAngleAxis(res_q_ceres.data(), residuals.data());
  67. residuals.template bottomRows<3>() = res_t;
  68. return true;
  69. }
  70. private:
  71. // Measurement of relative pose from j to i.
  72. Eigen::Quaterniond meas_q_i_j_;
  73. Eigen::Vector3d meas_t_i_j_;
  74. };
  75. } // namespace ceres
  76. #endif // CERES_INTERNAL_AUTODIFF_BENCHMARK_RELATIVE_POSE_ERROR_H_