Classes | |
class | PoseMath |
Functions | |
def | fromCameraParams |
def | fromMatrix |
def | fromMsg |
def | fromTf |
def | toMatrix |
def | toMsg |
def | toPose |
def | toTf |
def kdl_posemath.fromCameraParams | ( | cv, | |
rvec, | |||
tvec | |||
) |
:param cv: OpenCV module :param rvec: A Rodrigues rotation vector - see :func:`Rodrigues2` :type rvec: 3x1 :class:`CvMat` :param tvec: A translation vector :type tvec: 3x1 :class:`CvMat` :return: New :class:`PyKDL.Frame` object For use with :func:`FindExtrinsicCameraParams2`:: import cv import tf_conversions.posemath as pm ... rvec = cv.CreateMat(3, 1, cv.CV_32FC1) tvec = cv.CreateMat(3, 1, cv.CV_32FC1) cv.FindExtrinsicCameraParams2(model, corners, intrinsic_matrix, kc, rvec, tvec) pose = pm.fromCameraParams(cv, rvec, tvec)
Definition at line 140 of file kdl_posemath.py.
def kdl_posemath.fromMatrix | ( | m | ) |
:param m: input 4x4 matrix :type m: :func:`numpy.array` :return: New :class:`PyKDL.Frame` object Convert a pose represented as a 4x4 numpy array to a :class:`PyKDL.Frame`.
Definition at line 94 of file kdl_posemath.py.
def kdl_posemath.fromMsg | ( | p | ) |
:param p: input pose :type p: :class:`geometry_msgs.msg.Pose` :return: New :class:`PyKDL.Frame` object Convert a pose represented as a ROS Pose message to a :class:`PyKDL.Frame`.
Definition at line 63 of file kdl_posemath.py.
def kdl_posemath.fromTf | ( | tf | ) |
:param tf: :class:`tf.Transformer` transform :type tf: tuple (translation, quaternion) :return: New :class:`PyKDL.Frame` object Convert a pose returned by :meth:`tf.Transformer.lookupTransform` to a :class:`PyKDL.Frame`. .. doctest:: >>> import rospy >>> import tf >>> import geometry_msgs.msg >>> t = tf.Transformer(True, rospy.Duration(10.0)) >>> m = geometry_msgs.msg.TransformStamped() >>> m.header.frame_id = 'THISFRAME' >>> m.child_frame_id = 'CHILD' >>> m.transform.translation.x = 668.5 >>> m.transform.rotation.w = 1.0 >>> t.setTransform(m) >>> t.lookupTransform('THISFRAME', 'CHILD', rospy.Time(0)) ((668.5, 0.0, 0.0), (0.0, 0.0, 0.0, 1.0)) >>> import tf_conversions.posemath as pm >>> p = pm.fromTf(t.lookupTransform('THISFRAME', 'CHILD', rospy.Time(0))) >>> print pm.toMsg(p * p) position: x: 1337.0 y: 0.0 z: 0.0 orientation: x: 0.0 y: 0.0 z: 0.0 w: 1.0
Definition at line 9 of file kdl_posemath.py.
def kdl_posemath.toMatrix | ( | f | ) |
:param f: input pose :type f: :class:`PyKDL.Frame` Return a numpy 4x4 array for the Frame F.
Definition at line 108 of file kdl_posemath.py.
def kdl_posemath.toMsg | ( | f | ) |
:param f: input pose :type f: :class:`PyKDL.Frame` Return a ROS Pose message for the Frame f.
Definition at line 77 of file kdl_posemath.py.
def kdl_posemath.toPose | ( | x, | |
q | |||
) |
:param x: input position :param 1: input quaternion :type p: output pose Return a ROS pose from python lists.
Definition at line 121 of file kdl_posemath.py.
def kdl_posemath.toTf | ( | f | ) |
:param f: input pose :type f: :class:`PyKDL.Frame` Return a tuple (position, quaternion) for the pose.
Definition at line 52 of file kdl_posemath.py.