local_parameterization_se3.hpp 1.3 KB

1234567891011121314151617181920212223242526272829303132333435363738394041424344454647
  1. #ifndef SOPHUS_TEST_LOCAL_PARAMETERIZATION_SE3_HPP
  2. #define SOPHUS_TEST_LOCAL_PARAMETERIZATION_SE3_HPP
  3. #include <ceres/local_parameterization.h>
  4. #include <sophus/se3.hpp>
  5. namespace Sophus {
  6. namespace test {
  7. class LocalParameterizationSE3 : public ceres::LocalParameterization {
  8. public:
  9. virtual ~LocalParameterizationSE3() {}
  10. // SE3 plus operation for Ceres
  11. //
  12. // T * exp(x)
  13. //
  14. virtual bool Plus(double const* T_raw, double const* delta_raw,
  15. double* T_plus_delta_raw) const {
  16. Eigen::Map<SE3d const> const T(T_raw);
  17. Eigen::Map<Vector6d const> const delta(delta_raw);
  18. Eigen::Map<SE3d> T_plus_delta(T_plus_delta_raw);
  19. T_plus_delta = T * SE3d::exp(delta);
  20. return true;
  21. }
  22. // Jacobian of SE3 plus operation for Ceres
  23. //
  24. // Dx T * exp(x) with x=0
  25. //
  26. virtual bool ComputeJacobian(double const* T_raw,
  27. double* jacobian_raw) const {
  28. Eigen::Map<SE3d const> T(T_raw);
  29. Eigen::Map<Eigen::Matrix<double, 7, 6, Eigen::RowMajor>> jacobian(
  30. jacobian_raw);
  31. jacobian = T.Dx_this_mul_exp_x_at_0();
  32. return true;
  33. }
  34. virtual int GlobalSize() const { return SE3d::num_parameters; }
  35. virtual int LocalSize() const { return SE3d::DoF; }
  36. };
  37. } // namespace test
  38. } // namespace Sophus
  39. #endif