Armature Actuator
=================


**An actuator to manipulate Blender armatures in MORSE.**


**Armatures** are the MORSE generic way to simulate kinematic chains
made of a combination of revolute joints (hinge) and prismatic
joints (slider).

This component only allows to *write* armature configuration. To read the
armature pose, you need an :doc:`armature pose sensor <../sensors/armature_pose>`.

.. 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 read by the armature actuator
    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 pose sensor <../sensors/armature_pose>`

.. note::

    :tag:`ros` Armatures can be controlled in ROS through the
    `JointTrajectoryAction
    <http://www.ros.org/wiki/pr2_controllers/Tutorials/Moving%20the%20arm%20using%20the%20Joint%20Trajectory%20Action>`_
    interface.



.. cssclass:: properties morse-section

Configuration parameters for armature actuator
----------------------------------------------


You can set these properties in your scripts with ``<component>.properties(<property1>=..., <property2>=...)``.

- ``DistanceTolerance`` (float, default: ``0.005``)
	Tolerance in meters when translating a joint
- ``AngleTolerance`` (float, default: ``0.01``)
	Tolerance in radians when rotating a joint
- ``RotationSpeed`` (float, default: ``0.8``)
	Global rotation speed for the armature rotational joints (in rad/s)
- ``LinearSpeed`` (float, default: ``0.05``)
	Global linear speed for the armature prismatic joints (in m/s)


.. cssclass:: fields morse-section

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

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

.. cssclass:: services morse-section

Services for Armature Actuator
------------------------------

- ``rotate(joint, rotation, speed)`` (non blocking)
    Rotates a joint at a given speed (in rad/s).
    
    :sees: http://www.blender.org/documentation/blender_python_api_2_64_release/bge.types.html#bge.types.BL_ArmatureChannel.joint_rotation
    
    
  - Parameters

    - ``joint``: name of the armature's joint to rotate
    - ``rotation``: rotation around the joint axis in radians
    - ``speed``: (default: value of 'radial_speed' property) rotation speed, in rad/s

- ``get_IK_limits()`` (blocking)
    Returns the IK limits for the given joint.
    
    - For revolute joints, returns a pair `(ik_min,ik_max)`, in radians.
    - For prismatic joint, returns a pair `(0.0, max translation)`, in meters.
    
- ``set_rotations(rotations)`` (blocking)
    Sets in one call the rotations of the revolute joints in this armature.
    
    Has the same effect as applying `set_rotation` on each of the joints
    independantly.
    
    Rotations must be ordered from the root to the tip of the armature.
    
    If more rotations are provided than the number of joints, the remaining ones are discarded. If less rotations are provided, the maximum are applied.
    
    .. important::
    
        If a prismatic joint is encountered while applying the rotation,
        an exception is thrown, and **no** rotation is applied.
    
    :sees: `set_rotation`
    
  - Parameters

    - ``rotations``: a set of absolute rotations, in radians

- ``translate(joint, translation, speed)`` (non blocking)
    Translates a joint at a given speed (in m/s).
    
    
  - Parameters

    - ``joint``: name of the armature's joint to translate
    - ``translation``: the absolute translation, relative to the joint origin, in meters
    - ``speed``: (default: value of 'linear_speed' property) translation speed, in m/s

- ``get_dofs()`` (blocking)
    Returns a dictionary with keys the channels
    of the armature and as values the rotation axis of the joint.
    
- ``set_translations(translations)`` (blocking)
    Sets in one call the translations of the prismatic joints in this armature.
    
    Has the same effect as applying `set_translation` on each of the joints
    independantly.
    
    Translations must be ordered from the root to the tip of the armature.
    
    If more translations are provided than the number of joints, the remaining ones are discarded. If less translations are provided, the maximum are applied.
    
    .. important::
    
        If a revolute joint is encountered while applying the translations,
        an exception is thrown, and **no** translation is applied.
    
    :sees: `set_translation`
    
  - Parameters

    - ``translations``: a set of absolute translations, in meters

- ``trajectory(trajectory)`` (non blocking)
    Executes a joint trajectory to the armature.
    
    The `trajectory` parameter should have the following structure:
    
    .. code-block:: python
    
        trajectory = {
            'starttime': <timestamp in second>,
            'points': [
                {'positions': [...],
                 'velocities': [...],
                 'accelerations' [...],
                 'time_from_start': <seconds>}
                {...},
                ...
                ]
            }
    
    .. warning::
        
        Currently, both `velocities` and `accelerations` are ignored.
    
    The trajectory execution starts after `starttime` timestamp passed
    (if omitted, the trajectory execution starts right away).
    
    `points` is the list of trajectory waypoints. It is assumed that the
    values in the waypoints are ordered the same way as in the set of
    joint of the armature (ie, from the root to the tip of the armature).
    `velocities` and `accelerations` are optional.
    
    The component attempts to achieve each waypoint at the time obtained
    by adding that waypoint's `time_from_start` value to `starttime`.
    
    
  - Parameters

    - ``trajectory``: the trajectory to execute, as describe above.

- ``set_translation(joint, translation)`` (blocking)
    Translates instantaneously the given (prismatic) joint by the given
    translation. Joint speed limit is not taken into account.
    
    :sees: http://www.blender.org/documentation/blender_python_api_2_64_release/bge.types.html#bge.types.BL_ArmatureChannel.location
    
    If the joint does not exist or is not a prismatic joint (slider),
    throws a MorseServiceFailed exception.
    
    The translation is always clamped to the joint limit.
    
    
  - Parameters

    - ``joint``: name of the joint to move
    - ``translation``: absolute translation from the joint origin in the joint sliding axis, in meters

- ``set_rotation(joint, rotation)`` (blocking)
    Rotates instantaneously the given (revolute) joint by the given
    rotation. Joint speed limit is not taken into account.
    
    If the joint does not exist or is not a revolute joint (hinge),
    throws a MorseServiceFailed exception.
    
    The rotation is always clamped to the joint limit.
    
    
  - Parameters

    - ``joint``: name of the joint to rotate
    - ``rotation``: absolute rotation from the joint origin along the joint rotation axis, in radians

- ``set_target(x, y, z)`` (non blocking)
    Sets a target position for the armature's tip.
    
    MORSE uses inverse kinematics to find the joint
    angles/positions in order to get the armature tip as close
    as possible to the target.
    
    .. important::
    
        No obstacle avoidance takes place: while moving the armature
        may hit objects.
    
    .. warning::
        
        Not implemented yet! Only as a placeholder!
    
    
  - Parameters

    - ``x``: X coordinate of the IK target
    - ``y``: Y coordinate of the IK target
    - ``z``: Z coordinate of the IK target



.. 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 actuator
    armature = Armature()

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

    env = Environment('empty')
    

.. cssclass:: files morse-section

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

- `Source code <../../_modules/morse/actuators/armature.html>`_
- `Unit-test <../../_modules/base/armature_testing.html>`_




*(This page has been auto-generated from MORSE module morse.actuators.armature.)*
