5 #include <pinocchio/math/rpy.hpp> 6 #include <pinocchio/math/quaternion.hpp> 7 #include <pinocchio/spatial/skew.hpp> 9 #include <boost/variant.hpp> 11 #include <boost/test/unit_test.hpp> 12 #include <boost/utility/binary.hpp> 14 BOOST_AUTO_TEST_SUITE(BOOST_TEST_MODULE)
18 double r = static_cast <
double> (
rand()) / (static_cast <double> (RAND_MAX/(2*M_PI))) - M_PI;
19 double p = static_cast <
double> (
rand()) / (static_cast <double> (RAND_MAX/M_PI)) - (M_PI/2);
20 double y = static_cast <
double> (
rand()) / (static_cast <double> (RAND_MAX/(2*M_PI))) - M_PI;
24 Eigen::Matrix3d Raa = (Eigen::AngleAxisd(y, Eigen::Vector3d::UnitZ())
25 * Eigen::AngleAxisd(p, Eigen::Vector3d::UnitY())
26 * Eigen::AngleAxisd(r, Eigen::Vector3d::UnitX())
29 BOOST_CHECK(R.isApprox(Raa));
36 BOOST_CHECK(Rv.isApprox(Raa));
37 BOOST_CHECK(Rv.isApprox(R));
47 for(
int k = 0; k < n ; ++k)
49 Eigen::Quaterniond
quat;
51 const Eigen::Matrix3d
R = quat.toRotationMatrix();
56 BOOST_CHECK(Rprime.isApprox(R));
57 BOOST_CHECK(-M_PI <= v[0] && v[0] <= M_PI);
58 BOOST_CHECK(-M_PI/2 <= v[1] && v[1] <= M_PI/2);
59 BOOST_CHECK(-M_PI <= v[2] && v[2] <= M_PI);
69 for(
int k = 0; k < n2 ; ++k)
71 double r = static_cast <
double> (
rand()) / (static_cast <double> (RAND_MAX/(2*M_PI))) - M_PI;
72 double y = static_cast <
double> (
rand()) / (static_cast <double> (RAND_MAX/(2*M_PI))) - M_PI;
77 const Eigen::Matrix3d
R = Eigen::AngleAxisd(y, Eigen::Vector3d::UnitZ()).toRotationMatrix()
79 * Eigen::AngleAxisd(r, Eigen::Vector3d::UnitX()).toRotationMatrix();
84 BOOST_CHECK(Rprime.isApprox(R));
85 BOOST_CHECK(-M_PI <= v[0] && v[0] <= M_PI);
86 BOOST_CHECK(-M_PI/2 <= v[1] && v[1] <= M_PI/2);
87 BOOST_CHECK(-M_PI <= v[2] && v[2] <= M_PI);
91 for(
int k = 0; k < n2 ; ++k)
93 double r = static_cast <
double> (
rand()) / (static_cast <double> (RAND_MAX/(2*M_PI))) - M_PI;
94 double y = static_cast <
double> (
rand()) / (static_cast <double> (RAND_MAX/(2*M_PI))) - M_PI;
99 const Eigen::Matrix3d
R = Eigen::AngleAxisd(y, Eigen::Vector3d::UnitZ()).toRotationMatrix()
101 * Eigen::AngleAxisd(r, Eigen::Vector3d::UnitX()).toRotationMatrix();
106 BOOST_CHECK(Rprime.isApprox(R));
107 BOOST_CHECK(-M_PI <= v[0] && v[0] <= M_PI);
108 BOOST_CHECK(-M_PI/2 <= v[1] && v[1] <= M_PI/2);
109 BOOST_CHECK(-M_PI <= v[2] && v[2] <= M_PI);
117 Eigen::Vector3d
rpy(Eigen::Vector3d::Zero());
119 BOOST_CHECK(j0.isIdentity());
121 BOOST_CHECK(jL.isIdentity());
123 BOOST_CHECK(jW.isIdentity());
125 BOOST_CHECK(jA.isIdentity());
128 double r = static_cast <
double> (
rand()) / (static_cast <double> (RAND_MAX/(2*M_PI))) - M_PI;
129 double p = static_cast <
double> (
rand()) / (static_cast <double> (RAND_MAX/M_PI)) - (M_PI/2);
130 double y = static_cast <
double> (
rand()) / (static_cast <double> (RAND_MAX/(2*M_PI))) - M_PI;
131 rpy = Eigen::Vector3d(r, p, y);
137 BOOST_CHECK(j0 == jL);
138 BOOST_CHECK(jW == jA);
139 BOOST_CHECK(jW.isApprox(R*jL));
142 Eigen::Vector3d jL0Expected = Eigen::Vector3d::UnitX();
143 Eigen::Vector3d jL1Expected = Eigen::AngleAxisd(r, Eigen::Vector3d::UnitX()).toRotationMatrix().transpose().col(1);
144 Eigen::Vector3d jL2Expected = (Eigen::AngleAxisd(p, Eigen::Vector3d::UnitY())
145 * Eigen::AngleAxisd(r, Eigen::Vector3d::UnitX())
147 BOOST_CHECK(jL.col(0).isApprox(jL0Expected));
148 BOOST_CHECK(jL.col(1).isApprox(jL1Expected));
149 BOOST_CHECK(jL.col(2).isApprox(jL2Expected));
151 Eigen::Vector3d jW0Expected = (Eigen::AngleAxisd(y, Eigen::Vector3d::UnitZ())
152 * Eigen::AngleAxisd(p, Eigen::Vector3d::UnitY())
154 Eigen::Vector3d jW1Expected = Eigen::AngleAxisd(y, Eigen::Vector3d::UnitZ()).toRotationMatrix().col(1);
155 Eigen::Vector3d jW2Expected = Eigen::Vector3d::UnitZ();
156 BOOST_CHECK(jW.col(0).isApprox(jW0Expected));
157 BOOST_CHECK(jW.col(1).isApprox(jW1Expected));
158 BOOST_CHECK(jW.col(2).isApprox(jW2Expected));
161 Eigen::Vector3d rpydot = Eigen::Vector3d::Random();
162 double const eps = 1e-7;
163 double const tol = 1e-5;
168 Eigen::Matrix3d Rdot = dRdr * rpydot[0] + dRdp * rpydot[1] + dRdy * rpydot[2];
170 Eigen::Vector3d omegaL = jL * rpydot;
173 Eigen::Vector3d omegaW = jW * rpydot;
181 double r = static_cast <
double> (
rand()) / (static_cast <double> (RAND_MAX/(2*M_PI))) - M_PI;
182 double p = static_cast <
double> (
rand()) / (static_cast <double> (RAND_MAX/M_PI)) - (M_PI/2);
184 double y = static_cast <
double> (
rand()) / (static_cast <double> (RAND_MAX/(2*M_PI))) - M_PI;
185 Eigen::Vector3d
rpy(r, p, y);
189 BOOST_CHECK(j0inv.isApprox(j0.inverse()));
193 BOOST_CHECK(jLinv.isApprox(jL.inverse()));
197 BOOST_CHECK(jWinv.isApprox(jW.inverse()));
201 BOOST_CHECK(jAinv.isApprox(jA.inverse()));
208 double r = static_cast <
double> (
rand()) / (static_cast <double> (RAND_MAX/(2*M_PI))) - M_PI;
209 double p = static_cast <
double> (
rand()) / (static_cast <double> (RAND_MAX/M_PI)) - (M_PI/2);
210 double y = static_cast <
double> (
rand()) / (static_cast <double> (RAND_MAX/(2*M_PI))) - M_PI;
211 Eigen::Vector3d
rpy(r, p, y);
212 Eigen::Vector3d rpydot(Eigen::Vector3d::Zero());
214 BOOST_CHECK(dj0.isZero());
216 BOOST_CHECK(djL.isZero());
218 BOOST_CHECK(djW.isZero());
220 BOOST_CHECK(djA.isZero());
223 rpydot = Eigen::Vector3d::Random();
228 BOOST_CHECK(dj0 == djL);
229 BOOST_CHECK(djW == djA);
234 Eigen::Vector3d omegaL = jL * rpydot;
235 Eigen::Vector3d omegaW = jW * rpydot;
236 BOOST_CHECK(omegaW.isApprox(R*omegaL));
241 double const eps = 1e-7;
242 double const tol = 1e-5;
243 Eigen::Vector3d rpyEps = rpy;
254 Eigen::Matrix3d djLf = djLdr * rpydot[0] + djLdp * rpydot[1] + djLdy * rpydot[2];
255 BOOST_CHECK(djL.isApprox(djLf, tol));
266 Eigen::Matrix3d djWf = djWdr * rpydot[0] + djWdp * rpydot[1] + djWdy * rpydot[2];
267 BOOST_CHECK(djW.isApprox(djWf, tol));
270 BOOST_AUTO_TEST_SUITE_END()
The WORLD frame convention corresponds to the frame concident with the Universe/Inertial frame but mo...
Eigen::Matrix< typename Vector3Like::Scalar, 3, 3, PINOCCHIO_EIGEN_PLAIN_TYPE(Vector3Like)::Options > computeRpyJacobian(const Eigen::MatrixBase< Vector3Like > &rpy, const ReferenceFrame rf=LOCAL)
Compute the Jacobian of the Roll-Pitch-Yaw conversion.
Eigen::Matrix< typename Matrix3Like::Scalar, 3, 1, PINOCCHIO_EIGEN_PLAIN_TYPE(Matrix3Like)::Options > matrixToRpy(const Eigen::MatrixBase< Matrix3Like > &R)
Convert from Transformation Matrix to Roll, Pitch, Yaw.
The LOCAL frame convention corresponds to the frame directly attached to the moving part (Joint...
BOOST_AUTO_TEST_CASE(test_rpyToMatrix)
void uniformRandom(const Eigen::QuaternionBase< Derived > &q)
Uniformly random quaternion sphere.
The LOCAL_WORLD_ALIGNED frame convention corresponds to the frame centered on the moving part (Joint...
Eigen::Matrix< typename Vector3Like::Scalar, 3, 3, PINOCCHIO_EIGEN_PLAIN_TYPE(Vector3Like)::Options > computeRpyJacobianInverse(const Eigen::MatrixBase< Vector3Like > &rpy, const ReferenceFrame rf=LOCAL)
Compute the inverse Jacobian of the Roll-Pitch-Yaw conversion.
void toRotationMatrix(const Eigen::MatrixBase< Vector3 > &axis, const Scalar &cos_value, const Scalar &sin_value, const Eigen::MatrixBase< Matrix3 > &res)
Computes a rotation matrix from a vector and values of sin and cos orientations values.
Eigen::Matrix< Scalar, 3, 3 > rpyToMatrix(const Scalar &r, const Scalar &p, const Scalar &y)
Convert from Roll, Pitch, Yaw to rotation Matrix.
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...
Eigen::Matrix< typename Vector3Like0::Scalar, 3, 3, PINOCCHIO_EIGEN_PLAIN_TYPE(Vector3Like0)::Options > computeRpyJacobianTimeDerivative(const Eigen::MatrixBase< Vector3Like0 > &rpy, const Eigen::MatrixBase< Vector3Like1 > &rpydot, const ReferenceFrame rf=LOCAL)
Compute the time derivative Jacobian of the Roll-Pitch-Yaw conversion.