google-deepmind / mujoco

Multi-Joint dynamics with Contact. A general purpose physics simulator.
https://mujoco.org
Apache License 2.0
8.3k stars 836 forks source link

How to obtain/view (x,y,z) points in the convex hull of geoms and flexcomp objects #1635

Closed kurtenkera closed 6 months ago

kurtenkera commented 7 months ago

Hi,

I want to know how I can both "obtain" and "view" the (x,y,z) spatial points in the convex hull of a given (1) primitive geom (e.g., sphere, ellipsoid, box, capsule, cylinder), (b) rigid geom that references an STL file of a CAD geometry and (c) soft flexcomp that references a MSH file.

Note, by "obtain", I mean that I wish to store all of the points within the convex hull in a Numpy array (e.g., with shape = (n_convexhullpts, 3)) since I am using the Python bindings to access MuJoCo. By "view", I wish to view these points during a simulation using any recommended approach (note, I attempted to follow the advice described in issue #499, but had no luck).

I will label all of my specific questions below:

Q1: When I play around with the XML file below (see below) of a box falling from a height at various initial euler rotations, it appears that there are only 8 points in the convex hull of the box geom (i.e., the 8 corners).

<mujoco>
<worldbody>
  <light diffuse=".5 .5 .5" pos="0 0 3" dir="0 0 -1"/>
  <geom type="plane" size="1 1 0.1" rgba=".9 0 0 1"/>
  <body pos="0 0 1" euler = "0 45 90">
    <joint type="free"/>
    <geom type="box" size=".1 .2 .3" rgba="0 .9 0 1"/>
  </body>
</worldbody>
</mujoco>

This is evident to me, simply from the highlighted contacts which I am able to manually activate in the MuJoCo simulation GUI (see 4 highlighted contacts at the corners below):

image

Is there a way to obtain these 8 points (measured from either the world frame or local body frame) computationally through one of the mjModel attributes? For example, is there an attribute for all of the primitive geom objects which returns the points in their convex hull that are used for potential collision events (i.e. where the points are measured in the world or local body frame and stored in a Numpy array with shape = (n_convexhullpts, 3))? I have explored the mjModel documentation but cannot find anything?

Q2: Is there a nice general way to view all possible contact points in the convex hull of any primitive geom during simulation (e.g. for the box falling from some height, is there a way to view all 8 points in the convex hull throughout the simulation)?

Q3: I've created a simulation of a falling rigid hollow cylinder that references an STL file (contained in this ZIP folder: hollow_cylinder.zip). I did this using the code below:

import mujoco
import mediapy as media

xml_string = """
<mujoco>

  <asset>
    <mesh file="mesh_files/hollow_cylinder.stl"/>
  </asset>

  <option gravity = "0 0 -9.8" />

  <worldbody>
    <light diffuse=".5 .5 .5" pos="0 0 3" dir="0 0 -1"/>
    <geom type="plane" size="10 10 0.1" rgba="0 0.8 0 1"/>
    <body pos="0 0 2" euler = "0 60 0">
      <joint type="free"/>
      <geom type="mesh" name="hollow_cylinder" mesh="hollow_cylinder"/>
    </body>
  </worldbody>

</mujoco>
"""
model = mujoco.MjModel.from_xml_string(xml_string)
data = mujoco.MjData(model)

n_frames = 70
frames = []
renderer = mujoco.Renderer(model)

# simulate and render
for i in range(n_frames):
  while data.time < i/30.0: #1/4x real time
    mujoco.mj_step(model, data)
  renderer.update_scene(data)
  frame = renderer.render()
  frames.append(frame)

# show video
media.show_video(frames, fps=30)

The animation is shown here:

https://github.com/google-deepmind/mujoco/assets/127472392/8575ed2d-06f0-498b-95ec-dc6609c768ca

How can I computationally obtain all of the spatial points in the convex hull of this geom that references an STL file? It seems like the way to access this information using C/C++ is described here. However I need to do this in Python?

Q4: Is model.mesh_vertnum equal to the number of points in the convex hull of the above geom that references the STL file? (NOTE: For my hollow cylinder, model.mesh_vertnum = [504])

Q5: What does model.mesh_graph return? For my above STL file, model.mesh_graph returned an array with 3758 elements. The documentation suggests that model.mesh_graph contains information related to the convex hull but I'm not sure what these 3758 elements are?

Q6: How can I view all spatial points in the convex hull of my hollow cylinder that references an STL file?

Q7: Finally, I'd like to also know how to view and obtain all spatial points in the convex hull of a flexcomp object that references a MSH file?

kurtenkera commented 7 months ago

@yuvaltassa @saran-t @quagla It just occurred to me that the convex hull is probably comprised of a finite set of points $\in \mathbb{R}^3$ in the original STL/MSH file under consideration. And a smooth surface used for collision detection purposes is probably derived by connecting this finite set of points with flat faces. Is this true?

I'm still interested in methods for obtaining the original points in the convex hull if this is possible, as well as methods for viewing the convex hull during simulation?

Ideally I would like to iterate over the faces of the convex hull of a mesh/geom/flexcomp, and access the respective vertices/vertex indices.

yuvaltassa commented 6 months ago
  1. Primitive geoms do not have vertices. An ellipsoid is a perfectly smooth, abstract ellipsoid. The renderer invents some vertices in order to render it, but that's just for visualization.
  2. Meshes, read this. Note that pressing the "H" key will visualize the convex hulls, which are more clearly seen in wireframe mode ("W" key).
  3. Flexes are a different story altogether. The is no convex hull, it is already a collection of convex things (triangles and tetrahedra).