1 #include <ceres/ceres.h>
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);
31 EIGEN_MAKE_ALIGNED_OPERATOR_NEW
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);
41 residuals = (
T_aw * T_wa).log();
44 residuals = (T_wa *
T_aw).log();
46 residuals = (T_wa *
T_aw.cast<T>()).log();
54 EIGEN_MAKE_ALIGNED_OPERATOR_NEW
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);
67 Vector3T point_b_prime =
T_aw * point_b;
69 point_b_prime =
T_aw.cast<T>() * point_b;
72 Vector3T point_a_prime = T_wa *
point_a;
74 point_a_prime = T_wa *
point_a.cast<T>();
76 residuals = point_b_prime - point_a_prime;
87 static constexpr
int kNumPointParameters = 3;
94 ceres::Problem problem;
102 ceres::CostFunction* cost_function1 =
106 problem.AddResidualBlock(cost_function1, NULL, T_wr.
data());
107 ceres::CostFunction* cost_function2 =
110 kNumPointParameters>(
112 problem.AddResidualBlock(cost_function2, NULL, T_wr.
data(), point_a.data());
115 ceres::Solver::Options options;
118 options.linear_solver_type = ceres::DENSE_QR;
121 ceres::Solver::Summary summary;
122 Solve(options, &problem, &summary);
123 std::cout << summary.BriefReport() << std::endl;
126 double const mse = (T_w_targ.inverse() * T_wr).log().squaredNorm();
131 template <
typename Scalar>
141 using Point = SE3Type::Point;
144 std::vector<SE3Type> se3_vec;
146 SE3Type(SO3Type::exp(Point(0.2, 0.5, 0.0)), Point(0, 0, 0)));
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)));
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)));
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)));
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)));
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)));
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);
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]);
182 std::cerr <<
"failed!" << std::endl << std::endl;
187 Eigen::Matrix<ceres::Jet<double, 28>, 4, 4> mat;