Skip to content

Commit 07aa4e1

Browse files
committed
Add invalid link com diagnosis.
1 parent 692a2fb commit 07aa4e1

File tree

5 files changed

+42
-23
lines changed

5 files changed

+42
-23
lines changed

genesis/engine/entities/rigid_entity/rigid_entity.py

Lines changed: 10 additions & 12 deletions
Original file line numberDiff line numberDiff line change
@@ -24,7 +24,7 @@
2424
from genesis.utils import terrain as tu
2525
from genesis.utils import urdf as uu
2626
from genesis.utils.urdf import compose_inertial_properties, rotate_inertia
27-
from genesis.utils.misc import DeprecationError, broadcast_tensor, ti_to_torch
27+
from genesis.utils.misc import DeprecationError, broadcast_tensor, ti_to_numpy, ti_to_torch
2828
from genesis.engine.states.entities import RigidEntityState
2929

3030
from ..base_entity import Entity
@@ -3285,17 +3285,15 @@ def get_mass(self):
32853285
an array of shape (n_envs,) with per-environment masses.
32863286
"""
32873287
if self._enable_heterogeneous:
3288-
# Use solver's batched links_info for accurate per-environment masses
3289-
all_links_mass = self._solver.links_info.inertial_mass.to_numpy()
3290-
links_idx = np.arange(self.link_start, self.link_end)
3291-
# Shape: (n_links, n_envs) -> sum over links axis
3292-
return all_links_mass[links_idx].sum(axis=0)
3293-
else:
3294-
# Original behavior: sum link masses to scalar
3295-
mass = 0.0
3296-
for link in self.links:
3297-
mass += link.get_mass()
3298-
return mass
3288+
links_idx = slice(self.link_start, self.link_end)
3289+
links_mass = ti_to_numpy(self._solver.links_info.inertial_mass, None, links_idx, transpose=True)
3290+
return links_mass.sum(axis=1)
3291+
3292+
# Original behavior: sum link masses to scalar
3293+
mass = 0.0
3294+
for link in self.links:
3295+
mass += link.get_mass()
3296+
return mass
32993297

33003298
# ------------------------------------------------------------------------------------
33013299
# --------------------------------- naming methods -----------------------------------

genesis/engine/entities/rigid_entity/rigid_link.py

Lines changed: 25 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -21,6 +21,7 @@
2121

2222
# If mass is too small, we do not care much about spatial inertia discrepancy
2323
MASS_EPS = 0.005
24+
AABB_EPS = 0.002
2425
INERTIA_RATIO_MAX = 100.0
2526

2627

@@ -137,6 +138,8 @@ def _build(self):
137138
hint_mass = 0.0
138139
hint_com = np.zeros(3, dtype=gs.np_float)
139140
hint_inertia = np.zeros((3, 3), dtype=gs.np_float)
141+
aabb_min = np.full((3,), float("inf"), dtype=gs.np_float)
142+
aabb_max = np.full((3,), float("-inf"), dtype=gs.np_float)
140143
if not self._is_fixed:
141144
# Determine which geom list to use: geoms first, then vgeoms, then fallback
142145
if self._geoms:
@@ -220,15 +223,37 @@ def _build(self):
220223
hint_mass, hint_com, hint_inertia, geom_mass, geom_com_link, geom_inertia_link
221224
)
222225

226+
# Compute the bounding box of the links using both visual and collision geometries to be conservative
227+
for geoms, is_visual in zip((self._geoms, self._vgeoms), (False, True)):
228+
for geom in geoms:
229+
verts = geom.init_vverts if is_visual else geom.init_verts
230+
verts = gu.transform_by_trans_quat(verts, geom._init_pos, geom._init_quat)
231+
aabb_min = np.minimum(aabb_min, verts.min(axis=0))
232+
aabb_max = np.maximum(aabb_max, verts.max(axis=0))
233+
223234
# Make sure that provided spatial inertia is consistent with the estimate from the geometries if not fixed
224235
if hint_mass > MASS_EPS:
236+
if self._inertial_pos is not None:
237+
tol = (aabb_max - aabb_min) * AABB_EPS + AABB_EPS
238+
if not ((aabb_min - tol < self._inertial_pos) & (self._inertial_pos < aabb_max + tol)).all():
239+
com_str: list[str] = []
240+
aabb_str: list[str] = []
241+
for name, pos, axis_min, axis_max in zip(("x", "y", "z"), self._inertial_pos, aabb_min, aabb_max):
242+
com_str.append(f"{name}={pos:0.3f}")
243+
aabb_str.append(f"{name}=({axis_min:0.3f}, {axis_max:0.3f})")
244+
gs.logger.warning(
245+
f"Link '{self._name}' has dubious center of mass [{', '.join(com_str)}] compared to the "
246+
f"bounding box from geometry [{', '.join(aabb_str)}]."
247+
)
248+
225249
if self._inertial_mass is not None:
226250
if not (hint_mass / INERTIA_RATIO_MAX <= self._inertial_mass <= INERTIA_RATIO_MAX * hint_mass):
227251
gs.logger.warning(
228252
f"Link '{self._name}' has dubious mass {self._inertial_mass:0.3f} compared to the estimate "
229253
f"from geometry {hint_mass:0.3f} given material density {rho:0.0f}."
230254
)
231255
hint_inertia *= self._inertial_mass / hint_mass
256+
232257
if self._inertial_i is not None:
233258
inertia_diag = np.diag(self._inertial_i)
234259
hint_inertia_diag = np.diag(hint_inertia)

genesis/utils/mjcf.py

Lines changed: 2 additions & 2 deletions
Original file line numberDiff line numberDiff line change
@@ -144,7 +144,7 @@ def build_model(xml, discard_visual, default_armature=None, merge_fixed_links=Fa
144144
compiler.attrib |= dict(
145145
fusestatic="false",
146146
strippath="false",
147-
inertiafromgeom="false", # This option is unreliable, so doing this ourselves
147+
inertiafromgeom="false",
148148
balanceinertia="false",
149149
discardvisual="true" if discard_visual else "false",
150150
autolimits="true",
@@ -173,7 +173,7 @@ def build_model(xml, discard_visual, default_armature=None, merge_fixed_links=Fa
173173
# Special treatment for URDF
174174
if is_urdf_file:
175175
# Discard placeholder inertias that were used to avoid parsing failure
176-
for i, link in enumerate(robot.links):
176+
for link in robot.links:
177177
if link.inertial is None:
178178
body = mj.body(link.name)
179179
body.inertia[:] = 0.0

genesis/utils/usd/usd_geometry.py

Lines changed: 1 addition & 1 deletion
Original file line numberDiff line numberDiff line change
@@ -53,7 +53,7 @@ def parse_prim_geoms(
5353

5454
if link_prim is not None and prim.IsA(UsdGeom.Gprim):
5555
# parse materials
56-
geom_surface, geom_uvname, surface_id, bake_success = context.apply_surface(prim, surface)
56+
geom_surface, geom_uvname, _surface_id, bake_success = context.apply_surface(prim, surface)
5757
gprim = UsdGeom.Gprim(prim)
5858
uvs = {geom_uvname: None}
5959

genesis/utils/usd/usd_rigid_entity.py

Lines changed: 4 additions & 8 deletions
Original file line numberDiff line numberDiff line change
@@ -94,11 +94,6 @@ def _parse_link(
9494
l_info["inertial_quat"] = usd_quat_to_numpy(mass_api.GetPrincipalAxesAttr().Get())
9595
l_info["inertial_i"] = np.diag(usd_pos_to_numpy(mass_api.GetDiagonalInertiaAttr().Get()))
9696
l_info["inertial_mass"] = float(mass_api.GetMassAttr().Get() or 0.0)
97-
else:
98-
l_info["inertial_pos"] = gu.zero_pos()
99-
l_info["inertial_quat"] = gu.identity_quat()
100-
l_info["inertial_i"] = None
101-
l_info["inertial_mass"] = None
10297

10398
j_infos = []
10499
for joint_prim, parent_idx, is_body1 in joints:
@@ -310,10 +305,11 @@ def _parse_link(
310305

311306
if abs(1.0 - morph.scale) > gs.EPS:
312307
l_info["pos"] *= morph.scale
313-
l_info["inertial_pos"] *= morph.scale
314-
if l_info["inertial_mass"] is not None:
308+
if l_info.get("inertial_pos") is not None:
309+
l_info["inertial_pos"] *= morph.scale
310+
if l_info.get("inertial_mass") is not None:
315311
l_info["inertial_mass"] *= morph.scale**3
316-
if l_info["inertial_i"] is not None:
312+
if l_info.get("inertial_i") is not None:
317313
l_info["inertial_i"] *= morph.scale**5
318314
l_info["invweight"][:] = -1.0
319315
for j_info in j_infos:

0 commit comments

Comments
 (0)