blenderproc.python.types.URDFUtility module
All URDF objects are captured in this class.
- class blenderproc.python.types.URDFUtility.URDFObject(armature, links, xml_tree=None)[source]
Bases:
EntityThis class represents an URDF object, which is comprised of an armature and one or multiple links. Among others, it serves as an interface for manipulation of the URDF model.
- _set_fk_ik_mode(mode='fk')[source]
Sets the mode of the bone chain.
- Parameters:
mode (
str) – One of “fk” or “ik” for forward / inverse kinematic.
- _set_ik_bone_constraint(bone)[source]
Sets the ik bone constraint.
- Parameters:
bone (
PoseBone) – Bone to set as ik constraint bone.
- _set_ik_bone_controller(bone)[source]
Sets the ik bone controller.
- Parameters:
bone (
PoseBone) – Bone to set as ik control bone.
- _set_ik_bone_offset(offset)[source]
Sets the location offset between the control and constraint bone.
- Parameters:
offset (
Matrix) – The location offset.
- _set_ik_link(ik_link)[source]
Sets the ik link constraint.
- Parameters:
ik_link (
Optional[Link]) – Link to set as ik link.
- _set_keyframe(name, frame=0)[source]
- Sets a keyframe for a specific name for all bones of all links, as well as the copy_rotation constraint for
revolute joints.
- Parameters:
name (
str) – Name of the keyframe to be inserted.frame (
int) – Where to insert the keyframe.
- _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 (
str) – One of for forward / inverse kinematik.keep_pose (
bool) – If specified, will keep the pose when switching modes. Otherwise, will return to the old pose of the previously selected mode.
- create_ik_bone_controller(link=None, relative_location=None, use_rotation=True, chain_length=0)[source]
Creates an ik bone controller and a corresponding constraint bone for the respective link.
- Parameters:
link (
Optional[Link]) – The link to create an ik bone for. If None, will use the last link.relative_location (
Union[List[float],Vector,None]) – 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 (
bool) – Whether to rotate the child links as well. Defaults to True.chain_length (
int) – The number of parent links which are influenced by this ik bone. Defaults to 0 for all parents.
- get_all_collision_local2world_mats()[source]
Returns all transformations from the world frame to the collision objects.
- Return type:
array- Returns:
Numpy array of shape (num_bones, 4, 4).
- get_all_collision_objs()[source]
Returns a list of all collision objects.
- Return type:
List[MeshObject]- Returns:
List of all collision objects.
- get_all_inertial_local2world_mats()[source]
Returns all transformations from the world frame to the inertial objects.
- Return type:
array- Returns:
Numpy array of shape (num_bones, 4, 4).
- get_all_inertial_objs()[source]
Returns a list of all inertial objects.
- Return type:
List[Inertial]- Returns:
List of all inertial objects.
- get_all_local2world_mats()[source]
Returns all matrix_world matrices from every joint.
- Return type:
array- Returns:
Numpy array of shape (num_bones, 4, 4).
- get_all_urdf_objs()[source]
Returns a list of all urdf-related objects.
- Return type:
List[Union[Link,Inertial,MeshObject]]- Returns:
List of all urdf-related objects.
- get_all_visual_local2world_mats()[source]
Returns all transformations from world frame to the visual objects.
- Return type:
array- Returns:
Numpy array of shape (num_bones, 4, 4).
- get_all_visual_objs()[source]
Returns a list of all visual objects.
- Return type:
List[MeshObject]- Returns:
List of all visual objects.
- get_links_with_revolute_joints()[source]
Returns all revolute joints.
- Return type:
List[Link]- Returns:
List of revolute joints.
- has_reached_ik_pose(location_error=0.01, rotation_error=0.01)[source]
Checks whether the urdf object was able to move to the currently set pose.
- Parameters:
location_error (
float) – Tolerable location error in m.rotation_error (
float) – Tolerable rotation error in radians.
- Return type:
bool- Returns:
True if the link is at the desired ik pose; else False.
- hide(hide_object=True)[source]
Sets the visibility of the object.
- Parameters:
hide_object (
bool) – Determines whether the object should be hidden in rendering.
- hide_links_and_collision_inertial_objs()[source]
Hides links and their respective collision and inertial objects from rendering.
- remove_link_by_index(index=0)[source]
- Removes a link and all its associated objects given an index. Also handles relationship of the link’s child
with its parent. This is useful for removing a ‘world link’ which could be a simple flat surface, or if someone wants to shorten the whole urdf object.
- Parameters:
index (
int) – Index of the joint to be removed.
- set_ascending_category_ids(category_ids=None)[source]
Sets semantic categories to the links and their associated objects.
- Parameters:
category_ids (
Optional[List[int]]) – List of ‘category_id’s for every link. If None, will create a list from [1 … len(links)].
- set_location_ik(location, frame=0)[source]
Performs location change in inverse kinematics mode.
- Parameters:
location (
Union[List[float],array,Vector]) – Location vector.frame (
int) – The keyframe where to insert the rotation.
- set_rotation_euler_fk(link, rotation_euler, mode='absolute', frame=0)[source]
- Rotates one specific link or all links based on euler angles in forward kinematic mode. Validates values
with given constraints.
- Parameters:
link (
Optional[Link]) – The link to be rotated. If None, will perform the rotation on all revolute joints.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.frame (
int) – The keyframe where to insert the rotation.
- set_rotation_euler_ik(rotation_euler, mode='absolute', frame=0)[source]
Performs rotation in inverse kinematics mode.
- Parameters:
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.frame (
int) – The keyframe where to insert the rotation.