mujoco-react 0.1.0

This diff represents the content of publicly available package versions that have been released to one of the supported registries. The information contained in this diff is provided for informational purposes only and reflects changes between package versions as they appear in their respective public registries.
Files changed (42) hide show
  1. package/LICENSE +177 -0
  2. package/README.md +510 -0
  3. package/dist/index.d.ts +1080 -0
  4. package/dist/index.js +3518 -0
  5. package/dist/index.js.map +1 -0
  6. package/package.json +64 -0
  7. package/src/components/ContactListener.tsx +26 -0
  8. package/src/components/ContactMarkers.tsx +81 -0
  9. package/src/components/Debug.tsx +227 -0
  10. package/src/components/DragInteraction.tsx +227 -0
  11. package/src/components/FlexRenderer.tsx +102 -0
  12. package/src/components/IkGizmo.tsx +146 -0
  13. package/src/components/SceneLights.tsx +131 -0
  14. package/src/components/SceneRenderer.tsx +104 -0
  15. package/src/components/SelectionHighlight.tsx +69 -0
  16. package/src/components/TendonRenderer.tsx +84 -0
  17. package/src/components/TrajectoryPlayer.tsx +44 -0
  18. package/src/core/GenericIK.ts +339 -0
  19. package/src/core/MujocoCanvas.tsx +72 -0
  20. package/src/core/MujocoProvider.tsx +78 -0
  21. package/src/core/MujocoSimProvider.tsx +1201 -0
  22. package/src/core/SceneLoader.ts +275 -0
  23. package/src/hooks/useActuators.ts +36 -0
  24. package/src/hooks/useBodyState.ts +56 -0
  25. package/src/hooks/useContacts.ts +125 -0
  26. package/src/hooks/useCtrl.ts +40 -0
  27. package/src/hooks/useCtrlNoise.ts +59 -0
  28. package/src/hooks/useGamepad.ts +77 -0
  29. package/src/hooks/useGravityCompensation.ts +22 -0
  30. package/src/hooks/useJointState.ts +64 -0
  31. package/src/hooks/useKeyboardTeleop.ts +97 -0
  32. package/src/hooks/usePolicy.ts +56 -0
  33. package/src/hooks/useSensor.ts +83 -0
  34. package/src/hooks/useSitePosition.ts +62 -0
  35. package/src/hooks/useTrajectoryPlayer.ts +105 -0
  36. package/src/hooks/useTrajectoryRecorder.ts +97 -0
  37. package/src/hooks/useVideoRecorder.ts +82 -0
  38. package/src/index.ts +108 -0
  39. package/src/rendering/CapsuleGeometry.ts +35 -0
  40. package/src/rendering/GeomBuilder.ts +140 -0
  41. package/src/rendering/Reflector.ts +225 -0
  42. package/src/types.ts +619 -0
@@ -0,0 +1,275 @@
1
+ /**
2
+ * @license
3
+ * SPDX-License-Identifier: Apache-2.0
4
+ */
5
+
6
+ import { MujocoData, MujocoModel, MujocoModule } from '../types';
7
+ import { SceneConfig, SceneObject, XmlPatch } from '../types';
8
+
9
+ /**
10
+ * Reads a null-terminated C string from MuJoCo's WASM memory.
11
+ */
12
+ export function getName(mjModel: MujocoModel, address: number): string {
13
+ let name = '';
14
+ let idx = address;
15
+ let safety = 0;
16
+ while (mjModel.names[idx] !== 0 && safety < 100) {
17
+ name += String.fromCharCode(mjModel.names[idx++]);
18
+ safety++;
19
+ }
20
+ return name;
21
+ }
22
+
23
+ /**
24
+ * Find a site by name in the MuJoCo model. Returns -1 if not found.
25
+ */
26
+ export function findSiteByName(mjModel: MujocoModel, name: string): number {
27
+ for (let i = 0; i < mjModel.nsite; i++) {
28
+ if (getName(mjModel, mjModel.name_siteadr[i]).includes(name)) return i;
29
+ }
30
+ return -1;
31
+ }
32
+
33
+ /**
34
+ * Find an actuator by name in the MuJoCo model. Returns -1 if not found.
35
+ */
36
+ export function findActuatorByName(mjModel: MujocoModel, name: string): number {
37
+ for (let i = 0; i < mjModel.nu; i++) {
38
+ if (getName(mjModel, mjModel.name_actuatoradr[i]).includes(name)) return i;
39
+ }
40
+ return -1;
41
+ }
42
+
43
+ /**
44
+ * Find a keyframe by name in the MuJoCo model. Returns -1 if not found.
45
+ */
46
+ export function findKeyframeByName(mjModel: MujocoModel, name: string): number {
47
+ for (let i = 0; i < mjModel.nkey; i++) {
48
+ if (getName(mjModel, mjModel.name_keyadr[i]) === name) return i;
49
+ }
50
+ return -1;
51
+ }
52
+
53
+ /**
54
+ * Find a body by name in the MuJoCo model. Returns -1 if not found.
55
+ */
56
+ export function findBodyByName(mjModel: MujocoModel, name: string): number {
57
+ for (let i = 0; i < mjModel.nbody; i++) {
58
+ if (getName(mjModel, mjModel.name_bodyadr[i]) === name) return i;
59
+ }
60
+ return -1;
61
+ }
62
+
63
+ /**
64
+ * Find a joint by name in the MuJoCo model. Returns -1 if not found.
65
+ */
66
+ export function findJointByName(mjModel: MujocoModel, name: string): number {
67
+ for (let i = 0; i < mjModel.njnt; i++) {
68
+ if (getName(mjModel, mjModel.name_jntadr[i]) === name) return i;
69
+ }
70
+ return -1;
71
+ }
72
+
73
+ /**
74
+ * Find a geom by name in the MuJoCo model. Returns -1 if not found.
75
+ */
76
+ export function findGeomByName(mjModel: MujocoModel, name: string): number {
77
+ for (let i = 0; i < mjModel.ngeom; i++) {
78
+ if (getName(mjModel, mjModel.name_geomadr[i]) === name) return i;
79
+ }
80
+ return -1;
81
+ }
82
+
83
+ /**
84
+ * Find a sensor by name in the MuJoCo model. Returns -1 if not found.
85
+ */
86
+ export function findSensorByName(mjModel: MujocoModel, name: string): number {
87
+ for (let i = 0; i < mjModel.nsensor; i++) {
88
+ if (getName(mjModel, mjModel.name_sensoradr[i]) === name) return i;
89
+ }
90
+ return -1;
91
+ }
92
+
93
+ /**
94
+ * Find a tendon by name in the MuJoCo model. Returns -1 if not found.
95
+ */
96
+ export function findTendonByName(mjModel: MujocoModel, name: string): number {
97
+ for (let i = 0; i < (mjModel.ntendon ?? 0); i++) {
98
+ if (getName(mjModel, mjModel.name_tendonadr[i]) === name) return i;
99
+ }
100
+ return -1;
101
+ }
102
+
103
+ /**
104
+ * Convert a SceneObject config to MuJoCo XML.
105
+ */
106
+ function sceneObjectToXml(obj: SceneObject): string {
107
+ const joint = obj.freejoint ? '<freejoint/>' : '';
108
+ const pos = obj.position.map((v) => v.toFixed(3)).join(' ');
109
+ const size = obj.size.map((v) => v.toFixed(3)).join(' ');
110
+ const rgba = obj.rgba.join(' ');
111
+ const mass = obj.mass ? ` mass="${obj.mass}"` : '';
112
+ const friction = obj.friction ? ` friction="${obj.friction}"` : '';
113
+ const solref = obj.solref ? ` solref="${obj.solref}"` : '';
114
+ const solimp = obj.solimp ? ` solimp="${obj.solimp}"` : '';
115
+ const condim = obj.condim ? ` condim="${obj.condim}"` : '';
116
+ // Always set contype/conaffinity=1 so objects collide regardless of model defaults
117
+ return `<body name="${obj.name}" pos="${pos}">${joint}<geom type="${obj.type}" size="${size}" rgba="${rgba}" contype="1" conaffinity="1"${mass}${friction}${solref}${solimp}${condim}/></body>`;
118
+ }
119
+
120
+ interface LoadResult {
121
+ mjModel: MujocoModel;
122
+ mjData: MujocoData;
123
+ siteId: number;
124
+ gripperId: number;
125
+ }
126
+
127
+ /**
128
+ * Config-driven scene loader — replaces the old RobotLoader + patchSingleRobot approach.
129
+ */
130
+ export async function loadScene(
131
+ mujoco: MujocoModule,
132
+ config: SceneConfig,
133
+ onProgress?: (msg: string) => void
134
+ ): Promise<LoadResult> {
135
+ // 1. Clean up virtual filesystem
136
+ try { mujoco.FS.unmount('/working'); } catch { /* ignore */ }
137
+ try { mujoco.FS.mkdir('/working'); } catch { /* ignore */ }
138
+
139
+ const baseUrl =
140
+ config.baseUrl ||
141
+ `https://raw.githubusercontent.com/google-deepmind/mujoco_menagerie/main/${config.robotId}/`;
142
+
143
+ const downloaded = new Set<string>();
144
+ const queue: string[] = [config.sceneFile];
145
+ const parser = new DOMParser();
146
+
147
+ // 2. Download all model files
148
+ while (queue.length > 0) {
149
+ const fname = queue.shift()!;
150
+ if (downloaded.has(fname)) continue;
151
+ downloaded.add(fname);
152
+
153
+ onProgress?.(`Downloading ${fname}...`);
154
+
155
+ const res = await fetch(baseUrl + fname);
156
+ if (!res.ok) {
157
+ console.warn(`Failed to fetch ${fname}: ${res.status} ${res.statusText}`);
158
+ continue;
159
+ }
160
+
161
+ // Create virtual directory structure
162
+ const dirParts = fname.split('/');
163
+ dirParts.pop();
164
+ let currentPath = '/working';
165
+ for (const part of dirParts) {
166
+ currentPath += '/' + part;
167
+ try { mujoco.FS.mkdir(currentPath); } catch { /* ignore */ }
168
+ }
169
+
170
+ if (fname.endsWith('.xml')) {
171
+ let text = await res.text();
172
+
173
+ // 3. Apply XML patches from config
174
+ for (const patch of config.xmlPatches ?? []) {
175
+ if (fname.endsWith(patch.target) || fname === patch.target) {
176
+ if (patch.replace) {
177
+ text = text.replace(patch.replace[0], patch.replace[1]);
178
+ }
179
+ if (patch.inject && patch.injectAfter) {
180
+ const idx = text.indexOf(patch.injectAfter);
181
+ if (idx !== -1) {
182
+ // Find the end of the opening tag (next '>') after the match
183
+ const tagEnd = text.indexOf('>', idx + patch.injectAfter.length);
184
+ if (tagEnd !== -1) {
185
+ text = text.slice(0, tagEnd + 1) + patch.inject + text.slice(tagEnd + 1);
186
+ }
187
+ }
188
+ }
189
+ }
190
+ }
191
+
192
+ // 4. Inject scene objects into the scene file
193
+ if (fname === config.sceneFile && config.sceneObjects?.length) {
194
+ const xml = config.sceneObjects.map((obj) => sceneObjectToXml(obj)).join('');
195
+ text = text.replace('</worldbody>', xml + '</worldbody>');
196
+ }
197
+
198
+ mujoco.FS.writeFile(`/working/${fname}`, text);
199
+ scanDependencies(text, fname, parser, downloaded, queue);
200
+ } else {
201
+ const buffer = new Uint8Array(await res.arrayBuffer());
202
+ mujoco.FS.writeFile(`/working/${fname}`, buffer);
203
+ }
204
+ }
205
+
206
+ // 5. Load model
207
+ onProgress?.('Loading model...');
208
+ const mjModel = mujoco.MjModel.loadFromXML(`/working/${config.sceneFile}`);
209
+ const mjData = new mujoco.MjData(mjModel);
210
+
211
+ // 6. Find TCP site and gripper actuator
212
+ const siteId = findSiteByName(mjModel, config.tcpSiteName ?? 'tcp');
213
+ const gripperId = findActuatorByName(mjModel, config.gripperActuatorName ?? 'gripper');
214
+
215
+ // 7. Set initial pose
216
+ if (config.homeJoints) {
217
+ for (let i = 0; i < config.homeJoints.length; i++) {
218
+ mjData.ctrl[i] = config.homeJoints[i];
219
+ if (mjModel.actuator_trnid[2 * i + 1] === 1) {
220
+ const jointId = mjModel.actuator_trnid[2 * i];
221
+ if (jointId >= 0 && jointId < mjModel.njnt) {
222
+ const qposAdr = mjModel.jnt_qposadr[jointId];
223
+ mjData.qpos[qposAdr] = config.homeJoints[i];
224
+ }
225
+ }
226
+ }
227
+ }
228
+
229
+ mujoco.mj_forward(mjModel, mjData);
230
+
231
+ return { mjModel, mjData, siteId, gripperId };
232
+ }
233
+
234
+ /**
235
+ * Scan XML for file dependencies (meshes, textures, includes).
236
+ */
237
+ function scanDependencies(
238
+ xmlString: string,
239
+ currentFile: string,
240
+ parser: DOMParser,
241
+ downloaded: Set<string>,
242
+ queue: string[]
243
+ ) {
244
+ const xmlDoc = parser.parseFromString(xmlString, 'text/xml');
245
+
246
+ const compiler = xmlDoc.querySelector('compiler');
247
+ const meshDir = compiler?.getAttribute('meshdir') || '';
248
+ const textureDir = compiler?.getAttribute('texturedir') || '';
249
+ const currentDir = currentFile.includes('/')
250
+ ? currentFile.substring(0, currentFile.lastIndexOf('/') + 1)
251
+ : '';
252
+
253
+ xmlDoc.querySelectorAll('[file]').forEach((el) => {
254
+ const fileAttr = el.getAttribute('file');
255
+ if (!fileAttr) return;
256
+
257
+ let prefix = '';
258
+ if (el.tagName.toLowerCase() === 'mesh') {
259
+ prefix = meshDir ? meshDir + '/' : '';
260
+ } else if (['texture', 'hfield'].includes(el.tagName.toLowerCase())) {
261
+ prefix = textureDir ? textureDir + '/' : '';
262
+ }
263
+
264
+ let fullPath = (currentDir + prefix + fileAttr).replace(/\/\//g, '/');
265
+ const parts = fullPath.split('/');
266
+ const norm: string[] = [];
267
+ for (const p of parts) {
268
+ if (p === '..') norm.pop();
269
+ else if (p !== '.') norm.push(p);
270
+ }
271
+ fullPath = norm.join('/');
272
+
273
+ if (!downloaded.has(fullPath)) queue.push(fullPath);
274
+ });
275
+ }
@@ -0,0 +1,36 @@
1
+ /**
2
+ * @license
3
+ * SPDX-License-Identifier: Apache-2.0
4
+ */
5
+
6
+ import { useMemo } from 'react';
7
+ import { useMujocoSim } from '../core/MujocoSimProvider';
8
+ import { getName } from '../core/SceneLoader';
9
+ import type { ActuatorInfo } from '../types';
10
+
11
+ /**
12
+ * Returns a stable array of actuator metadata for building control UIs.
13
+ * Computed once when the model loads. Consumer reads/writes data.ctrl[id] directly.
14
+ */
15
+ export function useActuators(): ActuatorInfo[] {
16
+ const { mjModelRef, status } = useMujocoSim();
17
+
18
+ return useMemo(() => {
19
+ if (status !== 'ready') return [];
20
+ const model = mjModelRef.current;
21
+ if (!model) return [];
22
+
23
+ const actuators: ActuatorInfo[] = [];
24
+ for (let i = 0; i < model.nu; i++) {
25
+ const name = getName(model, model.name_actuatoradr[i]);
26
+ const lo = model.actuator_ctrlrange[i * 2];
27
+ const hi = model.actuator_ctrlrange[i * 2 + 1];
28
+ const hasRange = lo < hi;
29
+ const range: [number, number] = hasRange
30
+ ? [lo, hi]
31
+ : [-Infinity, Infinity];
32
+ actuators.push({ id: i, name, range });
33
+ }
34
+ return actuators;
35
+ }, [status, mjModelRef]);
36
+ }
@@ -0,0 +1,56 @@
1
+ /**
2
+ * @license
3
+ * SPDX-License-Identifier: Apache-2.0
4
+ *
5
+ * useBodyState — per-body position/velocity tracking (spec 2.2)
6
+ */
7
+
8
+ import { useEffect, useRef } from 'react';
9
+ import * as THREE from 'three';
10
+ import { useMujocoSim, useAfterPhysicsStep } from '../core/MujocoSimProvider';
11
+ import { findBodyByName } from '../core/SceneLoader';
12
+ import type { BodyStateResult } from '../types';
13
+
14
+ /**
15
+ * Track a MuJoCo body's world position, quaternion, and velocities.
16
+ * All values are ref-based — updated every physics frame without re-renders.
17
+ */
18
+ export function useBodyState(name: string): BodyStateResult {
19
+ const { mjModelRef, status } = useMujocoSim();
20
+ const bodyIdRef = useRef(-1);
21
+ const position = useRef(new THREE.Vector3());
22
+ const quaternion = useRef(new THREE.Quaternion());
23
+ const linearVelocity = useRef(new THREE.Vector3());
24
+ const angularVelocity = useRef(new THREE.Vector3());
25
+
26
+ useEffect(() => {
27
+ const model = mjModelRef.current;
28
+ if (!model || status !== 'ready') return;
29
+ bodyIdRef.current = findBodyByName(model, name);
30
+ }, [name, status, mjModelRef]);
31
+
32
+ useAfterPhysicsStep((_model, data) => {
33
+ const bid = bodyIdRef.current;
34
+ if (bid < 0) return;
35
+
36
+ // Position from xpos (3 per body)
37
+ const i3 = bid * 3;
38
+ position.current.set(data.xpos[i3], data.xpos[i3 + 1], data.xpos[i3 + 2]);
39
+
40
+ // Quaternion from xquat (4 per body, MuJoCo order: w,x,y,z)
41
+ const i4 = bid * 4;
42
+ quaternion.current.set(
43
+ data.xquat[i4 + 1], data.xquat[i4 + 2],
44
+ data.xquat[i4 + 3], data.xquat[i4]
45
+ );
46
+
47
+ // Velocity from cvel (6 per body: [angular(3), linear(3)])
48
+ if (data.cvel) {
49
+ const i6 = bid * 6;
50
+ angularVelocity.current.set(data.cvel[i6], data.cvel[i6 + 1], data.cvel[i6 + 2]);
51
+ linearVelocity.current.set(data.cvel[i6 + 3], data.cvel[i6 + 4], data.cvel[i6 + 5]);
52
+ }
53
+ });
54
+
55
+ return { position, quaternion, linearVelocity, angularVelocity };
56
+ }
@@ -0,0 +1,125 @@
1
+ /**
2
+ * @license
3
+ * SPDX-License-Identifier: Apache-2.0
4
+ *
5
+ * useContacts — structured contact query hook (spec 2.4)
6
+ * useContactEvents — contact enter/exit events (spec 2.5)
7
+ */
8
+
9
+ import { useCallback, useEffect, useRef } from 'react';
10
+ import { useMujocoSim, useAfterPhysicsStep } from '../core/MujocoSimProvider';
11
+ import { findBodyByName, getName } from '../core/SceneLoader';
12
+ import type { ContactInfo } from '../types';
13
+
14
+ /**
15
+ * Track contacts for a specific body (or all contacts if no body specified).
16
+ * Calls the callback every physics frame with current contact list.
17
+ * Reads `data.ncon` first to avoid allocating for zero contacts.
18
+ */
19
+ export function useContacts(
20
+ bodyName?: string,
21
+ callback?: (contacts: ContactInfo[]) => void,
22
+ ): React.RefObject<ContactInfo[]> {
23
+ const { mjModelRef } = useMujocoSim();
24
+ const contactsRef = useRef<ContactInfo[]>([]);
25
+ const bodyIdRef = useRef(-1);
26
+ const callbackRef = useRef(callback);
27
+ callbackRef.current = callback;
28
+
29
+ useEffect(() => {
30
+ if (!bodyName) { bodyIdRef.current = -1; return; }
31
+ const model = mjModelRef.current;
32
+ if (!model) return;
33
+ bodyIdRef.current = findBodyByName(model, bodyName);
34
+ }, [bodyName, mjModelRef]);
35
+
36
+ useAfterPhysicsStep((model, data) => {
37
+ const ncon = data.ncon;
38
+ if (ncon === 0) {
39
+ if (contactsRef.current.length > 0) contactsRef.current = [];
40
+ callbackRef.current?.([]);
41
+ return;
42
+ }
43
+
44
+ const contacts: ContactInfo[] = [];
45
+ const filterBody = bodyIdRef.current;
46
+
47
+ for (let i = 0; i < ncon; i++) {
48
+ try {
49
+ const c = (data.contact as { get(i: number): { geom1: number; geom2: number; pos: Float64Array; dist: number } }).get(i);
50
+ // Filter by body if specified
51
+ if (filterBody >= 0) {
52
+ const b1 = model.geom_bodyid[c.geom1];
53
+ const b2 = model.geom_bodyid[c.geom2];
54
+ if (b1 !== filterBody && b2 !== filterBody) continue;
55
+ }
56
+ contacts.push({
57
+ geom1: c.geom1,
58
+ geom1Name: getName(model, model.name_geomadr[c.geom1]),
59
+ geom2: c.geom2,
60
+ geom2Name: getName(model, model.name_geomadr[c.geom2]),
61
+ pos: [c.pos[0], c.pos[1], c.pos[2]],
62
+ depth: c.dist,
63
+ });
64
+ } catch {
65
+ break;
66
+ }
67
+ }
68
+ contactsRef.current = contacts;
69
+ callbackRef.current?.(contacts);
70
+ });
71
+
72
+ return contactsRef;
73
+ }
74
+
75
+ /**
76
+ * Contact enter/exit events for a specific body (spec 2.5).
77
+ * Tracks which geom pairs are in contact frame-to-frame and fires
78
+ * onEnter/onExit callbacks on transitions.
79
+ */
80
+ export function useContactEvents(
81
+ bodyName: string,
82
+ handlers: {
83
+ onEnter?: (info: ContactInfo) => void;
84
+ onExit?: (info: ContactInfo) => void;
85
+ },
86
+ ) {
87
+ const prevPairsRef = useRef(new Set<string>());
88
+ const onEnterRef = useRef(handlers.onEnter);
89
+ const onExitRef = useRef(handlers.onExit);
90
+ onEnterRef.current = handlers.onEnter;
91
+ onExitRef.current = handlers.onExit;
92
+
93
+ const prevContactMapRef = useRef(new Map<string, ContactInfo>());
94
+
95
+ const onContacts = useCallback((contacts: ContactInfo[]) => {
96
+ const currentPairs = new Set<string>();
97
+ const currentMap = new Map<string, ContactInfo>();
98
+
99
+ for (const c of contacts) {
100
+ const key = `${Math.min(c.geom1, c.geom2)}_${Math.max(c.geom1, c.geom2)}`;
101
+ currentPairs.add(key);
102
+ currentMap.set(key, c);
103
+ }
104
+
105
+ // New contacts (enter)
106
+ for (const key of currentPairs) {
107
+ if (!prevPairsRef.current.has(key)) {
108
+ onEnterRef.current?.(currentMap.get(key)!);
109
+ }
110
+ }
111
+
112
+ // Lost contacts (exit)
113
+ for (const key of prevPairsRef.current) {
114
+ if (!currentPairs.has(key)) {
115
+ const prev = prevContactMapRef.current.get(key);
116
+ if (prev) onExitRef.current?.(prev);
117
+ }
118
+ }
119
+
120
+ prevPairsRef.current = currentPairs;
121
+ prevContactMapRef.current = currentMap;
122
+ }, []);
123
+
124
+ useContacts(bodyName, onContacts);
125
+ }
@@ -0,0 +1,40 @@
1
+ /**
2
+ * @license
3
+ * SPDX-License-Identifier: Apache-2.0
4
+ *
5
+ * useCtrl — clean read/write access to a named actuator's ctrl value (spec 3.1)
6
+ */
7
+
8
+ import { useCallback, useEffect, useRef } from 'react';
9
+ import { useMujocoSim } from '../core/MujocoSimProvider';
10
+ import { findActuatorByName } from '../core/SceneLoader';
11
+
12
+ /**
13
+ * Access a single actuator's control value by name.
14
+ *
15
+ * Returns [currentValue, setValue]:
16
+ * - `currentValue` is a ref updated every frame (no re-renders).
17
+ * - `setValue` writes directly to `data.ctrl[actuatorId]`.
18
+ */
19
+ export function useCtrl(name: string): [React.RefObject<number>, (value: number) => void] {
20
+ const { mjModelRef, mjDataRef, status } = useMujocoSim();
21
+ const actuatorIdRef = useRef(-1);
22
+ const valueRef = useRef(0);
23
+
24
+ useEffect(() => {
25
+ const model = mjModelRef.current;
26
+ if (!model || status !== 'ready') return;
27
+ actuatorIdRef.current = findActuatorByName(model, name);
28
+ }, [name, status, mjModelRef]);
29
+
30
+ // Read current value each frame (via afterStep would be ideal but
31
+ // useCtrl is primarily for writing; reading can use the ref)
32
+ const setValue = useCallback((value: number) => {
33
+ const data = mjDataRef.current;
34
+ if (!data || actuatorIdRef.current < 0) return;
35
+ data.ctrl[actuatorIdRef.current] = value;
36
+ valueRef.current = value;
37
+ }, [mjDataRef]);
38
+
39
+ return [valueRef, setValue];
40
+ }
@@ -0,0 +1,59 @@
1
+ /**
2
+ * @license
3
+ * SPDX-License-Identifier: Apache-2.0
4
+ *
5
+ * useCtrlNoise — control noise / perturbation hook (spec 3.2)
6
+ */
7
+
8
+ import { useRef } from 'react';
9
+ import { useMujocoSim, useBeforePhysicsStep } from '../core/MujocoSimProvider';
10
+
11
+ interface CtrlNoiseConfig {
12
+ /** Exponential filter rate (0-1). Higher = faster noise changes. Default: 0.01. */
13
+ rate?: number;
14
+ /** Standard deviation of Gaussian noise. Default: 0.05. */
15
+ std?: number;
16
+ /** Enable/disable. Default: true. */
17
+ enabled?: boolean;
18
+ }
19
+
20
+ /**
21
+ * Apply Gaussian noise with exponential filtering to all ctrl values.
22
+ * Useful for robustness testing and domain randomization.
23
+ *
24
+ * noise[i] = (1 - rate) * noise[i] + rate * N(0, std)
25
+ * data.ctrl[i] += noise[i]
26
+ */
27
+ export function useCtrlNoise(config: CtrlNoiseConfig = {}) {
28
+ const { mjModelRef } = useMujocoSim();
29
+ const configRef = useRef(config);
30
+ configRef.current = config;
31
+ const noiseRef = useRef<Float64Array | null>(null);
32
+
33
+ useBeforePhysicsStep((_model, data) => {
34
+ const cfg = configRef.current;
35
+ if (cfg.enabled === false) return;
36
+
37
+ const rate = cfg.rate ?? 0.01;
38
+ const std = cfg.std ?? 0.05;
39
+ const nu = mjModelRef.current?.nu ?? 0;
40
+ if (nu === 0) return;
41
+
42
+ // Initialize noise buffer
43
+ if (!noiseRef.current || noiseRef.current.length !== nu) {
44
+ noiseRef.current = new Float64Array(nu);
45
+ }
46
+
47
+ const noise = noiseRef.current;
48
+ for (let i = 0; i < nu; i++) {
49
+ // Box-Muller transform for Gaussian noise
50
+ const u1 = Math.random();
51
+ const u2 = Math.random();
52
+ const gaussian = Math.sqrt(-2 * Math.log(u1)) * Math.cos(2 * Math.PI * u2);
53
+
54
+ // Exponential filter
55
+ noise[i] = (1 - rate) * noise[i] + rate * gaussian * std;
56
+ data.ctrl[i] += noise[i];
57
+ }
58
+ });
59
+ }
@@ -0,0 +1,77 @@
1
+ /**
2
+ * @license
3
+ * SPDX-License-Identifier: Apache-2.0
4
+ *
5
+ * useGamepad — gamepad teleoperation hook (spec 12.2)
6
+ */
7
+
8
+ import { useEffect, useRef } from 'react';
9
+ import { useMujocoSim, useBeforePhysicsStep } from '../core/MujocoSimProvider';
10
+ import { findActuatorByName } from '../core/SceneLoader';
11
+
12
+ interface GamepadConfig {
13
+ /** Map gamepad axis index to actuator name. */
14
+ axes?: Record<number, string>;
15
+ /** Map gamepad button index to actuator name. */
16
+ buttons?: Record<number, string>;
17
+ /** Axis deadzone. Default: 0.1. */
18
+ deadzone?: number;
19
+ /** Scale factor for axis values. Default: 1.0. */
20
+ scale?: number;
21
+ /** Gamepad index. Default: 0 (first connected). */
22
+ gamepadIndex?: number;
23
+ enabled?: boolean;
24
+ }
25
+
26
+ /**
27
+ * Map gamepad axes and buttons to actuator controls.
28
+ * Axes map their -1..1 value (scaled) to the actuator.
29
+ * Buttons map their 0..1 pressed value to the actuator.
30
+ */
31
+ export function useGamepad(config: GamepadConfig) {
32
+ const { mjModelRef, status } = useMujocoSim();
33
+ const configRef = useRef(config);
34
+ configRef.current = config;
35
+
36
+ // Cache actuator IDs
37
+ const axisCacheRef = useRef(new Map<number, number>());
38
+ const buttonCacheRef = useRef(new Map<number, number>());
39
+
40
+ useEffect(() => {
41
+ const model = mjModelRef.current;
42
+ if (!model || status !== 'ready') return;
43
+ axisCacheRef.current.clear();
44
+ buttonCacheRef.current.clear();
45
+ for (const [idx, name] of Object.entries(config.axes ?? {})) {
46
+ axisCacheRef.current.set(Number(idx), findActuatorByName(model, name));
47
+ }
48
+ for (const [idx, name] of Object.entries(config.buttons ?? {})) {
49
+ buttonCacheRef.current.set(Number(idx), findActuatorByName(model, name));
50
+ }
51
+ }, [config.axes, config.buttons, status, mjModelRef]);
52
+
53
+ useBeforePhysicsStep((_model, data) => {
54
+ const cfg = configRef.current;
55
+ if (cfg.enabled === false) return;
56
+
57
+ const gamepads = navigator.getGamepads?.();
58
+ if (!gamepads) return;
59
+ const gp = gamepads[cfg.gamepadIndex ?? 0];
60
+ if (!gp) return;
61
+
62
+ const deadzone = cfg.deadzone ?? 0.1;
63
+ const scale = cfg.scale ?? 1.0;
64
+
65
+ for (const [axisIdx, actId] of axisCacheRef.current) {
66
+ if (actId < 0 || axisIdx >= gp.axes.length) continue;
67
+ let val = gp.axes[axisIdx];
68
+ if (Math.abs(val) < deadzone) val = 0;
69
+ data.ctrl[actId] = val * scale;
70
+ }
71
+
72
+ for (const [btnIdx, actId] of buttonCacheRef.current) {
73
+ if (actId < 0 || btnIdx >= gp.buttons.length) continue;
74
+ data.ctrl[actId] = gp.buttons[btnIdx].value;
75
+ }
76
+ });
77
+ }
@@ -0,0 +1,22 @@
1
+ /**
2
+ * @license
3
+ * SPDX-License-Identifier: Apache-2.0
4
+ */
5
+
6
+ import { useBeforePhysicsStep } from '../core/MujocoSimProvider';
7
+
8
+ /**
9
+ * Applies gravity compensation each physics frame by adding qfrc_bias
10
+ * (gravity + Coriolis forces) to qfrc_applied for each DOF.
11
+ *
12
+ * The provider zeros qfrc_applied at the start of each frame, so this
13
+ * hook (and DragInteraction) compose correctly — both add to a clean slate.
14
+ */
15
+ export function useGravityCompensation(enabled = true): void {
16
+ useBeforePhysicsStep((model, data) => {
17
+ if (!enabled) return;
18
+ for (let i = 0; i < model.nv; i++) {
19
+ data.qfrc_applied[i] += data.qfrc_bias[i];
20
+ }
21
+ });
22
+ }