13 #include <boost/test/unit_test.hpp>
14 #include <boost/utility/binary.hpp>
16 BOOST_AUTO_TEST_SUITE(BOOST_TEST_MODULE)
18 template<
typename Vector3Like>
19 Eigen::Matrix<typename Vector3Like::Scalar, 3, 3, 0>
20 computeV(
const Eigen::MatrixBase<Vector3Like> & v3)
23 typedef Eigen::Matrix<Scalar, 3, 3, 0> ReturnType;
24 typedef ReturnType Matrix3;
27 const Scalar t = pinocchio::math::sqrt(
t2);
50 template<
typename Vector3Like>
51 Eigen::Matrix<typename Vector3Like::Scalar, 3, 3, 0>
55 typedef Eigen::Matrix<Scalar, 3, 3, 0> ReturnType;
56 typedef ReturnType Matrix3;
59 const Scalar t = pinocchio::math::sqrt(
t2);
84 using CppAD::NearEqual;
87 typedef AD<Scalar> ADScalar;
96 M.translation().setZero();
103 typedef Eigen::Matrix<Scalar, Eigen::Dynamic, Eigen::Dynamic> Matrix;
104 typedef Eigen::Matrix<ADScalar, Eigen::Dynamic, 1> ADVector;
106 ADMotion ad_v(
v.cast<ADScalar>());
107 ADSE3 ad_M(
M.cast<ADScalar>());
108 ADSE3::Matrix3 rot = ad_M.rotation();
114 CppAD::Independent(
X);
123 CppAD::ADFun<Scalar> map(
X,
Y);
126 Eigen::Map<Motion::Vector3>(
x.data()).setZero();
128 CPPAD_TESTVECTOR(
Scalar) nu_next_vec = map.Forward(0,
x);
129 Motion::Vector3 nu_next(Eigen::Map<Motion::Vector3>(nu_next_vec.data()));
133 CPPAD_TESTVECTOR(
Scalar)
jac = map.Jacobian(
x);
135 Matrix
jacobian = Eigen::Map<PINOCCHIO_EIGEN_PLAIN_ROW_MAJOR_TYPE(Matrix)>(
jac.data(), 3, 3);
137 BOOST_CHECK(rot_next_from_map.isApprox(rot_next));
144 using CppAD::NearEqual;
147 typedef AD<Scalar> ADScalar;
155 SE3 M(SE3::Random());
163 BOOST_CHECK((
V * Vinv).isIdentity());
169 typedef Eigen::Matrix<Scalar, Eigen::Dynamic, Eigen::Dynamic> Matrix;
170 typedef Eigen::Matrix<ADScalar, Eigen::Dynamic, 1> ADVector;
172 ADMotion ad_v(
v.cast<ADScalar>());
173 ADSE3 ad_M(
M.cast<ADScalar>());
179 CppAD::Independent(
X);
180 ADMotion::Vector6 X_ =
X;
186 Y.head<3>() = ad_M_next.translation();
188 ad_M.translation() + ad_M.rotation() *
computeV(ad_v_ref.angular()) * ad_v_ref.linear();
190 CppAD::ADFun<Scalar> map(
X,
Y);
192 CPPAD_TESTVECTOR(
Scalar)
x((
size_t)
X.size());
193 Eigen::Map<Motion::Vector6>(
x.data()).setZero();
195 CPPAD_TESTVECTOR(
Scalar) translation_vec = map.Forward(0,
x);
196 Motion::Vector3 translation1(Eigen::Map<Motion::Vector3>(translation_vec.data()));
197 Motion::Vector3 translation2(Eigen::Map<Motion::Vector3>(translation_vec.data() + 3));
198 BOOST_CHECK(translation1.isApprox(M_next.translation()));
199 BOOST_CHECK(translation2.isApprox(M_next.translation()));
201 CPPAD_TESTVECTOR(
Scalar)
jac = map.Jacobian(
x);
204 Eigen::Map<PINOCCHIO_EIGEN_PLAIN_ROW_MAJOR_TYPE(Matrix)>(
jac.data(),
Y.size(),
X.size());
206 BOOST_CHECK(
jacobian.topLeftCorner(3, 3).isApprox(
M.rotation()));
212 using CppAD::NearEqual;
215 typedef AD<Scalar> ADScalar;
223 SE3 M(SE3::Random());
228 typedef Eigen::Matrix<Scalar, Eigen::Dynamic, Eigen::Dynamic> Matrix;
229 typedef Eigen::Matrix<ADScalar, Eigen::Dynamic, 1> ADVector;
231 ADMotion ad_v(
v.cast<ADScalar>());
232 ADSE3 ad_M(
M.cast<ADScalar>());
236 X.segment<3>(Motion::LINEAR) = ad_v.linear();
237 X.segment<3>(Motion::ANGULAR) = ad_v.angular();
239 CppAD::Independent(
X);
240 ADMotion::Vector6 X_ =
X;
247 Y.segment<3>(Motion::LINEAR) = ad_log_M_next.linear();
248 Y.segment<3>(Motion::ANGULAR) = ad_log_M_next.angular();
250 CppAD::ADFun<Scalar> map(
X,
Y);
253 Eigen::Map<Motion::Vector6>(
x.data()).setZero();
255 CPPAD_TESTVECTOR(
Scalar) nu_next_vec = map.Forward(0,
x);
256 Motion nu_next(Eigen::Map<Motion::Vector6>(nu_next_vec.data()));
258 CPPAD_TESTVECTOR(
Scalar)
jac = map.Jacobian(
x);
260 Matrix
jacobian = Eigen::Map<PINOCCHIO_EIGEN_PLAIN_ROW_MAJOR_TYPE(Matrix)>(
jac.data(), 6, 6);
264 typedef Eigen::Matrix<Scalar, 6, 6> Matrix6;
265 Matrix6 Jlog6_fd(Matrix6::Zero());
269 for (
int k = 0; k < 6; ++k)
271 dv.toVector()[k] =
eps;
273 v_plus =
log6(M_plus);
274 Jlog6_fd.col(k) = (v_plus -
v0).toVector() /
eps;
275 dv.toVector()[k] = 0;
278 SE3::Matrix6 Jlog6_analytic;
281 BOOST_CHECK(
Jlog6.isApprox(Jlog6_analytic));
282 BOOST_CHECK(Jlog6_fd.isApprox(
Jlog6, pinocchio::math::sqrt(
eps)));
285 BOOST_AUTO_TEST_SUITE_END()