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 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.
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: | armature pose sensor |
---|
Note
ros Armatures can be controlled in ROS through the JointTrajectoryAction interface.
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)
No data field documented (see above for possible notes).
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.
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.
Translates a joint at a given speed (in m/s).
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 |
---|
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!
Returns the IK limits for the given joint.
Returns a dictionary with keys the channels of the armature and as values the rotation axis of the joint.
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.
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 |
---|
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 |
---|
The following example shows how to use this component in a Builder script:
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(armature)
# define one or several communication interface, like 'socket'
armature.add_interface(<interface>)
env = Environment('empty')
(This page has been auto-generated from MORSE module morse.actuators.armature.)