How to load a textured mesh that can result in collision?
Opened this issue · 0 comments
zjwzcx commented
I found two ways to load mesh into Isaac Gym:
1. self.gym.load_asset() -> self.gym.create_actor()
2. self.gym.add_triangle_mesh()
What's the difference between them?
I found that the mesh loaded by load_asset() shows the texture while it cannot result in correct collision. The mesh loaded by add_triangle_mesh() can result in collision but shows no texture.
Way 1:
urdf_name = "xxxx.urdf"
asset = self.gym.load_asset(self.sim, asset_root, urdf_name, asset_options)
pose = gymapi.Transform()
ahandle = self.gym.create_actor(env_handle, asset, pose, None, env_index, 0)
urdf file:
<?xml version="1.0" encoding="utf-8"?>
<robot name="statue" xmlns:xacro="http://www.ros.org/wiki/xacro">
<link name="statue">
<inertial>
<mass value=".25"/>
<origin rpy="0 0 0" xyz="0 0 0"/>
<inertia ixx="1e-4" ixy="0" ixz="0" iyy="1e-4" iyz="0" izz="1e-4"/>
</inertial>
<visual>
<origin rpy="0 0 0" xyz="0 0 0"/>
<geometry>
<mesh filename="obj_name.obj"/>
</geometry>
</visual>
<collision>
<origin rpy="0 0 0" xyz="0 0 0"/>
<geometry>
<mesh filename="obj_name.obj"/>
</geometry>
</collision>
</link>
</robot>
Way 2:
mesh = o3d.io.read_triangle_mesh('obj_name.obj')
mesh_vertices = np.asarray(mesh.vertices).astype(np.float32)
mesh_triangles = np.asarray(mesh.triangles).astype(np.uint32)
tm_params = gymapi.TriangleMeshParams()
tm_params.nb_vertices = mesh_vertices.shape[0]
tm_params.nb_triangles = mesh_triangles.shape[0]
self.gym.add_triangle_mesh(self.sim, mesh_vertices.flatten(order='C'),
mesh_triangles.flatten(order='C'),
tm_params)