blenderproc.python.types.LinkUtility module¶
-
class
blenderproc.python.types.LinkUtility.
Link
(bpy_object)[source]¶ Bases:
blenderproc.python.types.EntityUtility.Entity
-
_clip_value_from_constraint
(bone, value=0, constraint_name='', axis='X')[source]¶ - Checks if an axis is constraint, and clips the value to the min/max of this constraint. If the constraint
- does not exist, nothing is done.
Parameters: Return type: Returns: Clipped value if a constraint is set, else the initial value.
-
_create_ik_bone_controller
(relative_location=[0.0, 0.0, 0.0], use_rotation=True, chain_length=0)[source]¶ Creates an ik bone controller and a corresponding constraint bone for the respective link.
Parameters: - relative_location (
Union
[List
[float
],Vector
]) – Relative location of the ik bone controller w.r.t. the bone’s location. This can be used to shift the point of control further away from the end effector. - use_rotation – Whether to rotate the child links as well. Defaults to True.
- chain_length – The number of parent links which are influenced by this ik bone. Defaults to 0 for all parents.
Return type: (<class ‘bpy_types.PoseBone’>, <class ‘bpy_types.PoseBone’>, <class ‘Matrix’>)
Returns: Constraint and control bone.
- relative_location (
-
_determine_rotation_axis
(bone)[source]¶ - Determines the single rotation axis and checks if the constraints are set well to have only one axis of
- freedom.
Parameters: bone ( PoseBone
) – Bone of which the rotation axis will be determined.Return type: Optional
[str
]Returns: The single rotation axis (‘X’, ‘Y’ or ‘Z’) or None if no constraint is set..
-
_set_fk_ik_mode
(mode='fk')[source]¶ Sets the mode of the link.
Parameters: mode – One of [“fk”, “ik”] denoting forward or inverse kinematics mode.
-
_set_rotation_euler
(bone, rotation_euler, mode='absolute')[source]¶ Rotates the bone based on euler angles. Validates values with given constraints.
Parameters: - bone (
PoseBone
) – The bone to be rotated. - rotation_euler (
Union
[float
,List
[float
],Euler
,ndarray
]) – The amount of rotation (in radians). Either three floats for x, y and z axes, or a single float. In the latter case, the axis of rotation is derived based on the rotation constraint. If these are not properly set (i.e., two axes must have equal min/max values) an exception will be thrown. - mode (
str
) – One of [“absolute”, “relative”]. For absolute rotations we clip the rotation value based on the constraints. For relative we don’t - this will result in inverse motion after the constraint’s limits have been reached.
- bone (
-
get_all_objs
()[source]¶ Returns all meshes of this link.
Returns: List of all meshes (visual, collision, inertial) for this link.
-
get_collision_local2world_mats
()[source]¶ Returns the transformation matrices from world to the collision parts.
Return type: Optional
[List
]Returns: List of transformation matrices.
-
get_collisions
()[source]¶ Returns the collision meshes for this link.
Return type: List
[MeshObject
]Returns: List of collision meshes.
-
get_fk_ik_mode
()[source]¶ Returns the currently selected mode.
Return type: str
Returns: One of [“fk”, “ik”] denoting forward or inverse kinematics mode.
-
get_inertial
()[source]¶ Returns the inertial meshes for this link.
Return type: Inertial
Returns: List of inertial meshes.
-
get_inertial_local2world_mat
()[source]¶ Returns the transformation matrix from world to the inertial part.
Return type: Matrix
Returns: The transformation matrix.
-
get_joint_rotation
(frame=None)[source]¶ Get current joint rotation based on euler angles.
Parameters: frame ( Optional
[int
]) – The desired frame.Return type: float
Returns: Current joint rotation in radians.
-
get_joint_type
()[source]¶ Returns the joint type.
Return type: Optional
[str
]Returns: The joint type of the armature.
-
get_visual_local2world_mats
()[source]¶ Returns the transformation matrices from world to the visual parts.
Return type: Optional
[List
]Returns: List of transformation matrices.
-
get_visuals
()[source]¶ Returns the visual meshes for this link.
Return type: List
[MeshObject
]Returns: List of visual meshes.
-
hide
(hide_object=True)[source]¶ Sets the visibility of the object and all visual, collision and inertial parts.
Parameters: hide_object ( bool
) – Determines whether the object should be hidden in rendering.
-
parent_with_bone
(weight_distribution='rigid')[source]¶ Parents all objects of the link to the bone.
Parameters: weight_distribution – One of [‘envelope’, ‘automatic’, ‘rigid’]. For more information please see https://docs.blender.org/manual/en/latest/animation/armatures/skinning/parenting.html.
-
set_armature
(armature)[source]¶ Sets the armature which holds all the bones of all links.
Parameters: armature ( Armature
) – The armature.
-
set_bone
(bone)[source]¶ Sets the bone controlling the visuals / collisions / inertial of the link.
Parameters: bone ( PoseBone
) – The bone.
-
set_collision_local2link_mats
(matrix_list)[source]¶ Sets the transformation matrices from link to the collision parts.
Parameters: matrix_list ( List
[Matrix
]) – List of transformation matrices.
-
set_collisions
(collisions)[source]¶ Sets the collision meshes for this link.
Parameters: collisions ( List
[MeshObject
]) – List of collision meshes.
-
set_fk_bone
(bone)[source]¶ Sets the bone controlling the forward kinematic motion of this link.
Parameters: bone ( PoseBone
) – The bone.
-
set_ik_bone
(bone)[source]¶ Sets the bone controlling the inverse kinematic motion of this link.
Parameters: bone ( PoseBone
) – The bone.
-
set_ik_bone_constraint
(bone)[source]¶ Sets the constraint bone responsible for constraining to inverse kinematic motion.
Parameters: bone ( PoseBone
) – The bone.
-
set_ik_bone_controller
(bone)[source]¶ Sets the control bone controlling the inverse kinematic motion for this link.
Parameters: bone ( PoseBone
) – The bone.
-
set_inertial
(inertial)[source]¶ Sets the inertial meshes for this link.
Parameters: inertial ( Inertial
) – List of inertial meshes.
-
set_inertial_local2link_mat
(matrix)[source]¶ Sets the transformation matrix from link to inertial.
Parameters: matrix ( Matrix
) – The transformation matrix from link to inertial.
-
set_joint_type
(joint_type)[source]¶ Sets the joint type of the link which specifies the connection to its parent.
Parameters: joint_type ( Optional
[str
]) – One of [‘fixed’, ‘prismatic’, ‘revolute’, ‘continuous’, ‘planar’, ‘floating’ or None].
-
set_link2bone_mat
(matrix)[source]¶ Sets the transformation matrix from bone to link.
Parameters: matrix ( Matrix
) – The transformation from bone to link.
-
set_location
(*args, **kwargs)[source]¶ Sets the location of the entity in 3D world coordinates.
Parameters: - location – The location to set.
- frame – The frame number which the value should be set to. If None is given, the current frame number is used.
-
set_location_ik
(location)[source]¶ Sets the location of the ik bone controller in inverse kinematics mode.
Parameters: location ( Union
[List
[float
], <built-in function array>,Vector
]) – Location vector.
-
set_rotation_euler
(*args, **kwargs)[source]¶ Sets the rotation of the entity in euler angles.
Parameters: - rotation_euler – The euler angles to set.
- frame – The frame number which the value should be set to. If None is given, the current frame number is used.
-
set_rotation_euler_fk
(*args, **kwargs)[source]¶ Sets the rotation for this link in forward kinematics mode. See self._set_rotation_euler() for details.
-
set_rotation_euler_ik
(*args, **kwargs)[source]¶ Sets the rotation for this link in inverse kinematics mode. See self._set_rotation_euler() for details.
-
set_visual_local2link_mats
(matrix_list)[source]¶ Sets the transformation matrices from link to the visual parts.
Parameters: matrix_list ( List
[Matrix
]) – List of transformation matrices.
-
set_visuals
(visuals)[source]¶ Sets the visual meshes for this link.
Parameters: visuals ( List
[MeshObject
]) – List of visual meshes.
-
switch_fk_ik_mode
(mode='fk', keep_pose=True)[source]¶ - Switches between forward and inverse kinematics mode. Will do this automatically when switching between e.g.
- set_rotation_euler_fk() and set_rotation_euler_ik().
Parameters: - mode – One of [“fk”, “ik”] denoting forward or inverse kinematics mode.
- keep_pose – If specified, will keep the pose when switching modes. Otherwise will return to the old pose of the previously selected mode.
-