5 #include "pinocchio/autodiff/cppad.hpp" 7 #include "pinocchio/spatial/se3.hpp" 8 #include "pinocchio/spatial/motion.hpp" 9 #include "pinocchio/spatial/explog.hpp" 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>
23 typedef Eigen::Matrix<Scalar,3,3,0> ReturnType;
24 typedef ReturnType Matrix3;
26 Scalar t2 = v3.squaredNorm();
27 const Scalar
t = pinocchio::math::sqrt(t2);
28 Scalar alpha, beta, zeta;
41 zeta = (1 - alpha)/(t2);
45 = alpha * Matrix3::Identity()
47 + zeta * v3 * v3.transpose();
52 template<
typename Vector3Like>
53 Eigen::Matrix<typename Vector3Like::Scalar,3,3,0>
57 typedef Eigen::Matrix<Scalar,3,3,0> ReturnType;
58 typedef ReturnType Matrix3;
60 Scalar t2 = v3.squaredNorm();
61 const Scalar
t = pinocchio::math::sqrt(t2);
77 = alpha * Matrix3::Identity()
79 + beta * v3 * v3.transpose();
87 using CppAD::NearEqual;
90 typedef AD<Scalar> ADScalar;
97 Motion
v(Motion::Zero());
98 SE3
M(SE3::Random()); M.translation().setZero();
105 typedef Eigen::Matrix<Scalar,Eigen::Dynamic,Eigen::Dynamic> Matrix;
106 typedef Eigen::Matrix<ADScalar,Eigen::Dynamic,1> ADVector;
108 ADMotion ad_v(v.cast<ADScalar>());
109 ADSE3 ad_M(M.cast<ADScalar>());
110 ADSE3::Matrix3 rot = ad_M.rotation();
116 CppAD::Independent(X);
117 ADMotion::Vector3 X_ = X;
125 CppAD::ADFun<Scalar> map(X,Y);
127 CPPAD_TESTVECTOR(Scalar)
x(3);
128 Eigen::Map<Motion::Vector3>(
x.data()).setZero();
130 CPPAD_TESTVECTOR(Scalar) nu_next_vec = map.Forward(0,
x);
131 Motion::Vector3 nu_next(Eigen::Map<Motion::Vector3>(nu_next_vec.data()));
135 CPPAD_TESTVECTOR(Scalar) jac = map.Jacobian(
x);
137 Matrix jacobian = Eigen::Map<PINOCCHIO_EIGEN_PLAIN_ROW_MAJOR_TYPE(Matrix)>(jac.data(),3,3);
139 BOOST_CHECK(rot_next_from_map.isApprox(rot_next));
140 BOOST_CHECK(jacobian.isApprox(Jlog3));
146 using CppAD::NearEqual;
149 typedef AD<Scalar> ADScalar;
156 Motion
v(Motion::Zero());
157 SE3
M(SE3::Random());
160 Motion::Vector3 v3_test; v3_test.setRandom();
164 BOOST_CHECK((V*Vinv).isIdentity());
170 typedef Eigen::Matrix<Scalar,Eigen::Dynamic,Eigen::Dynamic> Matrix;
171 typedef Eigen::Matrix<ADScalar,Eigen::Dynamic,1> ADVector;
173 ADMotion ad_v(v.cast<ADScalar>());
174 ADSE3 ad_M(M.cast<ADScalar>());
180 CppAD::Independent(X);
181 ADMotion::Vector6 X_ = X;
187 Y.head<3>() = ad_M_next.translation();
188 Y.tail<3>() = 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);
203 Matrix jacobian = Eigen::Map<PINOCCHIO_EIGEN_PLAIN_ROW_MAJOR_TYPE(Matrix)>(jac.data(),Y.size(),X.size());
205 BOOST_CHECK(jacobian.topLeftCorner(3,3).isApprox(M.rotation()));
213 using CppAD::NearEqual;
216 typedef AD<Scalar> ADScalar;
223 Motion
v(Motion::Zero());
224 SE3
M(SE3::Random());
229 typedef Eigen::Matrix<Scalar,Eigen::Dynamic,Eigen::Dynamic> Matrix;
230 typedef Eigen::Matrix<ADScalar,Eigen::Dynamic,1> ADVector;
232 ADMotion ad_v(v.cast<ADScalar>());
233 ADSE3 ad_M(M.cast<ADScalar>());
237 X.segment<3>(Motion::LINEAR) = ad_v.linear();
238 X.segment<3>(Motion::ANGULAR) = ad_v.angular();
240 CppAD::Independent(X);
241 ADMotion::Vector6 X_ = X;
248 Y.segment<3>(Motion::LINEAR) = ad_log_M_next.linear();
249 Y.segment<3>(Motion::ANGULAR) = ad_log_M_next.angular();
251 CppAD::ADFun<Scalar> map(X,Y);
253 CPPAD_TESTVECTOR(Scalar)
x(6);
254 Eigen::Map<Motion::Vector6>(
x.data()).setZero();
256 CPPAD_TESTVECTOR(Scalar) nu_next_vec = map.Forward(0,
x);
257 Motion nu_next(Eigen::Map<Motion::Vector6>(nu_next_vec.data()));
259 CPPAD_TESTVECTOR(Scalar) jac = map.Jacobian(
x);
261 Matrix jacobian = Eigen::Map<PINOCCHIO_EIGEN_PLAIN_ROW_MAJOR_TYPE(Matrix)>(jac.data(),6,6);
264 Motion dv(Motion::Zero());
265 typedef Eigen::Matrix<Scalar,6,6> Matrix6;
266 Matrix6 Jlog6_fd(Matrix6::Zero());
267 Motion v_plus, v0(
log6(M));
269 const Scalar
eps = 1e-8;
270 for(
int k = 0; k < 6; ++k)
272 dv.toVector()[k] =
eps;
273 SE3 M_plus = M *
exp6(dv);
274 v_plus =
log6(M_plus);
275 Jlog6_fd.col(k) = (v_plus-v0).toVector()/
eps;
276 dv.toVector()[k] = 0;
279 SE3::Matrix6 Jlog6_analytic;
282 BOOST_CHECK(Jlog6.isApprox(Jlog6_analytic));
283 BOOST_CHECK(Jlog6_fd.isApprox(Jlog6,pinocchio::math::sqrt(eps)));
286 BOOST_AUTO_TEST_SUITE_END()
Eigen::Matrix< typename Matrix3Like::Scalar, 3, 1, PINOCCHIO_EIGEN_PLAIN_TYPE(Matrix3Like)::Options > log3(const Eigen::MatrixBase< Matrix3Like > &R, typename Matrix3Like::Scalar &theta)
Same as log3.
Eigen::Matrix< typename Vector3Like::Scalar, 3, 3, 0 > computeVinv(const Eigen::MatrixBase< Vector3Like > &v3)
void Jlog3(const Scalar &theta, const Eigen::MatrixBase< Vector3Like > &log, const Eigen::MatrixBase< Matrix3Like > &Jlog)
Derivative of log3.
Eigen::Matrix< typename Vector3Like::Scalar, 3, 3, 0 > computeV(const Eigen::MatrixBase< Vector3Like > &v3)
void Jlog6(const SE3Tpl< Scalar, Options > &M, const Eigen::MatrixBase< Matrix6Like > &Jlog)
Derivative of log6 where and .
MotionTpl< Scalar, Options > log6(const SE3Tpl< Scalar, Options > &M)
Log: SE3 -> se3.
void Jlog3(const Eigen::QuaternionBase< QuaternionLike > &quat, const Eigen::MatrixBase< Matrix3Like > &Jlog)
Computes the Jacobian of log3 operator for a unit quaternion.
Eigen::Matrix< typename Vector3Like::Scalar, 3, 3, PINOCCHIO_EIGEN_PLAIN_TYPE(Vector3Like)::Options > exp3(const Eigen::MatrixBase< Vector3Like > &v)
Exp: so3 -> SO3.
ConstLinearType linear() const
MotionTpl< double, 0 > Motion
void SINCOS(const S1 &a, S2 *sa, S3 *ca)
Computes sin/cos values of a given input scalar.
BOOST_AUTO_TEST_CASE(test_log3)
void skew(const Eigen::MatrixBase< Vector3 > &v, const Eigen::MatrixBase< Matrix3 > &M)
Computes the skew representation of a given 3d vector, i.e. the antisymmetric matrix representation o...
ConstAngularType angular() const
SE3Tpl< typename MotionDerived::Scalar, PINOCCHIO_EIGEN_PLAIN_TYPE(typename MotionDerived::Vector3)::Options > exp6(const MotionDense< MotionDerived > &nu)
Exp: se3 -> SE3.