test_ceres_se3.cpp
Go to the documentation of this file.
1 #include <ceres/ceres.h>
2 #include <iostream>
3 #include <sophus/se3.hpp>
4 
6 
7 // Eigen's ostream operator is not compatible with ceres::Jet types.
8 // In particular, Eigen assumes that the scalar type (here Jet<T,N>) can be
9 // casted to an arithmetic type, which is not true for ceres::Jet.
10 // Unfortunately, the ceres::Jet class does not define a conversion
11 // operator (http://en.cppreference.com/w/cpp/language/cast_operator).
12 //
13 // This workaround creates a template specialization for Eigen's cast_impl,
14 // when casting from a ceres::Jet type. It relies on Eigen's internal API and
15 // might break with future versions of Eigen.
16 namespace Eigen {
17 namespace internal {
18 
19 template <class T, int N, typename NewType>
20 struct cast_impl<ceres::Jet<T, N>, NewType> {
22  static inline NewType run(ceres::Jet<T, N> const& x) {
23  return static_cast<NewType>(x.a);
24  }
25 };
26 
27 } // namespace internal
28 } // namespace Eigen
29 
31  EIGEN_MAKE_ALIGNED_OPERATOR_NEW
33 
34  template <class T>
35  bool operator()(T const* const sT_wa, T* sResiduals) const {
36  Eigen::Map<Sophus::SE3<T> const> const T_wa(sT_wa);
37  Eigen::Map<Eigen::Matrix<T, 6, 1> > residuals(sResiduals);
38 
39  // We are able to mix Sophus types with doubles and Jet types without
40  // needing to cast to T.
41  residuals = (T_aw * T_wa).log();
42  // Reverse order of multiplication. This forces the compiler to verify that
43  // (Jet, double) and (double, Jet) SE3 multiplication work correctly.
44  residuals = (T_wa * T_aw).log();
45  // Finally, ensure that Jet-to-Jet multiplication works.
46  residuals = (T_wa * T_aw.cast<T>()).log();
47  return true;
48  }
49 
51 };
52 
54  EIGEN_MAKE_ALIGNED_OPERATOR_NEW
56  : T_aw(T_aw), point_a(point_a) {}
57 
58  template <class T>
59  bool operator()(T const* const sT_wa, T const* const spoint_b,
60  T* sResiduals) const {
61  using Vector3T = Eigen::Matrix<T, 3, 1>;
62  Eigen::Map<Sophus::SE3<T> const> const T_wa(sT_wa);
63  Eigen::Map<Vector3T const> point_b(spoint_b);
64  Eigen::Map<Vector3T> residuals(sResiduals);
65 
66  // Multiply SE3d by Jet Vector3.
67  Vector3T point_b_prime = T_aw * point_b;
68  // Ensure Jet SE3 multiplication with Jet Vector3.
69  point_b_prime = T_aw.cast<T>() * point_b;
70 
71  // Multiply Jet SE3 with Vector3d.
72  Vector3T point_a_prime = T_wa * point_a;
73  // Ensure Jet SE3 multiplication with Jet Vector3.
74  point_a_prime = T_wa * point_a.cast<T>();
75 
76  residuals = point_b_prime - point_a_prime;
77  return true;
78  }
79 
82 };
83 
84 bool test(Sophus::SE3d const& T_w_targ, Sophus::SE3d const& T_w_init,
85  Sophus::SE3d::Point const& point_a_init,
86  Sophus::SE3d::Point const& point_b) {
87  static constexpr int kNumPointParameters = 3;
88 
89  // Optimisation parameters.
90  Sophus::SE3d T_wr = T_w_init;
91  Sophus::SE3d::Point point_a = point_a_init;
92 
93  // Build the problem.
94  ceres::Problem problem;
95 
96  // Specify local update rule for our parameter
97  problem.AddParameterBlock(T_wr.data(), Sophus::SE3d::num_parameters,
99 
100  // Create and add cost functions. Derivatives will be evaluated via
101  // automatic differentiation
102  ceres::CostFunction* cost_function1 =
103  new ceres::AutoDiffCostFunction<TestSE3CostFunctor, Sophus::SE3d::DoF,
105  new TestSE3CostFunctor(T_w_targ.inverse()));
106  problem.AddResidualBlock(cost_function1, NULL, T_wr.data());
107  ceres::CostFunction* cost_function2 =
108  new ceres::AutoDiffCostFunction<TestPointCostFunctor, kNumPointParameters,
110  kNumPointParameters>(
111  new TestPointCostFunctor(T_w_targ.inverse(), point_b));
112  problem.AddResidualBlock(cost_function2, NULL, T_wr.data(), point_a.data());
113 
114  // Set solver options (precision / method)
115  ceres::Solver::Options options;
116  options.gradient_tolerance = 0.01 * Sophus::Constants<double>::epsilon();
117  options.function_tolerance = 0.01 * Sophus::Constants<double>::epsilon();
118  options.linear_solver_type = ceres::DENSE_QR;
119 
120  // Solve
121  ceres::Solver::Summary summary;
122  Solve(options, &problem, &summary);
123  std::cout << summary.BriefReport() << std::endl;
124 
125  // Difference between target and parameter
126  double const mse = (T_w_targ.inverse() * T_wr).log().squaredNorm();
127  bool const passed = mse < 10. * Sophus::Constants<double>::epsilon();
128  return passed;
129 }
130 
131 template <typename Scalar>
132 bool CreateSE3FromMatrix(const Eigen::Matrix<Scalar, 4, 4>& mat) {
134  std::cout << se3.translation().x() << std::endl;
135  return true;
136 }
137 
138 int main(int, char**) {
139  using SE3Type = Sophus::SE3<double>;
140  using SO3Type = Sophus::SO3<double>;
141  using Point = SE3Type::Point;
142  double const kPi = Sophus::Constants<double>::pi();
143 
144  std::vector<SE3Type> se3_vec;
145  se3_vec.push_back(
146  SE3Type(SO3Type::exp(Point(0.2, 0.5, 0.0)), Point(0, 0, 0)));
147  se3_vec.push_back(
148  SE3Type(SO3Type::exp(Point(0.2, 0.5, -1.0)), Point(10, 0, 0)));
149  se3_vec.push_back(SE3Type(SO3Type::exp(Point(0., 0., 0.)), Point(0, 100, 5)));
150  se3_vec.push_back(
151  SE3Type(SO3Type::exp(Point(0., 0., 0.00001)), Point(0, 0, 0)));
152  se3_vec.push_back(SE3Type(SO3Type::exp(Point(0., 0., 0.00001)),
153  Point(0, -0.00000001, 0.0000000001)));
154  se3_vec.push_back(
155  SE3Type(SO3Type::exp(Point(0., 0., 0.00001)), Point(0.01, 0, 0)));
156  se3_vec.push_back(SE3Type(SO3Type::exp(Point(kPi, 0, 0)), Point(4, -5, 0)));
157  se3_vec.push_back(
158  SE3Type(SO3Type::exp(Point(0.2, 0.5, 0.0)), Point(0, 0, 0)) *
159  SE3Type(SO3Type::exp(Point(kPi, 0, 0)), Point(0, 0, 0)) *
160  SE3Type(SO3Type::exp(Point(-0.2, -0.5, -0.0)), Point(0, 0, 0)));
161  se3_vec.push_back(
162  SE3Type(SO3Type::exp(Point(0.3, 0.5, 0.1)), Point(2, 0, -7)) *
163  SE3Type(SO3Type::exp(Point(kPi, 0, 0)), Point(0, 0, 0)) *
164  SE3Type(SO3Type::exp(Point(-0.3, -0.5, -0.1)), Point(0, 6, 0)));
165 
166  std::vector<Point> point_vec;
167  point_vec.emplace_back(1.012, 2.73, -1.4);
168  point_vec.emplace_back(9.2, -7.3, -4.4);
169  point_vec.emplace_back(2.5, 0.1, 9.1);
170  point_vec.emplace_back(12.3, 1.9, 3.8);
171  point_vec.emplace_back(-3.21, 3.42, 2.3);
172  point_vec.emplace_back(-8.0, 6.1, -1.1);
173  point_vec.emplace_back(0.0, 2.5, 5.9);
174  point_vec.emplace_back(7.1, 7.8, -14);
175  point_vec.emplace_back(5.8, 9.2, 0.0);
176 
177  for (size_t i = 0; i < se3_vec.size(); ++i) {
178  const int other_index = (i + 3) % se3_vec.size();
179  bool const passed = test(se3_vec[i], se3_vec[other_index], point_vec[i],
180  point_vec[other_index]);
181  if (!passed) {
182  std::cerr << "failed!" << std::endl << std::endl;
183  exit(-1);
184  }
185  }
186 
187  Eigen::Matrix<ceres::Jet<double, 28>, 4, 4> mat;
188  mat.setIdentity();
189  std::cout << CreateSE3FromMatrix(mat) << std::endl;
190 
191  return 0;
192 }
test
bool test(Sophus::SE3d const &T_w_targ, Sophus::SE3d const &T_w_init, Sophus::SE3d::Point const &point_a_init, Sophus::SE3d::Point const &point_b)
Definition: test_ceres_se3.cpp:84
Eigen
Definition: rxso2.hpp:16
TestSE3CostFunctor
Definition: test_ceres_se3.cpp:30
TestPointCostFunctor::operator()
bool operator()(T const *const sT_wa, T const *const spoint_b, T *sResiduals) const
Definition: test_ceres_se3.cpp:59
CreateSE3FromMatrix
bool CreateSE3FromMatrix(const Eigen::Matrix< Scalar, 4, 4 > &mat)
Definition: test_ceres_se3.cpp:132
Sophus::SO3
SO3 using default storage; derived from SO3Base.
Definition: so3.hpp:19
Sophus::SE3::data
SOPHUS_FUNC Scalar * data()
Definition: se3.hpp:513
EIGEN_DEVICE_FUNC
#define EIGEN_DEVICE_FUNC
Definition: common.hpp:34
TestPointCostFunctor
Definition: test_ceres_se3.cpp:53
Sophus::SE3::DoF
static constexpr int DoF
Definition: se3.hpp:434
TestPointCostFunctor::point_a
Eigen::Vector3d point_a
Definition: test_ceres_se3.cpp:81
main
int main(int, char **)
Definition: test_ceres_se3.cpp:138
TestPointCostFunctor::T_aw
Sophus::SE3d T_aw
Definition: test_ceres_se3.cpp:80
Sophus::test::LocalParameterizationSE3
Definition: local_parameterization_se3.hpp:10
TestSE3CostFunctor::operator()
bool operator()(T const *const sT_wa, T *sResiduals) const
Definition: test_ceres_se3.cpp:35
Sophus::Vector3d
Vector3< double > Vector3d
Definition: types.hpp:23
Sophus::Constants::epsilon
static SOPHUS_FUNC Scalar epsilon()
Definition: common.hpp:147
Sophus::SE3::translation
SOPHUS_FUNC TranslationMember & translation()
Definition: se3.hpp:535
Eigen::internal::cast_impl< ceres::Jet< T, N >, NewType >::run
static EIGEN_DEVICE_FUNC NewType run(ceres::Jet< T, N > const &x)
Definition: test_ceres_se3.cpp:22
Sophus::SE3
SE3 using default storage; derived from SE3Base.
Definition: se3.hpp:11
TestPointCostFunctor::TestPointCostFunctor
EIGEN_MAKE_ALIGNED_OPERATOR_NEW TestPointCostFunctor(Sophus::SE3d T_aw, Eigen::Vector3d point_a)
Definition: test_ceres_se3.cpp:55
se3.hpp
local_parameterization_se3.hpp
Sophus::Constants::pi
static SOPHUS_FUNC Scalar pi()
Definition: common.hpp:154
TestSE3CostFunctor::TestSE3CostFunctor
EIGEN_MAKE_ALIGNED_OPERATOR_NEW TestSE3CostFunctor(Sophus::SE3d T_aw)
Definition: test_ceres_se3.cpp:32
TestSE3CostFunctor::T_aw
Sophus::SE3d T_aw
Definition: test_ceres_se3.cpp:50
Sophus::SE3::Point
typename Base::Point Point
Definition: se3.hpp:439
Sophus::SE3::num_parameters
static constexpr int num_parameters
Definition: se3.hpp:435


sophus
Author(s): Hauke Strasdat
autogenerated on Wed Mar 2 2022 01:01:48