def rpy(self, unit='rad', order='zyx'): """ SO(3) or SE(3) as roll-pitch-yaw angles :param order: angle sequence order, default to 'zyx' :type order: str :param unit: angular units: 'rad' [default], or 'deg' :type unit: str :return: 3-vector of roll-pitch-yaw angles :rtype: numpy.ndarray, shape=(3,) ``x.rpy`` is the roll-pitch-yaw angle representation of the rotation. The angles are a 3-vector :math:`(r, p, y)` which correspond to successive rotations about the axes specified by ``order``: - ``'zyx'`` [default], rotate by yaw about the z-axis, then by pitch about the new y-axis, then by roll about the new x-axis. Convention for a mobile robot with x-axis forward and y-axis sideways. - ``'xyz'``, rotate by yaw about the x-axis, then by pitch about the new y-axis, then by roll about the new z-axis. Convention for a robot gripper with z-axis forward and y-axis between the gripper fingers. - ``'yxz'``, rotate by yaw about the y-axis, then by pitch about the new x-axis, then by roll about the new z-axis. Convention for a camera with z-axis parallel to the optic axis and x-axis parallel to the pixel rows. If `len(x)` is: - 1, return an ndarray with shape=(3,) - N>1, return ndarray with shape=(N,3) :seealso: :func:`~spatialmath.pose3d.SE3.RPY`, :func:`~spatialmath.base.transforms3d.tr2rpy` :SymPy: not supported """ if len(self) == 1: return base.tr2rpy(self.A, unit=unit, order=order) else: return np.array( [base.tr2rpy(x, unit=unit, order=order) for x in self.A]).T
def rpy(self, unit='deg', order='zyx'): """ Extract roll-pitch-yaw angles from SO(3) rotation :param self: rotation or pose :type angles: SO3, SE3 instance :param unit: angular units: 'rad' [default], or 'deg' :type unit: str :return: 3-vector of roll-pitch-yaw angles :rtype: numpy.ndarray, shape=(3,) ``R.rpy`` is the roll-pitch-yaw angle representation of the rotation. The angles are a 3-vector :math:`(r, p, y)` which correspond to successive rotations about the axes specified by ``order``: - 'zyx' [default], rotate by yaw about the z-axis, then by pitch about the new y-axis, then by roll about the new x-axis. Convention for a mobile robot with x-axis forward and y-axis sideways. - 'xyz', rotate by yaw about the x-axis, then by pitch about the new y-axis, then by roll about the new z-axis. Covention for a robot gripper with z-axis forward and y-axis between the gripper fingers. - 'yxz', rotate by yaw about the y-axis, then by pitch about the new x-axis, then by roll about the new z-axis. Convention for a camera with z-axis parallel to the optic axis and x-axis parallel to the pixel rows. ``R.rpy`` returns an: - ndarray with shape=(3,), if len(R) == 1 - ndarray with shape=(N,3), if len(R) = N > 1 :seealso: :func:`~spatialmath.pose3d.SE3.RPY`, ::func:`spatialmath.base.transforms3d.tr2rpy` """ if len(self) == 1: return tr.tr2rpy(self.A, unit=unit) else: return np.array([tr.tr2rpy(x, unit=unit) for x in self.A]).T
def rpy(self, unit='rad', order='zyx'): return tr.tr2rpy(self.R, unit=unit, order=order)