Drake
expmap.h
Go to the documentation of this file.
1 
4 #pragma once
5 
6 #include <cmath>
7 
8 #include <Eigen/Dense>
9 
11 #include "drake/math/autodiff.h"
12 
13 namespace drake {
14 namespace math {
15 
16 namespace internal {
17 template <typename Derived>
18 Eigen::Matrix<typename Derived::Scalar, 4, 1> expmap2quatNonDegenerate(
19  const Eigen::MatrixBase<Derived>& v,
20  typename Derived::Scalar& theta_squared) {
21  using namespace std;
22  typedef typename Derived::Scalar Scalar;
23  static_assert(
24  Derived::RowsAtCompileTime == 3 && Derived::ColsAtCompileTime == 1,
25  "Wrong size.");
26 
27  Eigen::Matrix<Scalar, 4, 1> q;
28 
29  Scalar theta = sqrt(theta_squared);
30  Scalar arg = theta / Scalar(2);
31  q(0) = cos(arg);
32  q.template bottomRows<3>() = v;
33  q.template bottomRows<3>() *= sin(arg) / theta;
34 
35  return q;
36 }
37 
38 template <typename Derived>
39 Eigen::Matrix<typename Derived::Scalar, 4, 1> expmap2quatDegenerate(
40  const Eigen::MatrixBase<Derived>& v,
41  typename Derived::Scalar& theta_squared) {
42  typedef typename Derived::Scalar Scalar;
43  static_assert(
44  Derived::RowsAtCompileTime == 3 && Derived::ColsAtCompileTime == 1,
45  "Wrong size.");
46 
47  Eigen::Matrix<Scalar, 4, 1> q;
48 
49  q(0) = -theta_squared / 8.0 + 1.0;
50  q.template bottomRows<3>() = v;
51  q.template bottomRows<3>() *=
52  (theta_squared * 8.0E1 - 1.92E3) * (-2.604166666666667E-4);
53 
54  return q;
55 }
56 } // namespace internal
57 
58 template <typename Derived>
59 Eigen::Matrix<typename Derived::Scalar, 4, 1> expmap2quat(
60  const Eigen::MatrixBase<Derived>& v) {
61  EIGEN_STATIC_ASSERT_VECTOR_SPECIFIC_SIZE(Eigen::MatrixBase<Derived>, 3);
62  typedef typename Derived::Scalar Scalar;
63  Scalar theta_squared = v.squaredNorm();
64  if (theta_squared < pow(Eigen::NumTraits<Scalar>::epsilon(), 0.5)) {
65  return internal::expmap2quatDegenerate(v, theta_squared);
66  } else {
67  return internal::expmap2quatNonDegenerate(v, theta_squared);
68  }
69 }
70 
71 template <typename DerivedQ>
72 Eigen::Matrix<typename DerivedQ::Scalar, 3, 1> quat2expmap(
73  const Eigen::MatrixBase<DerivedQ>& q) {
74  typedef typename DerivedQ::Scalar Scalar;
75  static_assert(
76  DerivedQ::RowsAtCompileTime == 4 && DerivedQ::ColsAtCompileTime == 1,
77  "Wrong size.");
78 
79  Scalar t = sqrt(Scalar(1) - q(0) * q(0));
80  bool is_degenerate = (t * t < Eigen::NumTraits<Scalar>::epsilon());
81  Scalar s(2);
82  if (!is_degenerate) s *= acos(q(0)) / t;
83  return s * q.template tail<3>();
84 }
85 
86 template <typename Derived1, typename Derived2>
87 Eigen::Matrix<typename Derived1::Scalar, 3, 1> closestExpmap(
88  const Eigen::MatrixBase<Derived1>& expmap1,
89  const Eigen::MatrixBase<Derived2>& expmap2) {
90  using namespace std; // required for ADL of floor() and round().
91  static_assert(
92  Derived1::RowsAtCompileTime == 3 && Derived1::ColsAtCompileTime == 1,
93  "Wrong size.");
94  static_assert(
95  Derived2::RowsAtCompileTime == 3 && Derived2::ColsAtCompileTime == 1,
96  "Wrong size.");
97  static_assert(
98  std::is_same<typename Derived1::Scalar, typename Derived2::Scalar>::value,
99  "Scalar types don't match.");
100  typedef typename Derived1::Scalar Scalar;
101  typedef typename Eigen::NumTraits<Scalar>::Real Real;
102 
103  Real expmap1_norm = expmap1.norm();
104  Real expmap2_norm = expmap2.norm();
105  Eigen::Matrix<Scalar, 3, 1> ret;
106  if (expmap2_norm < Eigen::NumTraits<Scalar>::epsilon()) {
107  if (expmap1_norm > Eigen::NumTraits<Scalar>::epsilon()) {
108  auto expmap1_axis = (expmap1 / expmap1_norm).eval();
109  auto expmap1_round = round(expmap1_norm / (2 * M_PI));
110  return expmap1_axis * expmap1_round * 2 * M_PI;
111  } else {
112  return expmap2;
113  }
114  } else {
115  auto expmap2_axis = (expmap2 / expmap2_norm).eval();
116  auto expmap2_closest_k =
117  ((expmap2_axis.transpose() * expmap1).value() - expmap2_norm) /
118  (2 * M_PI);
119  auto expmap2_closest_k1 = floor(expmap2_closest_k);
120  auto expmap2_closest_k2 = expmap2_closest_k1 + 1.0;
121  auto expmap2_closest1 =
122  (expmap2 + 2 * expmap2_closest_k1 * M_PI * expmap2_axis).eval();
123  auto expmap2_closest2 =
124  (expmap2 + 2 * expmap2_closest_k2 * M_PI * expmap2_axis).eval();
125  if ((expmap2_closest1 - expmap1).norm() <
126  (expmap2_closest2 - expmap1).norm()) {
127  return expmap2_closest1;
128  } else {
129  return expmap2_closest2;
130  }
131  }
132 }
133 
134 template <typename DerivedQ, typename DerivedE>
135 void quat2expmapSequence(const Eigen::MatrixBase<DerivedQ>& quat,
136  const Eigen::MatrixBase<DerivedQ>& quat_dot,
137  Eigen::MatrixBase<DerivedE>& expmap,
138  Eigen::MatrixBase<DerivedE>& expmap_dot) {
139  static_assert(DerivedQ::RowsAtCompileTime == 4, "Wrong size.");
140  static_assert(DerivedE::RowsAtCompileTime == 3, "Wrong size.");
141  static_assert(
142  std::is_same<typename DerivedQ::Scalar, typename DerivedE::Scalar>::value,
143  "Scalar types don't match.");
144  typedef typename DerivedQ::Scalar Scalar;
145 
146  DRAKE_ASSERT(quat.cols() == quat_dot.cols() &&
147  "number of columns of quat doesn't match quat_dot");
148  Eigen::Index N = quat.cols();
149 
150  typedef Eigen::AutoDiffScalar<Eigen::Matrix<Scalar, 1, 1>> ADScalar;
151  auto quat_autodiff = quat.template cast<ADScalar>().eval();
152  for (int i = 0; i < quat.size(); i++) {
153  quat_autodiff(i).derivatives()(0) = quat_dot(i);
154  }
155 
156  expmap.resize(3, N);
157  expmap_dot.resize(3, N);
158  Eigen::Matrix<ADScalar, 3, 1> expmap_autodiff_previous;
159  for (int i = 0; i < N; i++) {
160  auto expmap_autodiff = quat2expmap(quat_autodiff.col(i));
161  if (i >= 1) {
162  expmap_autodiff =
163  closestExpmap(expmap_autodiff_previous, expmap_autodiff);
164  }
165  expmap.col(i) = autoDiffToValueMatrix(expmap_autodiff);
166  expmap_dot.col(i) = autoDiffToGradientMatrix(expmap_autodiff);
167  expmap_autodiff_previous = expmap_autodiff;
168  }
169 }
170 
171 } // namespace math
172 } // namespace drake
AutoDiffToValueMatrix< Derived >::type autoDiffToValueMatrix(const Eigen::MatrixBase< Derived > &auto_diff_matrix)
Definition: autodiff.h:40
Definition: constants.h:3
Eigen::Matrix< typename Derived::Scalar, 4, 1 > expmap2quatNonDegenerate(const Eigen::MatrixBase< Derived > &v, typename Derived::Scalar &theta_squared)
Definition: expmap.h:18
AutoDiffToGradientMatrix< Derived >::type autoDiffToGradientMatrix(const Eigen::MatrixBase< Derived > &auto_diff_matrix, int num_variables=Eigen::Dynamic)
Definition: autodiff.h:61
STL namespace.
FunctionalForm cos(FunctionalForm const &x)
Definition: functional_form.cc:188
double round(const Eigen::AutoDiffScalar< DerType > &x)
Overloads round to mimic std::round from <cmath>.
Definition: autodiff.h:17
FunctionalForm sqrt(FunctionalForm const &x)
Definition: functional_form.cc:208
Eigen::Matrix< typename Derived1::Scalar, 3, 1 > closestExpmap(const Eigen::MatrixBase< Derived1 > &expmap1, const Eigen::MatrixBase< Derived2 > &expmap2)
Definition: expmap.h:87
Eigen::Matrix< typename Derived::Scalar, 4, 1 > expmap2quatDegenerate(const Eigen::MatrixBase< Derived > &v, typename Derived::Scalar &theta_squared)
Definition: expmap.h:39
static double * t
Definition: inverseKinSnoptBackend.cpp:62
double floor(const Eigen::AutoDiffScalar< DerType > &x)
Overloads floor to mimic std::floor from <cmath>.
Definition: autodiff.h:25
#define DRAKE_ASSERT(condition)
DRAKE_ASSERT(condition) is similar to the built-in assert(condition) from the C++ system header <cas...
Definition: drake_assert.h:35
Utilities for arithmetic on AutoDiffScalar.
Provides Drake&#39;s assertion implementation.
Eigen::Matrix< typename DerivedQ::Scalar, 3, 1 > quat2expmap(const Eigen::MatrixBase< DerivedQ > &q)
Definition: expmap.h:72
Eigen::Matrix< typename Derived::Scalar, 4, 1 > expmap2quat(const Eigen::MatrixBase< Derived > &v)
Definition: expmap.h:59
void quat2expmapSequence(const Eigen::MatrixBase< DerivedQ > &quat, const Eigen::MatrixBase< DerivedQ > &quat_dot, Eigen::MatrixBase< DerivedE > &expmap, Eigen::MatrixBase< DerivedE > &expmap_dot)
Definition: expmap.h:135
FunctionalForm sin(FunctionalForm const &x)
Definition: functional_form.cc:203