phobos geometry module¶
This module provides all utilities that are related to mesh handling
Submodules¶
phobos.geometry.geometry module¶
- phobos.geometry.geometry.create_box(mesh, oriented=True, scale=1.0)¶
Create a box element.
- phobos.geometry.geometry.create_cylinder(mesh, scale=1.0)¶
Create a cylinder.
- phobos.geometry.geometry.create_sphere(mesh, scale=1.0)¶
Create a sphere
- phobos.geometry.geometry.get_reflection_matrix(point=array([0, 0, 0]), normal=array([0, 1, 0]))¶
- phobos.geometry.geometry.get_vertex_id(x, vertices)¶
- phobos.geometry.geometry.identical(mesh_a, mesh_b)¶
- phobos.geometry.geometry.improve_mesh(mesh)¶
- phobos.geometry.geometry.reduce_mesh(mesh, factor)¶
phobos.geometry.io module¶
- phobos.geometry.io.as_trimesh(scene_or_mesh, scale=None, silent=False)¶
- phobos.geometry.io.blender_2_mesh_info_dict(mesh)¶
Creates the mesh info dict :param mesh: bpy.types.Mesh
- Returns:
(n,3) single, “vertex_normals”: (n,3) single, “faces”: [n*[3*(n,3)]] intc, [“texture_coords”: (n,2) single]}
- Return type:
{“vertices”
- phobos.geometry.io.export_mesh(mesh, filepath, urdf_path=None, dae_mesh_color=None)¶
Export the mesh to a given filepath with an urdf_path. Detects the format by file ending. NOTE: For bobj it’s necessary to pass a trimesh.Trimesh as mesh other will raise an AssertionError.
- Parameters:
mesh – trimesh.Trimesh or trimesh.Scene
filepath – the filepath where to write the file
**mesh_info_dict – {“vertices”: (n,3) single, “vertex_normals”: (n,3) single, “faces”: [n*[n*(n,3)]] intc, [“texture_coords”: (n,2) single]}
- Returns:
(n,3) single, “vertex_normals”: (n,3) single, “faces”: [n*[3*(n,3)]] intc, [“texture_coords”: (n,2) single]}
- Return type:
{“vertices”
- phobos.geometry.io.import_mars_mesh(filepath, urdf_path=None)¶
- phobos.geometry.io.import_mesh(filepath, urdf_path=None)¶
Import the mesh from a given filepath with an urdf_path.
- phobos.geometry.io.mesh_info_dict_2_trimesh(vertices, faces, vertex_normals=None, texture_coords=None, **mesh_info_dict)¶
Creates the trimesh from the mesh info dict :param **mesh_info_dict: {“vertices”: (n,3) single, “vertex_normals”: (n,3) single, “faces”: [n*[3*(n,3)]] intc, [“texture_coords”: (n,2) single]}
- Returns:
trimesh.Trimesh
- phobos.geometry.io.parse_bobj(filepath)¶
Parses the mesh_info_dict from bobj format.
- Parameters:
filepath – the filepath where to write the file
- Returns:
(n,3) single, “vertex_normals”: (n,3) single, “faces”: [n*[3*(n,3)]] intc, [“texture_coords”: (n,2) single]}
- Return type:
{“vertices”
- phobos.geometry.io.parse_dae(filepath)¶
- phobos.geometry.io.parse_obj(filepath)¶
- phobos.geometry.io.triangulate_faces_in_info_dict(faces, **mesh_info_dict)¶
Triangulates the faces of the given mesh info dict. :param **mesh_info_dict: {“vertices”: (n,3) single, “vertex_normals”: (n,3) single, “faces”: [n*[n*(n,3)]] intc, [“texture_coords”: (n,2) single]}
- Returns:
(n,3) single, “vertex_normals”: (n,3) single, “faces”: [n*[3*(n,3)]] intc, [“texture_coords”: (n,2) single]}
- Return type:
{“vertices”
- phobos.geometry.io.trimesh_2_mesh_info_dict(mesh)¶
Creates the mesh info dict :param mesh: trimesh.Trimesh
- Returns:
(n,3) single, “vertex_normals”: (n,3) single, “faces”: [n*[3*(n,3)]] intc, [“texture_coords”: (n,2) single]}
- Return type:
{“vertices”
- phobos.geometry.io.write_bobj(filepath, vertices=None, vertex_normals=None, faces=None, texture_coords=None, **mesh_info_dict)¶
Writes the mesh_info_dict to bobj format.
- Parameters:
filepath – the filepath where to write the file
**mesh_info_dict – {“vertices”: (n,3) single, “vertex_normals”: (n,3) single, “faces”: [n*[n*(n,3)]] intc, [“texture_coords”: (n,2) single]}
- Returns:
(n,3) single, “vertex_normals”: (n,3) single, “faces”: [n*[3*(n,3)]] intc, [“texture_coords”: (n,2) single]}
- Return type:
{“vertices”
phobos.geometry.robot module¶
Tools for visual and collision editing.
- phobos.geometry.robot.find_zero_pose_collisions(robot)¶
- phobos.geometry.robot.generate_kccd_optimizer_ready_collision(robot, linkname, outputdir, join_first=True, merge_additionally=None, mars_meshes=False, reduce_meshes=0)¶
Takes the convexhulls of all visuals of the link and joins them to one mesh. If the join_first option is set to true then the meshes will be joint before the convexhull is generated.
WARNING: This function will edit the meshes pathes to absolute ones and should therefore only be used with a URDF that’S only purpose is to generate the kccd model
- phobos.geometry.robot.join_collisions(robot, linkname, collisionnames=None, name_id=None, only_return=False)¶
Replaces a series of visuals/collisions with a joined version of those given
- phobos.geometry.robot.reduce_mesh_collision(robot, linkname, collisionname=None, reduction=0.4)¶
Reduces the mesh collision(s) of the link(s) which have the corresponding collisionname.
- phobos.geometry.robot.remove_collision(robot, linkname, collisionname=None)¶
Remove the collision(s) of the link(s) which have the corresponding collisionname.
- phobos.geometry.robot.remove_visual(robot, linkname, visualname=None)¶
Remove the visual(s) of the link(s) which have the corresponding visualname.
- phobos.geometry.robot.replace_collision(robot, linkname, shape='box', oriented=False, scale=1.0)¶
Replace the collision(s) stated in linkname of the robot with an oriented shape.
- phobos.geometry.robot.replace_collisions(robot, shape='box', oriented=False, exclude=None)¶
Replace all collisions of the robot ( except exclude’s ) with a given shape. This can be a ‘sphere’, ‘cylinder’, ‘box’ or ‘convex’.
- phobos.geometry.robot.replace_geometry(element, shape='box', oriented=False, scale=1.0)¶
Replace the geometry of the element with an oriented shape. urdf_path is needed for mesh loading. :param element: An geometry element representation.Visual or representation.Collision :param shape: [‘box’, ‘sphere’, ‘cylinder’, ‘convex’] :param oriented: Whether the bounding box should be oriented to have the minimum volume to cover the element :param scale: whether the created shape shall be scaled by the given value
- Returns:
None
- phobos.geometry.robot.replace_visual(robot, linkname, shape='box', oriented=False)¶
Replace the visual(s) stated in linkname of the robot with an oriented shape.
- phobos.geometry.robot.replace_visuals(robot, shape='box', oriented=False, exclude=None)¶
Replace all visuals of the robot ( except exclude’s ) with a given shape. This can be a ‘sphere’, ‘cylinder’, ‘box’ or ‘convex’.