robokudo.utils.transform ======================== .. py:module:: robokudo.utils.transform Functions --------- .. autoapisummary:: robokudo.utils.transform.get_pose_from_transform_matrix robokudo.utils.transform.get_transform_matrix_from_pose robokudo.utils.transform.get_transform_matrix robokudo.utils.transform.get_transform_matrix_from_translation robokudo.utils.transform.get_transform_matrix_for_rotation_around_axis robokudo.utils.transform.get_transform_matrix_from_q robokudo.utils.transform.get_rotation_matrix_from_euler_angles robokudo.utils.transform.get_rotation_matrix_from_q robokudo.utils.transform.get_quaternion_from_rotation_matrix robokudo.utils.transform.get_quaternion_from_transform_matrix robokudo.utils.transform.get_translation_from_transform_matrix robokudo.utils.transform.get_rotation_from_transform_matrix robokudo.utils.transform.get_transform_from_plane_equation robokudo.utils.transform.construct_rotation_matrix Module Contents --------------- .. py:function:: get_pose_from_transform_matrix(transform: numpy.typing.NDArray) -> geometry_msgs.msg.Pose Get a ROS geometry_msgs Pose from a 4x4 transformation matrix. :param transform: 4x4 transformation matrix :return: Equivalent pose .. py:function:: get_transform_matrix_from_pose(pose: geometry_msgs.msg.Pose) -> numpy.typing.NDArray Get a 4x4 transformation matrix from a ROS geometry_msgs Pose. :param pose: Equivalent pose :return: 4x4 transformation matrix .. py:function:: get_transform_matrix(rotation: numpy.typing.NDArray, translation: numpy.typing.NDArray) -> numpy.typing.NDArray rotation: 3x3 translation 3dim vector returns 4x4 transformation matrix .. py:function:: get_transform_matrix_from_translation(translation: numpy.typing.NDArray) -> numpy.typing.NDArray translation 3dim vector returns 4x4 transformation matrix .. py:function:: get_transform_matrix_for_rotation_around_axis(angle: float, axis: tuple) -> numpy.typing.NDArray .. py:function:: get_transform_matrix_from_q(quaternion: numpy.typing.NDArray, translation: numpy.typing.NDArray) -> numpy.typing.NDArray rotation: quaternion (x,y,z,w) in an array translation 3dim vector returns 4x4 transformation matrix .. py:function:: get_rotation_matrix_from_euler_angles(x: float, y: float, z: float) -> numpy.typing.NDArray Euler angles in X,Y,Z order returns 3x3 rotation matrix .. py:function:: get_rotation_matrix_from_q(quaternion: numpy.typing.NDArray) -> numpy.typing.NDArray rotation: quaternion (x,y,z,w) in an array returns 3x3 rotation matrix .. py:function:: get_quaternion_from_rotation_matrix(rotation_matrix: numpy.typing.NDArray) -> numpy.typing.NDArray rotation: 3x3 rotation matrix returns quaternion(x,y,z,w) in an array .. py:function:: get_quaternion_from_transform_matrix(transform_matrix: numpy.typing.NDArray) -> numpy.typing.NDArray transform_matrix: 4x4 transformation matrix returns quaternion(x,y,z,w) in an array .. py:function:: get_translation_from_transform_matrix(transform_matrix: numpy.typing.NDArray) -> numpy.typing.NDArray transform_matrix: 4x4 transformation matrix returns translation(x,y,z) in an array .. py:function:: get_rotation_from_transform_matrix(transform_matrix: numpy.typing.NDArray) -> numpy.typing.NDArray transform_matrix: 4x4 transformation matrix returns rotation 3x3 .. py:function:: get_transform_from_plane_equation(plane_equation: numpy.typing.NDArray) -> numpy.typing.NDArray Given a plane equation in the general form (a,b,c,d), calculate a transformation matrix that can be used to transform a geometry onto that plane with the rotation based on the plane normal. :param plane_equation: Numpy array containing 4 elements (a,b,c,d) :return: A 4x4 transformation matrix .. py:function:: construct_rotation_matrix(pose_orientation: numpy.typing.NDArray, axis_order: list) -> numpy.typing.NDArray Constructs a rotation matrix based on the given pose orientation and axis order. This method can be used if you want to exchange axes with each other, for example when the z axis shall be switched with the x-axis. :param pose_orientation: A matrix representing the pose orientation as a 3x3 rotation matrix :param axis_order: A list of integers [a, b, c] where each element specifies the order of the axis (0 for the first axis, 1 for the second, and so on). :return: A new rotation matrix based on the specified axis order.