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
You can set these properties in your scripts with <component>.properties(<property1>=..., <property2>=...).
Tolerance in meters when translating a joint
Tolerance in radians when rotating a joint
Global rotation speed for the armature rotational joints (in rad/s)
Global linear speed for the armature prismatic joints (in m/s)
Default speed of IK target rotation (in rad/s)
Default speed of IK target motion (in m/s)
No data field documented (see above for possible notes).
(no documentation yet)
Returns the IK limits for the given joint.
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.
See also: set_rotation
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.
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.
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.
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). 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.
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.
Returns the configurations of a component (parsed from the properties).
Return value
a dictionary of the current component’s configurations
Returns a dictionary with keys the channels of the armature and as values the rotation axis of the joint.
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.
See also: set_translation
Rotates a joint at a given speed (in rad/s).
See also: Blender documentation on joint rotation
Returns the properties of a component.
Return value
a dictionary of the current component’s properties
Translates a joint at a given speed (in m/s).
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')
(This page has been auto-generated from MORSE module morse.actuators.armature.)