Skip to content
Merged
Show file tree
Hide file tree
Changes from all commits
Commits
File filter

Filter by extension

Filter by extension

Conversations
Failed to load comments.
Loading
Jump to
Jump to file
Failed to load files.
Loading
Diff view
Diff view
11 changes: 8 additions & 3 deletions genesis/engine/couplers/ipc_coupler/coupler.py
Original file line number Diff line number Diff line change
Expand Up @@ -10,6 +10,7 @@

import genesis as gs
import genesis.utils.geom as gu
from genesis.engine.entities.rigid_entity.rigid_link import RHO_MUJOCO, RHO_OBJECT, RHO_ROBOT
from genesis.engine.materials.FEM.cloth import Cloth
from genesis.options.solvers import IPCCouplerOptions, RigidOptions
from genesis.repr_base import RBC
Expand Down Expand Up @@ -496,9 +497,13 @@ def _add_rigid_geoms_to_ipc(self) -> None:
self._ipc_abd = AffineBodyConstitution()
self._ipc_constitution_tabular.insert(self._ipc_abd)

self._ipc_abd.apply_to(
rigid_link_geom, kappa=ABD_KAPPA * uipc.unit.MPa, mass_density=entity.material.rho
)
rho = entity.material.rho
if rho is None:
if entity.solver._enable_mujoco_compatibility:
rho = RHO_MUJOCO
else:
rho = RHO_ROBOT if target_link._is_robot else RHO_OBJECT
self._ipc_abd.apply_to(rigid_link_geom, kappa=ABD_KAPPA * uipc.unit.MPa, mass_density=rho)

# Apply SoftTransformConstraint and animator for coupled links
if is_soft_constraint_target:
Expand Down
1 change: 1 addition & 0 deletions genesis/engine/entities/rigid_entity/rigid_entity.py
Original file line number Diff line number Diff line change
Expand Up @@ -2254,6 +2254,7 @@ def _add_by_info(self, l_info, j_infos, g_infos, morph, surface):
root_idx=root_idx,
invweight=l_info.get("invweight"),
visualize_contact=self.visualize_contact,
is_robot=l_info.get("is_robot", root_idx != -1),
)
self._links.append(link)

Expand Down
17 changes: 17 additions & 0 deletions genesis/engine/entities/rigid_entity/rigid_link.py
Original file line number Diff line number Diff line change
Expand Up @@ -20,6 +20,10 @@
from .rigid_joint import RigidJoint


RHO_OBJECT = 600.0
RHO_ROBOT = 1500.0
RHO_MUJOCO = 1000.0

# If mass is too small, we do not care much about spatial inertia discrepancy
MASS_EPS = 0.005
AABB_EPS = 0.002
Expand Down Expand Up @@ -596,6 +600,7 @@ def __init__(
root_idx: int | None,
invweight: float | None,
visualize_contact: bool,
is_robot: bool,
):
super().__init__(
entity,
Expand All @@ -612,6 +617,8 @@ def __init__(
root_idx,
)

self._is_robot: bool = is_robot

if self._is_fixed and not entity._batch_fixed_verts:
verts_state_start = fixed_verts_state_start
else:
Expand Down Expand Up @@ -681,6 +688,11 @@ def _build(self):

# Get material density
rho = self.entity.material.rho
if rho is None:
if self._solver._enable_mujoco_compatibility:
rho = RHO_MUJOCO
else:
rho = RHO_ROBOT if self._is_robot else RHO_OBJECT

# For heterogeneous links, only use the first variant's geoms for the hint.
if self._variant_geom_ranges is not None:
Expand Down Expand Up @@ -784,6 +796,11 @@ def _build(self):
# Compute per-variant inertial for heterogeneous links
if self._variant_geom_ranges is not None:
rho = self.entity.material.rho
if rho is None:
if self._solver._enable_mujoco_compatibility:
rho = RHO_MUJOCO
else:
rho = RHO_ROBOT if self._is_robot else RHO_OBJECT
self._variant_inertial = []
for v in range(len(self._variant_geom_ranges)):
if v == 0:
Expand Down
9 changes: 6 additions & 3 deletions genesis/engine/materials/rigid.py
Original file line number Diff line number Diff line change
Expand Up @@ -24,8 +24,11 @@ class Rigid(Kinematic["RigidEntity"]):

Parameters
----------
rho : float, optional
The density of the material used to compute mass. Default is 200.0.
rho : float or None, optional
The density of the material used to estimate mass if necessary. When None, the default depends on context:
1000 kg/m^3 if MuJoCo compatibility is enabled (``RigidOptions.enable_mujoco_compatibility``),
otherwise 600 kg/m^3 for basic rigid objects (mug, table...) vs 1500 kg/m^3 for poly-articulated
robots. Default is None.
friction : float, optional
Friction coefficient within the rigid solver. If None, a default of 1.0 may be used or parsed from file.
needs_coup : bool, optional
Expand Down Expand Up @@ -73,7 +76,7 @@ class Rigid(Kinematic["RigidEntity"]):
``IPCCouplerOptions.contact_resistance``. Default is None.
"""

rho: ValidFloat = 200.0
rho: ValidFloat | None = None
friction: Annotated[ValidFloat, Field(ge=0.01, le=5.0)] | None = None
needs_coup: StrictBool = True
coup_friction: NonNegativeFloat = 0.1
Expand Down
20 changes: 11 additions & 9 deletions genesis/engine/sensors/temperature.py
Original file line number Diff line number Diff line change
Expand Up @@ -155,12 +155,12 @@ def _qd_polygon_area_from_points_3d(
ny = gs.qd_float(0.0)
nz = gs.qd_float(0.0)
for i in range(n):
cx = cx + scratch[i_b, i, _ScratchIdx.GROUP_POS_X]
cy = cy + scratch[i_b, i, _ScratchIdx.GROUP_POS_Y]
cz = cz + scratch[i_b, i, _ScratchIdx.GROUP_POS_Z]
nx = nx + scratch[i_b, i, _ScratchIdx.GROUP_NORMAL_X]
ny = ny + scratch[i_b, i, _ScratchIdx.GROUP_NORMAL_Y]
nz = nz + scratch[i_b, i, _ScratchIdx.GROUP_NORMAL_Z]
cx = cx + qd.cast(scratch[i_b, i, _ScratchIdx.GROUP_POS_X], gs.qd_float)
cy = cy + qd.cast(scratch[i_b, i, _ScratchIdx.GROUP_POS_Y], gs.qd_float)
cz = cz + qd.cast(scratch[i_b, i, _ScratchIdx.GROUP_POS_Z], gs.qd_float)
nx = nx + qd.cast(scratch[i_b, i, _ScratchIdx.GROUP_NORMAL_X], gs.qd_float)
ny = ny + qd.cast(scratch[i_b, i, _ScratchIdx.GROUP_NORMAL_Y], gs.qd_float)
nz = nz + qd.cast(scratch[i_b, i, _ScratchIdx.GROUP_NORMAL_Z], gs.qd_float)
n_inv = gs.qd_float(1.0) / gs.qd_float(n)
cx, cy, cz = cx * n_inv, cy * n_inv, cz * n_inv
nx, ny, nz = nx * n_inv, ny * n_inv, nz * n_inv
Expand Down Expand Up @@ -279,7 +279,7 @@ def _kernel_compute_contact_areas(
else:
for k in range(count):
d = scratch[i_b, k, _ScratchIdx.GROUP_DEPTH]
group_area = group_area + d * qd.math.pi
group_area = group_area + d * qd.cast(qd.math.pi, gs.qd_float)

area_per_contact = group_area / (gs.qd_float(count) + eps)
for k in range(count):
Expand All @@ -290,7 +290,7 @@ def _kernel_compute_contact_areas(
@qd.func
def _qd_k_eff(k_a: gs.qd_float, k_b: gs.qd_float, eps: gs.qd_float) -> gs.qd_float:
"""Effective conductivity for series thermal resistance: 2*k_a*k_b/(k_a+k_b+eps)."""
return 2.0 * k_a * k_b / (k_a + k_b + eps)
return gs.qd_float(2.0) * k_a * k_b / (k_a + k_b + eps)


@qd.kernel(fastcache=True)
Expand Down Expand Up @@ -368,7 +368,9 @@ def _kernel_contact_heat(
cell_idx = ix * (ny * nz) + iy * nz + iz
T_cell = output[start + cell_idx, i_b]
area_base = contact_area[i_c, i_b] + eps
area = qd.max(area_base, qd.math.pi * dw * collider_state.contact_data.penetration[i_c, i_b])
area = qd.max(
area_base, qd.cast(qd.math.pi, gs.qd_float) * dw * collider_state.contact_data.penetration[i_c, i_b]
)
flux = k_eff * (T_other - T_cell) / (vol / area + eps)
Q_vol = flux * area / vol
delta_T = dt * Q_vol / rcp
Expand Down
6 changes: 3 additions & 3 deletions genesis/utils/raycast_qd.py
Original file line number Diff line number Diff line change
Expand Up @@ -162,7 +162,7 @@ def ray_triangle_intersection(
valid = False

if valid:
f = 1.0 / a
f = gs.qd_float(1.0) / a
s = ray_start - v0
u = f * s.dot(h)

Expand All @@ -185,7 +185,7 @@ def ray_triangle_intersection(
valid = False

if valid:
result = qd.math.vec4(t, u, v, 1.0)
result = qd.math.vec4(t, u, v, gs.qd_float(1.0))

return result

Expand Down Expand Up @@ -215,7 +215,7 @@ def ray_aabb_intersection(
tmin = qd.min(t1, t2)
tmax = qd.max(t1, t2)

t_near = qd.max(tmin.x, tmin.y, tmin.z, 0.0)
t_near = qd.max(tmin.x, tmin.y, tmin.z, gs.qd_float(0.0))
t_far = qd.min(tmax.x, tmax.y, tmax.z)

# Check if ray intersects AABB
Expand Down
2 changes: 1 addition & 1 deletion tests/test_hybrid.py
Original file line number Diff line number Diff line change
Expand Up @@ -228,7 +228,7 @@ def test_sap_rigid_rigid_hydroelastic_contact(show_viewer):

# All the entities must be still
for entity in scene.entities:
assert_allclose(entity.get_links_vel(), 0.0, atol=2e-2)
assert_allclose(entity.get_links_vel(), 0.0, atol=0.03)

# The box should stay at its initial position
assert_allclose(box.get_pos(), (0.0, 0.0, BOX_HALFHEIGHT), atol=2e-3)
Expand Down
3 changes: 3 additions & 0 deletions tests/test_ipc.py
Original file line number Diff line number Diff line change
Expand Up @@ -271,6 +271,7 @@ def test_ipc_rigid_ground_clearance(n_envs, show_viewer):
scene.add_entity(
gs.morphs.Plane(),
material=gs.materials.Rigid(
rho=200.0,
coup_type="ipc_only",
),
)
Expand All @@ -283,6 +284,7 @@ def test_ipc_rigid_ground_clearance(n_envs, show_viewer):
size=(0.08, 0.08, 0.08),
),
material=gs.materials.Rigid(
rho=200.0,
coup_type="ipc_only",
coup_friction=0.0,
contact_resistance=resistance,
Expand Down Expand Up @@ -1474,6 +1476,7 @@ def test_cloth_uniform_biaxial_stretching(E, nu, strech_scale, n_envs, show_view
),
),
material=gs.materials.Rigid(
rho=200.0,
coup_type="two_way_soft_constraint",
coup_friction=0.8,
),
Expand Down
1 change: 1 addition & 0 deletions tests/test_render.py
Original file line number Diff line number Diff line change
Expand Up @@ -395,6 +395,7 @@ def test_render_api_advanced(tmp_path, n_envs, show_viewer, png_snapshot, render
file="urdf/go2/urdf/go2.urdf",
merge_fixed_links=False,
),
material=gs.materials.Rigid(rho=200.0),
)
cam_debug = scene.add_camera(
res=(640, 480),
Expand Down
10 changes: 5 additions & 5 deletions tests/test_rigid_physics.py
Original file line number Diff line number Diff line change
Expand Up @@ -2251,11 +2251,10 @@ def test_frictionloss_advanced(show_viewer, tol):
assert_allclose(robot.get_contacts()["position"][:, 2].min(), 0.0, tol=1e-4)
assert_allclose(robot.get_AABB()[0, 2], 0.0, tol=2e-4)
box_pos = box.get_pos()
assert box_pos[0] > 0.5
# This is to check collision detection is working correctly on metal
# The box will collide with the robot and rolling on the ground,
# We check whether it's rolling within a reasonable range and not blowing up.
# Behavior on mdetial is different from other platforms
assert box_pos[0] > 0.4

# This is to check collision detection is working correctly on Apple Metal.
# The box should collide with the robot and roll on the ground within a reasonable range without not blow up.
assert_allclose(box_pos[1:], 0.0, tol=0.05)
assert_allclose(box.get_dofs_velocity(), 0.0, tol=50 * tol)

Expand Down Expand Up @@ -5164,6 +5163,7 @@ def test_heterogeneous_robots(show_viewer, tol):
het_obj = scene.add_entity(
morph=het_morph,
material=gs.materials.Rigid(
rho=200.0,
friction=1e-2,
),
)
Expand Down
Loading