Public Member Functions | Static Public Member Functions | Public Attributes
kdl_posemath.PoseMath Class Reference

List of all members.

Public Member Functions

def __init__
def __invert__
def __mul__
def __repr__
def asEuler
def asMatrix
def asMessage
def asTf

Static Public Member Functions

def fromCameraParams
def fromEuler
def fromMatrix
def fromTf

Public Attributes

 msg

Detailed Description

:param msg: ROS Pose message


Poses can be concatenated using ``*``:

.. doctest::

    >>> import tf_conversions.posemath as pm
    >>> from math import pi
    >>> trans = PoseMath.fromEuler(1, 2, 3, 0, 0, 0)
    >>> rotate = PoseMath.fromEuler(0, 0, 0, pi / 2, 0, 0)
    >>> print trans * rotate
    position: 
      x: 1.0
      y: 2.0
      z: 3.0
    orientation: 
      x: 0.707106781187
      y: 0.0
      z: 0.0
      w: 0.707106781187
    >>> print rotate * trans
    position: 
      x: 1.0
      y: -3.0
      z: 2.0
    orientation: 
      x: 0.707106781187
      y: 0.0
      z: 0.0
      w: 0.707106781187

and inverted using ``~``:

.. doctest::

    >>> import tf_conversions.posemath as pm
    >>> trans = PoseMath.fromEuler(1, 2, 3, 0, 0, 0)
    >>> print ~trans
    position: 
      x: -1.0
      y: -2.0
      z: -3.0
    orientation: 
      x: 0.0
      y: 0.0
      z: 0.0
      w: 1.0

Definition at line 168 of file kdl_posemath.py.


Constructor & Destructor Documentation

def kdl_posemath.PoseMath.__init__ (   self,
  msg 
)

Definition at line 223 of file kdl_posemath.py.


Member Function Documentation

Definition at line 369 of file kdl_posemath.py.

def kdl_posemath.PoseMath.__mul__ (   self,
  other 
)

Definition at line 365 of file kdl_posemath.py.

Definition at line 375 of file kdl_posemath.py.

Return a tuple (x, y, z, Rx, Ry, Rz) for the pose. 

Definition at line 388 of file kdl_posemath.py.

Return a numpy 4x4 array for the pose. 

Definition at line 382 of file kdl_posemath.py.

Return the pose as a ROS ``Pose`` message 

Definition at line 378 of file kdl_posemath.py.

Return a tuple (position, quaternion) for the pose. 

Definition at line 393 of file kdl_posemath.py.

def kdl_posemath.PoseMath.fromCameraParams (   self,
  cv,
  rvec,
  tvec 
) [static]
: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 PoseMath 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 = PoseMath.fromCameraParams(cv, rvec, tvec)

Definition at line 336 of file kdl_posemath.py.

def kdl_posemath.PoseMath.fromEuler (   x,
  y,
  z,
  Rx,
  Ry,
  Rz 
) [static]
:param x: x translation
:type x: float 
:param y: y translation
:type y: float 
:param z: z translation
:type z: float 
:param Rx: rotation around x-axis in radians
:type Rx: float 
:param Ry: rotation around y-axis in radians
:type Ry: float 
:param Rz: rotation around z-axis in radians
:type Rz: float 
:return: New PoseMath object

Return a PoseMath object initialized from translation (x, y, z) and Euler rotation (Rx, Ry, Rz).

.. doctest::

    >>> import tf_conversions.posemath as pm
    >>> from math import pi
    >>> print PoseMath.fromEuler(1, 2, 3, 0, pi / 2, 0)
    position: 
      x: 1
      y: 2
      z: 3
    orientation: 
      x: 0.0
      y: 0.707106781187
      z: 0.0
      w: 0.707106781187


Definition at line 297 of file kdl_posemath.py.

def kdl_posemath.PoseMath.fromMatrix (   m) [static]
:param m: 4x4 array
:type m: :func:`numpy.array`
:return: New PoseMath object

Return a PoseMath object initialized from 4x4 matrix m

.. doctest::

    >>> import numpy
    >>> import tf_conversions.posemath as pm
    >>> print PoseMath.fromMatrix(numpy.identity(4))
    position: 
      x: 0.0
      y: 0.0
      z: 0.0
    orientation: 
      x: 0.0
      y: 0.0
      z: 0.0
      w: 1.0

Definition at line 227 of file kdl_posemath.py.

def kdl_posemath.PoseMath.fromTf (   tf) [static]
:param tf: tf transform
:type tf: tuple (translation, quaternion)
:return: New PoseMath object

Return a PoseMath object initialized from a :mod:`tf` transform, as returned by :meth:`tf.Transformer.lookupTransform`.

.. 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 = PoseMath.fromTf(t.lookupTransform('THISFRAME', 'CHILD', rospy.Time(0)))
    >>> print 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 257 of file kdl_posemath.py.


Member Data Documentation

Definition at line 223 of file kdl_posemath.py.


The documentation for this class was generated from the following file:


r2_teleop
Author(s): Paul Dinh
autogenerated on Fri Jan 3 2014 11:34:08