5 from numpy.linalg
import inv
6 from random
import random
8 from eigenpy
import AngleAxis
9 import pinocchio
as pin
11 from pinocchio.rpy import matrixToRpy, rpyToMatrix, rotate, computeRpyJacobian, computeRpyJacobianInverse, computeRpyJacobianTimeDerivative
13 from test_case
import PinocchioTestCase
as TestCase
18 m = np.array(list(range(9)))
19 self.assertEqual(
npToTuple(m), tuple(range(9)))
20 self.assertEqual(
npToTuple(m.T), tuple(range(9)))
21 self.assertEqual(
npToTuple(np.reshape(m, (3, 3))), ((0, 1, 2), (3, 4, 5), (6, 7, 8)))
24 self.assertApprox(
rotate(
'x', pi / 2), np.array([[1., 0., 0.],[0., 0., -1.],[0., 1., 0.]]))
28 rpy = np.array(list(range(3))) * pi / 2
37 self.assertTrue(
False)
44 self.assertTrue(
False)
54 Raa = AngleAxis(y, np.array([0., 0., 1.])).matrix() \
55 .dot(AngleAxis(p, np.array([0., 1., 0.])).matrix()) \
56 .dot(AngleAxis(r, np.array([1., 0., 0.])).matrix())
58 self.assertApprox(R, Raa)
60 v = np.array([r, p, y])
64 self.assertApprox(Rv, Raa)
65 self.assertApprox(Rv, R)
71 quat = pin.Quaternion(np.random.rand(4,1)).normalized()
72 R = quat.toRotationMatrix()
77 self.assertApprox(Rprime, R)
78 self.assertTrue(-pi <= v[0]
and v[0] <= pi)
79 self.assertTrue(-pi/2 <= v[1]
and v[1] <= pi/2)
80 self.assertTrue(-pi <= v[2]
and v[2] <= pi)
85 Rp = np.array([[ 0.0, 0.0, 1.0],
92 R = AngleAxis(y, np.array([0., 0., 1.])).matrix() \
94 .dot(AngleAxis(r, np.array([1., 0., 0.])).matrix())
99 self.assertApprox(Rprime, R)
100 self.assertTrue(-pi <= v[0]
and v[0] <= pi)
101 self.assertTrue(-pi/2 <= v[1]
and v[1] <= pi/2)
102 self.assertTrue(-pi <= v[2]
and v[2] <= pi)
105 Rp = np.array([[0.0, 0.0, -1.0],
112 R = AngleAxis(y, np.array([0., 0., 1.])).matrix() \
114 .dot(AngleAxis(r, np.array([1., 0., 0.])).matrix())
119 self.assertApprox(Rprime, R)
120 self.assertTrue(-pi <= v[0]
and v[0] <= pi)
121 self.assertTrue(-pi/2 <= v[1]
and v[1] <= pi/2)
122 self.assertTrue(-pi <= v[2]
and v[2] <= pi)
130 self.assertTrue((j0 == np.eye(3)).all())
132 self.assertTrue((jL == np.eye(3)).all())
134 self.assertTrue((jW == np.eye(3)).all())
136 self.assertTrue((jA == np.eye(3)).all())
142 rpy = np.array([r, p, y])
148 self.assertTrue((j0 == jL).all())
149 self.assertTrue((jW == jA).all())
150 self.assertApprox(jW, R.dot(jL))
153 rpydot = np.random.rand(3)
160 Rdot = dRdr * rpydot[0] + dRdp * rpydot[1] + dRdy * rpydot[2]
162 omegaL = jL.dot(rpydot)
163 self.assertTrue(np.allclose(Rdot, R.dot(pin.skew(omegaL)), atol=tol))
165 omegaW = jW.dot(rpydot)
166 self.assertTrue(np.allclose(Rdot, pin.skew(omegaW).dot(R), atol=tol))
174 rpy = np.array([r, p, y])
178 self.assertApprox(j0inv, inv(j0))
182 self.assertApprox(jLinv, inv(jL))
186 self.assertApprox(jWinv, inv(jW))
190 self.assertApprox(jAinv, inv(jA))
197 rpy = np.array([r, p, y])
200 self.assertTrue((dj0 == np.zeros((3,3))).all())
202 self.assertTrue((djL == np.zeros((3,3))).all())
204 self.assertTrue((djW == np.zeros((3,3))).all())
206 self.assertTrue((djA == np.zeros((3,3))).all())
209 rpydot = np.random.rand(3)
214 self.assertTrue((dj0 == djL).all())
215 self.assertTrue((djW == djA).all())
220 omegaL = jL.dot(rpydot)
221 omegaW = jW.dot(rpydot)
222 self.assertApprox(omegaW, R.dot(omegaL))
223 self.assertApprox(djW, pin.skew(omegaW).dot(R).dot(jL) + R.dot(djL))
224 self.assertApprox(djW, R.dot(pin.skew(omegaL)).dot(jL) + R.dot(djL))
226 if __name__ ==
'__main__':
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.
def test_computeRpyJacobianTimeDerivative(self)
def test_computeRpyJacobian(self)
def test_matrixToRpy(self)
Eigen::Matrix3d rotate(const std::string &axis, const double ang)
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.
def test_computeRpyJacobianInverse(self)
def test_rpyToMatrix(self)
void random(const LieGroupGenericTpl< LieGroupCollection > &lg, const Eigen::MatrixBase< Config_t > &qout)
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.
Eigen::Matrix< Scalar, 3, 3 > rpyToMatrix(const Scalar &r, const Scalar &p, const Scalar &y)
Convert from Roll, Pitch, Yaw to rotation Matrix.
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.
Roll-pitch-yaw operations.