def RPY(cls, angles, order='zyx', unit='rad'): """ Create an SO(3) pure rotation from roll-pitch-yaw angles :param angles: 3-vector of roll-pitch-yaw angles :type angles: array_like or numpy.ndarray with shape=(N,3) :param unit: angular units: 'rad' [default], or 'deg' :type unit: str :param unit: rotation order: 'zyx' [default], 'xyz', or 'yxz' :type unit: str :return: 4x4 homogeneous transformation matrix :rtype: SE3 instance ``SE3.RPY(ANGLES)`` is an SE(3) rotation defined by a 3-vector of roll, pitch, yaw angles :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. If ``angles`` is an Nx3 matrix then the result is a sequence of rotations each defined by RPY angles correponding to the rows of angles. :seealso: :func:`~spatialmath.pose3d.SE3.rpy`, :func:`~spatialmath.pose3d.SE3.RPY`, :func:`spatialmath.base.transforms3d.rpy2r` """ if argcheck.isvector(angles, 3): return cls(tr.rpy2tr(angles, order=order, unit=unit)) else: return cls([tr.rpy2tr(a, order=order, unit=unit) for a in angles])
def RPY(cls, *angles, unit='rad', order='zyx'): r""" Create an SE(3) pure rotation from roll-pitch-yaw angles :param 𝚪: roll-pitch-yaw angles :type 𝚪: array_like or numpy.ndarray with shape=(N,3) :param unit: angular units: 'rad' [default], or 'deg' :type unit: str :param order: rotation order: 'zyx' [default], 'xyz', or 'yxz' :type order: str :return: SE(3) matrix :rtype: SE3 instance - ``SE3.RPY(𝚪)`` is an SE(3) rotation defined by a 3-vector of roll, pitch, yaw angles :math:`\Gamma=(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. This is the **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. This is the **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. This is the **convention** for a camera with z-axis parallel to the optical axis and x-axis parallel to the pixel rows. If ``𝚪`` is an Nx3 matrix then the result is a sequence of rotations each defined by RPY angles corresponding to the rows of ``𝚪``. - ``SE3.RPY(⍺, β, 𝛾)`` as above but the angles are provided as three scalars. Example: .. runblock:: pycon >>> from spatialmath import SE3 >>> SE3.RPY(0.1, 0.2, 0.3) >>> SE3.RPY([0.1, 0.2, 0.3]) >>> SE3.RPY(0.1, 0.2, 0.3, order='xyz') >>> SE3.RPY(10, 20, 30, unit='deg') :seealso: :func:`~spatialmath.pose3d.SE3.rpy`, :func:`~spatialmath.base.transforms3d.rpy2r` :SymPy: supported """ if len(angles) == 1: angles = angles[0] if base.isvector(angles, 3): return cls(base.rpy2tr(angles, order=order, unit=unit), check=False) else: return cls( [base.rpy2tr(a, order=order, unit=unit) for a in angles], check=False)