File size: 9,575 Bytes
ee93ecd
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
1
2
3
4
5
6
7
8
9
10
11
12
13
14
15
16
17
18
19
20
21
22
23
24
25
26
27
28
29
30
31
32
33
34
35
36
37
38
39
40
41
42
43
44
45
46
47
48
49
50
51
52
53
54
55
56
57
58
59
60
61
62
63
64
65
66
67
68
69
70
71
72
73
74
75
76
77
78
79
80
81
82
83
84
85
86
87
88
89
90
91
92
93
94
95
96
97
98
99
100
101
102
103
104
105
106
107
108
109
110
111
112
113
114
115
116
117
118
119
120
121
122
123
124
125
126
127
128
129
130
131
132
133
134
135
136
137
138
139
140
141
142
143
144
145
146
147
148
149
150
151
152
153
154
155
156
157
158
159
160
161
162
163
164
165
166
167
168
169
170
171
172
173
174
175
176
177
178
179
180
181
182
183
184
185
186
187
188
189
190
191
192
193
194
195
196
197
198
199
200
201
202
203
204
205
206
207
208
209
210
211
212
213
214
215
216
217
218
219
220
221
222
223
224
225
226
227
228
229
230
231
232
233
234
235
236
237
238
239
240
241
242
243
244
245
246
247
248
249
250
251
252
253
254
255
256
257
258
259
260
261
262
263
264
265
266
267
268
269
270
271
272
273
274
275
276
277
278
279
280
281
282
283
284
285
"""Tests for EntityData."""

import mujoco
import pytest
import torch
from conftest import get_test_device

from mjlab.entity import Entity, EntityCfg
from mjlab.sim.sim import Simulation, SimulationCfg

FLOATING_BASE_XML = """
<mujoco>
  <worldbody>
    <body name="object" pos="0 0 1">
      <freejoint name="free_joint"/>
      <geom name="object_geom" type="box" size="0.1 0.1 0.1" rgba="0.3 0.3 0.8 1" mass="0.1"/>
    </body>
  </worldbody>
</mujoco>
"""


@pytest.fixture(scope="module")
def device():
  """Test device fixture."""
  return get_test_device()


def create_floating_base_entity():
  """Create a floating-base entity."""
  cfg = EntityCfg(spec_fn=lambda: mujoco.MjSpec.from_string(FLOATING_BASE_XML))
  return Entity(cfg)


def initialize_entity_with_sim(entity, device, num_envs=1):
  """Initialize an entity with a simulation."""
  model = entity.compile()
  sim_cfg = SimulationCfg()
  sim = Simulation(num_envs=num_envs, cfg=sim_cfg, model=model, device=device)
  entity.initialize(model, sim.model, sim.data, device)
  return entity, sim


def test_root_velocity_world_frame_roundtrip(device):
  """Test reading and writing root velocity is a no-op (world frame).

  Verifies that the API is consistent: if you write a velocity, read it
  back, and write it again, you get the same result. This ensures no
  unintended transformations happen in the read/write cycle.
  """
  entity = create_floating_base_entity()
  entity, sim = initialize_entity_with_sim(entity, device)

  pose = torch.tensor([0.0, 0.0, 1.0, 0.6, 0.2, 0.3, 0.7141], device=device).unsqueeze(
    0
  )
  entity.write_root_link_pose_to_sim(pose)

  vel_w = torch.tensor([1.0, 0.5, 0.0, 0.0, 0.3, 0.1], device=device).unsqueeze(0)
  entity.write_root_link_velocity_to_sim(vel_w)
  sim.forward()

  vel_w_read = entity.data.root_link_vel_w.clone()
  assert torch.allclose(vel_w_read, vel_w, atol=1e-4)

  entity.write_root_link_velocity_to_sim(vel_w_read)
  sim.forward()
  vel_w_after = entity.data.root_link_vel_w

  assert torch.allclose(vel_w_after, vel_w_read, atol=1e-4)


def test_root_velocity_frame_conversion(device):
  """Test angular velocity converts from world to body frame internally.

  The API accepts angular velocity in world frame, but MuJoCo's qvel
  stores it in body frame. This test verifies the conversion happens
  correctly by checking qvel directly.
  """
  from mjlab.utils.lab_api.math import (
    quat_apply_inverse,
  )

  entity = create_floating_base_entity()
  entity, sim = initialize_entity_with_sim(entity, device)

  quat_w = torch.tensor([0.6, 0.2, 0.3, 0.7141], device=device).unsqueeze(0)
  pose = torch.cat([torch.zeros(1, 3, device=device), quat_w], dim=-1)
  entity.write_root_link_pose_to_sim(pose)

  lin_vel_w = torch.tensor([1.0, 0.5, 0.2], device=device).unsqueeze(0)
  ang_vel_w = torch.tensor([0.1, 0.2, 0.3], device=device).unsqueeze(0)
  vel_w = torch.cat([lin_vel_w, ang_vel_w], dim=-1)
  entity.write_root_link_velocity_to_sim(vel_w)

  v_slice = entity.data.indexing.free_joint_v_adr
  qvel = sim.data.qvel[:, v_slice]

  assert torch.allclose(qvel[:, :3], lin_vel_w, atol=1e-5)

  expected_ang_vel_b = quat_apply_inverse(quat_w, ang_vel_w)
  assert torch.allclose(qvel[:, 3:], expected_ang_vel_b, atol=1e-5)


def test_write_velocity_uses_qpos_not_xquat(device):
  """Test write_root_velocity uses qpos (not stale xquat).

  Writing pose then velocity without forward() must work. This would fail
  if write_root_velocity used xquat (stale) instead of qpos (current).
  """
  entity = create_floating_base_entity()
  entity, sim = initialize_entity_with_sim(entity, device)

  initial_pose = torch.tensor(
    [0.0, 0.0, 1.0, 1.0, 0.0, 0.0, 0.0], device=device
  ).unsqueeze(0)
  entity.write_root_link_pose_to_sim(initial_pose)
  sim.forward()  # xquat now has identity orientation.

  # Write different orientation without forward() - xquat stale, qpos current.
  new_pose = torch.tensor(
    [0.0, 0.0, 1.0, 0.707, 0.0, 0.707, 0.0], device=device
  ).unsqueeze(0)
  vel_w = torch.tensor([1.0, 0.0, 0.0, 0.0, 1.0, 0.0], device=device).unsqueeze(0)

  entity.write_root_link_pose_to_sim(new_pose)
  entity.write_root_link_velocity_to_sim(vel_w)

  sim.forward()
  vel_w_read = entity.data.root_link_vel_w

  assert torch.allclose(vel_w_read, vel_w, atol=1e-4)


def test_read_requires_forward_to_be_current(device):
  """Test read properties are stale until forward() is called.

  Demonstrates why event order matters and why forward() is needed
  between writes and reads.
  """
  entity = create_floating_base_entity()
  entity, sim = initialize_entity_with_sim(entity, device)

  sim.forward()
  initial_pose = entity.data.root_link_pose_w.clone()

  new_pose = torch.tensor(
    [1.0, 2.0, 3.0, 0.707, 0.0, 0.707, 0.0], device=device
  ).unsqueeze(0)
  entity.write_root_link_pose_to_sim(new_pose)

  stale_pose = entity.data.root_link_pose_w
  assert torch.allclose(stale_pose, initial_pose, atol=1e-5)

  sim.forward()
  current_pose = entity.data.root_link_pose_w
  assert torch.allclose(current_pose, new_pose, atol=1e-4)
  assert not torch.allclose(current_pose, initial_pose, atol=1e-4)


@pytest.mark.parametrize(
  "property_name,expected_shape",
  [
    # Root properties.
    ("root_link_pose_w", (1, 7)),
    ("root_link_pos_w", (1, 3)),
    ("root_link_quat_w", (1, 4)),
    ("root_link_vel_w", (1, 6)),
    ("root_link_lin_vel_w", (1, 3)),
    ("root_link_ang_vel_w", (1, 3)),
    ("root_com_pose_w", (1, 7)),
    ("root_com_pos_w", (1, 3)),
    ("root_com_quat_w", (1, 4)),
    ("root_com_vel_w", (1, 6)),
    ("root_com_lin_vel_w", (1, 3)),
    ("root_com_ang_vel_w", (1, 3)),
    # Body properties (we only have 1 body in this test).
    ("body_link_pose_w", (1, 1, 7)),
    ("body_link_pos_w", (1, 1, 3)),
    ("body_link_quat_w", (1, 1, 4)),
    ("body_link_vel_w", (1, 1, 6)),
    ("body_com_pose_w", (1, 1, 7)),
    ("body_com_vel_w", (1, 1, 6)),
  ],
)
def test_entity_data_properties_accessible(device, property_name, expected_shape):
  """Test that all EntityData properties can be accessed without errors."""
  entity = create_floating_base_entity()
  entity, sim = initialize_entity_with_sim(entity, device)

  sim.forward()

  value = getattr(entity.data, property_name)
  assert value.shape == expected_shape, f"{property_name} has unexpected shape"


def test_entity_data_reset_clears_all_targets(device):
  """Test that EntityData.clear_state() zeros out all target buffers."""
  from pathlib import Path

  from mjlab.actuator.actuator import TransmissionType
  from mjlab.actuator.builtin_actuator import BuiltinMotorActuatorCfg
  from mjlab.entity import EntityArticulationInfoCfg

  xml_path = Path(__file__).parent / "fixtures" / "tendon_finger.xml"

  cfg = EntityCfg(
    spec_fn=lambda: mujoco.MjSpec.from_file(str(xml_path)),
    articulation=EntityArticulationInfoCfg(
      actuators=(
        BuiltinMotorActuatorCfg(
          target_names_expr=("finger_tendon",),
          transmission_type=TransmissionType.TENDON,
          effort_limit=10.0,
        ),
      )
    ),
  )
  entity = Entity(cfg)
  entity, sim = initialize_entity_with_sim(entity, device, num_envs=4)

  entity.data.joint_pos_target[:] = 1.0
  entity.data.joint_vel_target[:] = 2.0
  entity.data.joint_effort_target[:] = 3.0
  entity.data.tendon_len_target[:] = 4.0
  entity.data.tendon_vel_target[:] = 5.0
  entity.data.tendon_effort_target[:] = 6.0

  entity.data.clear_state()

  assert torch.all(entity.data.joint_pos_target == 0.0)
  assert torch.all(entity.data.joint_vel_target == 0.0)
  assert torch.all(entity.data.joint_effort_target == 0.0)
  assert torch.all(entity.data.tendon_len_target == 0.0)
  assert torch.all(entity.data.tendon_vel_target == 0.0)
  assert torch.all(entity.data.tendon_effort_target == 0.0)


def test_entity_data_reset_partial_envs(device):
  """Test that EntityData.clear_state() can reset specific environments."""
  from pathlib import Path

  from mjlab.actuator.actuator import TransmissionType
  from mjlab.actuator.builtin_actuator import BuiltinMotorActuatorCfg
  from mjlab.entity import EntityArticulationInfoCfg

  xml_path = Path(__file__).parent / "fixtures" / "tendon_finger.xml"

  cfg = EntityCfg(
    spec_fn=lambda: mujoco.MjSpec.from_file(str(xml_path)),
    articulation=EntityArticulationInfoCfg(
      actuators=(
        BuiltinMotorActuatorCfg(
          target_names_expr=("finger_tendon",),
          transmission_type=TransmissionType.TENDON,
          effort_limit=10.0,
        ),
      )
    ),
  )
  entity = Entity(cfg)
  entity, sim = initialize_entity_with_sim(entity, device, num_envs=4)

  entity.data.tendon_len_target[:] = 7.0
  entity.data.tendon_vel_target[:] = 8.0
  entity.data.tendon_effort_target[:] = 9.0

  env_ids = torch.tensor([1, 3], device=device)
  entity.data.clear_state(env_ids)

  assert torch.all(entity.data.tendon_len_target[0] == 7.0)
  assert torch.all(entity.data.tendon_len_target[1] == 0.0)
  assert torch.all(entity.data.tendon_len_target[2] == 7.0)
  assert torch.all(entity.data.tendon_len_target[3] == 0.0)

  assert torch.all(entity.data.tendon_vel_target[0] == 8.0)
  assert torch.all(entity.data.tendon_vel_target[1] == 0.0)
  assert torch.all(entity.data.tendon_vel_target[2] == 8.0)
  assert torch.all(entity.data.tendon_vel_target[3] == 0.0)

  assert torch.all(entity.data.tendon_effort_target[0] == 9.0)
  assert torch.all(entity.data.tendon_effort_target[1] == 0.0)
  assert torch.all(entity.data.tendon_effort_target[2] == 9.0)
  assert torch.all(entity.data.tendon_effort_target[3] == 0.0)