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 set an armature configuration. To read the armature pose, you need an armature pose sensor.

Important

To be valid, special care must be given when creating armatures. If you want to add new one, please carefully read the armature creation documentation.

This actuator offers two main ways to control a kinematic chain: either by setting the values of each joint individually (via a continuous datastream or via dedicated services: translate(), set_translation(), rotate(), set_rotation()) or by placing the end-effector and relying on a inverse kinematic solver (via the services set_IK_target() and move_IK_target()).

Note

When setting the joints with a datastream, the data structure that the armature actuator expects depends on the armature itself. It is a dictionary of pair (joint name, joint value). Joint values are either radians (for revolute joints) or meters (for prismatic joints)

To use inverse kinematics, you must first define IK targets to control your kinematic chain. You can create them manually from Blender or directly in your Builder script (refer to the Examples section below for an example).

Note

ros Armatures can be controlled in ROS through the JointTrajectoryAction interface.

See also: armature pose sensor

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)
  • IKRotationSpeed (float, default: 0.5)
    Default speed of IK target rotation (in rad/s)
  • IKLinearSpeed (float, default: 0.5)
    Default speed of IK target motion (in m/s)

Data fields

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

Services for Armature Actuator

  • 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.
  • get_configurations() (blocking)

    Returns the configurations of a component (parsed from the properties).

    • Return value

      a dictionary of the current component’s configurations

  • get_dofs() (blocking)

    Returns a dictionary with keys the channels of the armature and as values the rotation axes of the joint.

    Rotation axes are represented as a list of boolean. For instance, [True, False, True] means that the x and z axes of the joint are free to rotate (or translate, depending on the type of the joint).

  • get_joints() (blocking)

    Returns the names of all the joints in this armature, ordered from the root to the tip.

  • get_properties() (blocking)

    Returns the properties of a component.

    • Return value

      a dictionary of the current component’s properties

  • list_IK_targets() (blocking)

    (no documentation yet)

  • move_IK_target(name, translation, rotation, relative, linear_speed, radial_speed) (non blocking)

    Moves an IK (inverse kinematic) target at a given speed (in m/s for translation, rad/s for rotation).

    Note that moving an IK target conflicts somewhat with the original purpose of the inverse kinematic solver, and overall continuity is not guaranteed (the IK solver may find a solution for a given target position that ‘jumps’ relative to the solution for the previous target position).

    See also: place_IK_target to set instantaneously the IK target pose.

    • Parameters
      • name: name of the IK target (as returned by list_IK_targets())
      • translation: a [x,y,z] translation vector, in the scene frame, in meters.
      • rotation: a [rx,ry,rz] rotation, in the scene frame (ie, X,Y,Z rotation axis are the scene axis). Angles in radians.
      • relative: if True (default), translation and rotation are relative to the current target pose.
      • linear_speed: (default: value of the ik_target_linear_speed property) translation speed (in m/s).
      • radial_speed: (default: value of the ik_target_radial_speed property) rotation speed (in rad/s).
  • place_IK_target(name, translation, rotation, relative) (blocking)

    Places instantaneously a IK (inverse kinematic) target to a given position and orientation.

    See also: move_IK_target to move the IK target over time.

    • Parameters
      • name: name of the IK target (as returned by list_IK_targets())
      • translation: a [x,y,z] translation vector, in the scene frame, in meters.
      • rotation: a [rx,ry,rz] rotation, in the scene frame (ie, X,Y,Z rotation axis are the scene axis). Angles in radians.
      • relative: if True (default), translation and rotation are relative to the current target pose.
  • rotate(joint, rotation, speed) (non blocking)

    Rotates a joint at a given speed (in rad/s).

    See also: Blender documentation on 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
  • rotate_joints(joint_rotations, speed) (non blocking)

    Rotates a set of joints at a given speed (in rad/s).

    See also: Blender documentation on joint rotation

    Note

    Setting different speeds for each joints is not yet supported (but if you need it, ping morse-dev@laas.fr: it is fairly easy to add).

    • Parameters
      • joint_rotations: a list of mapping {name of the armature’s joint: rotation in radian}
      • speed: (default: value of ‘radial_speed’ property) rotation speed for all joints, in rad/s
  • set_property(prop_name, prop_val) (blocking)

    Modify one property on a component

    • Parameters

      • prop_name: the name of the property to modify (as shown the documentation)
      • prop_val: the new value of the property. Note that there is no checking about the type of the value so be careful
    • Return value

      nothing

  • 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_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. Use the service get_joints() to retrieve the list of joints in the correct order.

    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.

    See also: set_rotation

    • Parameters
      • rotations: a set of absolute rotations, in radians
  • set_translation(joint, translation) (blocking)

    Translates instantaneously the given (prismatic) joint by the given translation. Joint speed limit is not taken into account.

    See also: Blender documentation on joint 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_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. Use the service get_joints() to retrieve the list of joints in the correct order.

    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.

    See also: 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:

    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. Use the service get_joints() to retrieve the list of joints in the correct order.) 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.
  • 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
  • translate_joints(joint_translations, speed) (non blocking)

    Translates a set of joints at a given speed (in m/s).

    Note

    Setting different speeds for each joints is not yet supported (but if you need it, ping morse-dev@laas.fr: it is fairly easy to add).

    • Parameters
      • joint_translations: a list of mapping {name of the armature’s joint: translation in meters}
      • speed: (default: value of ‘linear_speed’ property) rotation speed for all joints, in m/s

Examples

The following examples show how to use this component in a Builder script:

from morse.builder import *

robot = ATRV()

# imports an armature,
# either from a Blender file...
armature = Armature(model_name = "<blend file>")
# ...or by providing the name of an existing armature:
# armature = Armature(armature_name = "<name of armature>")
# (note that you can combine both options to select an armature in a
# Blender file)

# if you want to use inverse kinematics, you can create 'IK targets'
# here as well:
armature.create_ik_targets(["<name of the bone you want to control>", ...])

# place your armature at the correct location
armature.translate(<x>, <y>, <z>)
armature.rotate(<rx>, <ry>, <rz>)

# define one or several communication interfaces, like 'socket' or 'ros'
# With ROS, this actuator exposes a JointTrajectoryAction interface.
armature.add_interface(<interface>)

robot.append(armature)

env = Environment('empty')

Other sources of examples

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