Armature Pose Sensor
====================


**Returns the joint state of a MORSE armature**


The sensor streams the joint state (ie, the rotation or translation value
of each joint belonging to the armature) of its parent armature.

.. note::

    This sensor **must** be added as a child of the armature
    you want to sense, like in the example below:

    .. code-block:: python

        robot = ATRV()

        arm = KukaLWR()
        robot.append(arm)
        arm.translate(z=0.9)

        arm_pose = ArmaturePose('arm_pose')
        arm.append(arm_pose)

This component only allows to *read* armature configuration. To change the
armature pose, you need an :doc:`armature actuator <../actuators/armature>`.

.. important:: 

    To be valid, special care must be given when creating armatures. If you
    want to add new one, please carefully read the :doc:`armature creation
    <../../dev/armature_creation>` documentation.


.. note::

    The data structure on datastream exported by the armature sensor
    depends on the armature.  It is a dictionary of pair `(joint name,
    joint value)`.  Joint values are either radians (for revolute joints)
    or meters (for prismatic joints)


:sees: :doc:`armature actuator <../actuators/armature>`


.. cssclass:: properties morse-section

Configuration parameters for armature pose sensor
-------------------------------------------------

*No configurable parameter.*

.. cssclass:: fields morse-section

Data fields
-----------

No data field documented (see above for possible notes).

.. cssclass:: services morse-section

Services for Armature Pose Sensor
---------------------------------

- ``get_local_data()`` (blocking)
    Returns the current data stored in the sensor.
    
    
  - Return value

    a dictionary of the current sensor's data 

- ``get_joints_length()`` (blocking)
    Returns a dict with the armature joints' names as key and
    and the corresponding bone length as value (in meters).
    
- ``get_joint(joint)`` (blocking)
    Returns the *value* of a given joint, either:
    - its absolute rotation in radian along its rotation axis, or
    - it absolute translation in meters along its translation axis.
    
    Throws an exception if the joint does not exist.
    
    
  - Parameters

    - ``joint``: the name of the joint in the armature.

- ``get_state()`` (blocking)
    Returns the joint state of the armature, ie a dictionnary with joint
    names as key and the corresponding rotation or translation as value
    (respectively in radian or meters).
    
    
- ``get_joints()`` (blocking)
    Returns the list of joints of the armature.
    
    
  - Return value

    the (ordered) list of joints in the armature, from root to tip. 



.. cssclass:: examples morse-section

Examples
--------


The following example shows how to use this component in a *Builder* script:

.. code-block:: python


    from morse.builder import *
    
    robot = ATRV()
    
    # creates a new instance of the sensor
    armaturepose = ArmaturePose()

    # place your component at the correct location
    armaturepose.translate(<x>, <y>, <z>)
    armaturepose.rotate(<rx>, <ry>, <rz>)
    
    robot.append(%(var)s)
    
    # define one or several communication interface, like 'socket'
    armaturepose.add_interface(<interface>)

    env = Environment('empty')
    

.. cssclass:: files morse-section

Other sources of examples
+++++++++++++++++++++++++

- `Source code <../../_modules/morse/sensors/armature_pose.html>`_
- `Unit-test <../../_modules/base/armature_pose_testing.html>`_




*(This page has been auto-generated from MORSE module morse.sensors.armature_pose.)*
