mujoco-react 8.3.3 → 8.4.1

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.
package/package.json CHANGED
@@ -1,6 +1,6 @@
1
1
  {
2
2
  "name": "mujoco-react",
3
- "version": "8.3.3",
3
+ "version": "8.4.1",
4
4
  "description": "Composable React Three Fiber building blocks for MuJoCo WASM simulations",
5
5
  "type": "module",
6
6
  "main": "./dist/index.js",
@@ -41,10 +41,10 @@ export class GenericIK {
41
41
  * @param model MuJoCo model
42
42
  * @param data MuJoCo data (qpos will be temporarily modified, then restored)
43
43
  * @param siteId Index of the end-effector site to control
44
- * @param numJoints Number of arm joints (assumes qpos[0..numJoints-1])
44
+ * @param qposAdr qpos addresses for scalar joints in solve order
45
45
  * @param targetPos Target position in world frame
46
46
  * @param targetQuat Target orientation in world frame
47
- * @param currentQ Current joint angles (length = numJoints)
47
+ * @param currentQ Current joint angles matching qposAdr order
48
48
  * @param opts Optional solver parameters
49
49
  * @returns Joint angles array, or null if solver diverged
50
50
  */
@@ -52,14 +52,14 @@ export class GenericIK {
52
52
  model: MujocoModel,
53
53
  data: MujocoData,
54
54
  siteId: number,
55
- numJoints: number,
55
+ qposAdr: ArrayLike<number>,
56
56
  targetPos: THREE.Vector3,
57
57
  targetQuat: THREE.Quaternion,
58
- currentQ: number[],
58
+ currentQ: ArrayLike<number>,
59
59
  opts?: Partial<GenericIKOptions>
60
60
  ): number[] | null {
61
61
  const o = { ...DEFAULTS, ...opts };
62
- const n = numJoints;
62
+ const n = qposAdr.length;
63
63
 
64
64
  // Save full qpos so we can restore after solving
65
65
  const savedQpos = new Float64Array(data.qpos.length);
@@ -86,9 +86,11 @@ export class GenericIK {
86
86
  let bestQ: number[] | null = null;
87
87
  let bestErr = Infinity;
88
88
 
89
+ if (n === 0) return null;
90
+
89
91
  for (let iter = 0; iter < o.maxIterations; iter++) {
90
92
  // Set joints and run FK
91
- for (let i = 0; i < n; i++) data.qpos[i] = q[i];
93
+ for (let i = 0; i < n; i++) data.qpos[qposAdr[i]] = q[i];
92
94
  this.mujoco.mj_forward(model, data);
93
95
 
94
96
  // Read current site pose
@@ -130,8 +132,9 @@ export class GenericIK {
130
132
 
131
133
  // Compute Jacobian via finite differences
132
134
  for (let j = 0; j < n; j++) {
133
- const saved = data.qpos[j];
134
- data.qpos[j] = q[j] + o.epsilon;
135
+ const adr = qposAdr[j];
136
+ const saved = data.qpos[adr];
137
+ data.qpos[adr] = q[j] + o.epsilon;
135
138
  this.mujoco.mj_forward(model, data);
136
139
 
137
140
  for (let i = 0; i < 3; i++) pertSitePos[i] = sp[off3 + i];
@@ -150,11 +153,11 @@ export class GenericIK {
150
153
  J[5 * n + j] = (dRot[2] / o.epsilon) * o.rotWeight;
151
154
 
152
155
  // Restore joint
153
- data.qpos[j] = saved;
156
+ data.qpos[adr] = saved;
154
157
  }
155
158
 
156
159
  // Restore base FK state for next iteration
157
- for (let i = 0; i < n; i++) data.qpos[i] = q[i];
160
+ for (let i = 0; i < n; i++) data.qpos[qposAdr[i]] = q[i];
158
161
 
159
162
  // Damped least squares: Δq = Jᵀ (J Jᵀ + λI)⁻¹ error
160
163
  // 1. Compute JJᵀ (6×6)
@@ -6,7 +6,7 @@
6
6
  import loadMujoco from '@mujoco/mujoco';
7
7
  import defaultMujocoWasmUrl from '@mujoco/mujoco/mujoco.wasm?url';
8
8
  import { createContext, useContext, useEffect, useRef, useState } from 'react';
9
- import { MujocoModule, MujocoContextValue } from '../types';
9
+ import type { MujocoModule, MujocoContextValue } from '../types';
10
10
 
11
11
  const MujocoContext = createContext<MujocoContextValue>({
12
12
  mujoco: null,
@@ -21,19 +21,77 @@ export function useMujocoWasm(): MujocoContextValue {
21
21
  return useContext(MujocoContext);
22
22
  }
23
23
 
24
- interface MujocoProviderProps {
24
+ export type MujocoWasmVariant = 'single' | 'threaded' | 'auto';
25
+
26
+ export interface MujocoLoaderOptions {
27
+ locateFile?: (path: string) => string;
28
+ printErr?: (text: string) => void;
29
+ }
30
+
31
+ export type MujocoLoader = (options?: MujocoLoaderOptions) => Promise<unknown>;
32
+
33
+ export interface MujocoProviderProps {
25
34
  wasmUrl?: string;
35
+ /** Optional URL for the multi-threaded WASM asset. */
36
+ mtWasmUrl?: string;
37
+ /**
38
+ * Optional official multi-threaded loader, usually imported from
39
+ * `@mujoco/mujoco/mt`. It is supplied by the app so the default package path
40
+ * does not force every bundler to process the threaded Emscripten build.
41
+ */
42
+ threadedLoader?: MujocoLoader;
43
+ /**
44
+ * MuJoCo WASM build to load. `single` is the default and works everywhere.
45
+ * `threaded` requires `threadedLoader` and cross-origin isolation. `auto`
46
+ * uses threaded only when both conditions are satisfied.
47
+ */
48
+ wasmVariant?: MujocoWasmVariant;
26
49
  /** Timeout in ms for WASM module load. Default: 30000. */
27
50
  timeout?: number;
28
51
  children: React.ReactNode;
29
52
  onError?: (error: Error) => void;
30
53
  }
31
54
 
55
+ function canUseThreadedWasm(): boolean {
56
+ return typeof globalThis !== 'undefined' && globalThis.crossOriginIsolated === true;
57
+ }
58
+
59
+ function isMujocoModule(value: unknown): value is MujocoModule {
60
+ return typeof value === 'object'
61
+ && value !== null
62
+ && 'FS' in value
63
+ && 'MjModel' in value
64
+ && 'MjData' in value
65
+ && 'mj_step' in value;
66
+ }
67
+
68
+ function hasWasmUrl(value: string | undefined): value is string {
69
+ return typeof value === 'string' && value.length > 0;
70
+ }
71
+
72
+ function resolveWasmVariant(
73
+ variant: MujocoWasmVariant | undefined,
74
+ threadedLoader: MujocoLoader | undefined,
75
+ mtWasmUrl: string | undefined
76
+ ): 'single' | 'threaded' {
77
+ if (variant === 'threaded') return 'threaded';
78
+ if (variant === 'auto' && threadedLoader && mtWasmUrl && canUseThreadedWasm()) return 'threaded';
79
+ return 'single';
80
+ }
81
+
32
82
  /**
33
83
  * MujocoProvider — WASM / module lifecycle.
34
84
  * Loads the MuJoCo WASM module on mount and provides it to children via context.
35
85
  */
36
- export function MujocoProvider({ wasmUrl, timeout = 30000, children, onError }: MujocoProviderProps) {
86
+ export function MujocoProvider({
87
+ wasmUrl,
88
+ mtWasmUrl,
89
+ threadedLoader,
90
+ wasmVariant = 'single',
91
+ timeout = 30000,
92
+ children,
93
+ onError,
94
+ }: MujocoProviderProps) {
37
95
  const [status, setStatus] = useState<'loading' | 'ready' | 'error'>('loading');
38
96
  const [error, setError] = useState<string | null>(null);
39
97
  const moduleRef = useRef<MujocoModule | null>(null);
@@ -42,8 +100,31 @@ export function MujocoProvider({ wasmUrl, timeout = 30000, children, onError }:
42
100
  useEffect(() => {
43
101
  isMounted.current = true;
44
102
 
45
- const wasmPromise = loadMujoco({
46
- locateFile: (path: string) => path.endsWith('.wasm') ? (wasmUrl ?? defaultMujocoWasmUrl) : path,
103
+ const variant = resolveWasmVariant(wasmVariant, threadedLoader, mtWasmUrl);
104
+ if (variant === 'threaded' && !threadedLoader) {
105
+ const err = new Error('MujocoProvider wasmVariant="threaded" requires a threadedLoader from @mujoco/mujoco/mt');
106
+ setError(err.message);
107
+ setStatus('error');
108
+ onError?.(err);
109
+ return;
110
+ }
111
+ let selectedWasmUrl = wasmUrl ?? defaultMujocoWasmUrl;
112
+
113
+ if (variant === 'threaded') {
114
+ if (!hasWasmUrl(mtWasmUrl)) {
115
+ const err = new Error('MujocoProvider wasmVariant="threaded" requires mtWasmUrl from @mujoco/mujoco/mt/mujoco.wasm?url');
116
+ setError(err.message);
117
+ setStatus('error');
118
+ onError?.(err);
119
+ return;
120
+ }
121
+ selectedWasmUrl = mtWasmUrl;
122
+ }
123
+
124
+ const load: MujocoLoader = variant === 'threaded' && threadedLoader ? threadedLoader : loadMujoco;
125
+
126
+ const wasmPromise = load({
127
+ locateFile: (path: string) => path.endsWith('.wasm') ? selectedWasmUrl : path,
47
128
  printErr: (text: string) => {
48
129
  if (text.includes('Aborted') && isMounted.current) {
49
130
  setError('Simulation crashed. Reload page.');
@@ -59,7 +140,10 @@ export function MujocoProvider({ wasmUrl, timeout = 30000, children, onError }:
59
140
  Promise.race([wasmPromise, timeoutPromise])
60
141
  .then((inst: unknown) => {
61
142
  if (isMounted.current) {
62
- moduleRef.current = inst as MujocoModule;
143
+ if (!isMujocoModule(inst)) {
144
+ throw new Error('MuJoCo WASM module initialized with an unexpected shape');
145
+ }
146
+ moduleRef.current = inst;
63
147
  setStatus('ready');
64
148
  }
65
149
  })
@@ -75,7 +159,7 @@ export function MujocoProvider({ wasmUrl, timeout = 30000, children, onError }:
75
159
  return () => {
76
160
  isMounted.current = false;
77
161
  };
78
- }, [wasmUrl, timeout]);
162
+ }, [wasmUrl, mtWasmUrl, threadedLoader, wasmVariant, timeout, onError]);
79
163
 
80
164
  return (
81
165
  <MujocoContext.Provider
@@ -17,8 +17,11 @@ import * as THREE from 'three';
17
17
  import { MujocoData, MujocoModel, MujocoModule, getContact, withContacts } from '../types';
18
18
  import { SceneRenderer } from '../components/SceneRenderer';
19
19
  import {
20
+ ActuatedJointInfo,
20
21
  ActuatorInfo,
21
22
  BodyInfo,
23
+ ControlGroupInfo,
24
+ ControlGroupSelector,
22
25
  ContactInfo,
23
26
  GeomInfo,
24
27
  JointInfo,
@@ -40,7 +43,10 @@ import {
40
43
  findSensorByName,
41
44
  findActuatorByName,
42
45
  getActuatedScalarQposAdr,
46
+ getActuatedJoints as getActuatedJointsFromModel,
47
+ getControlMap as getControlMapFromModel,
43
48
  getName,
49
+ resolveControlGroup as resolveControlGroupFromModel,
44
50
  } from './SceneLoader';
45
51
 
46
52
  // ---- Joint type names ----
@@ -65,6 +71,24 @@ const SENSOR_TYPE_NAMES: Record<number, string> = {
65
71
  45: 'clock', 46: 'tactile', 47: 'plugin', 48: 'user',
66
72
  };
67
73
 
74
+ const EMPTY_CONTROL_GROUP: ControlGroupInfo = {
75
+ joints: [],
76
+ actuators: [],
77
+ qposAdr: [],
78
+ dofAdr: [],
79
+ ctrlAdr: [],
80
+ readQpos: () => new Float64Array(0),
81
+ readCtrl: () => new Float64Array(0),
82
+ writeQpos: () => {},
83
+ writeCtrl: () => {},
84
+ };
85
+
86
+ function isMutableApiRef(
87
+ ref: React.ForwardedRef<MujocoSimAPI>
88
+ ): ref is React.MutableRefObject<MujocoSimAPI | null> {
89
+ return typeof ref === 'object' && ref !== null && 'current' in ref;
90
+ }
91
+
68
92
  // Preallocated force/torque temps for applyForce/applyTorque
69
93
  const _applyForce = new Float64Array(3);
70
94
  const _applyTorque = new Float64Array(3);
@@ -329,8 +353,8 @@ export function MujocoSimProvider({
329
353
  if (externalApiRef) {
330
354
  if (typeof externalApiRef === 'function') {
331
355
  externalApiRef(api);
332
- } else {
333
- (externalApiRef as React.MutableRefObject<MujocoSimAPI | null>).current = api;
356
+ } else if (isMutableApiRef(externalApiRef)) {
357
+ externalApiRef.current = api;
334
358
  }
335
359
  }
336
360
  }
@@ -614,14 +638,14 @@ export function MujocoSimProvider({
614
638
  const result: JointInfo[] = [];
615
639
  for (let i = 0; i < model.njnt; i++) {
616
640
  const type = model.jnt_type[i];
617
- const limited = model.jnt_limited ? model.jnt_limited[i] !== 0 : false;
641
+ const range: [number, number] = [model.jnt_range[2 * i], model.jnt_range[2 * i + 1]];
618
642
  result.push({
619
643
  id: i,
620
644
  name: getName(model, model.name_jntadr[i]),
621
645
  type,
622
646
  typeName: JOINT_TYPE_NAMES[type] ?? `unknown(${type})`,
623
- range: [model.jnt_range[2 * i], model.jnt_range[2 * i + 1]],
624
- limited,
647
+ range,
648
+ limited: range[0] < range[1],
625
649
  bodyId: model.jnt_bodyid[i],
626
650
  qposAdr: model.jnt_qposadr[i],
627
651
  dofAdr: model.jnt_dofadr[i],
@@ -679,6 +703,21 @@ export function MujocoSimProvider({
679
703
  return result;
680
704
  }, []);
681
705
 
706
+ const getControlMapApi = useCallback((): ControlGroupInfo => {
707
+ const model = mjModelRef.current;
708
+ return model ? getControlMapFromModel(model) : EMPTY_CONTROL_GROUP;
709
+ }, []);
710
+
711
+ const getActuatedJointsApi = useCallback((): ActuatedJointInfo[] => {
712
+ const model = mjModelRef.current;
713
+ return model ? getActuatedJointsFromModel(model) : [];
714
+ }, []);
715
+
716
+ const resolveControlGroupApi = useCallback((selector: ControlGroupSelector): ControlGroupInfo | null => {
717
+ const model = mjModelRef.current;
718
+ return model ? resolveControlGroupFromModel(model, selector) : null;
719
+ }, []);
720
+
682
721
  const getSensors = useCallback((): SensorInfo[] => {
683
722
  const model = mjModelRef.current;
684
723
  if (!model) return [];
@@ -939,6 +978,9 @@ export function MujocoSimProvider({
939
978
  getQvel,
940
979
  setCtrl,
941
980
  getCtrl,
981
+ getControlMap: getControlMapApi,
982
+ getActuatedJoints: getActuatedJointsApi,
983
+ resolveControlGroup: resolveControlGroupApi,
942
984
  applyForce,
943
985
  applyTorque: applyTorqueApi,
944
986
  setExternalForce,
@@ -970,6 +1012,7 @@ export function MujocoSimProvider({
970
1012
  status, config, reset, setSpeed, togglePause, setPaused, step,
971
1013
  getTime, getTimestep, applyKeyframe, saveState, restoreState,
972
1014
  setQpos, setQvel, getQpos, getQvel, setCtrl, getCtrl,
1015
+ getControlMapApi, getActuatedJointsApi, resolveControlGroupApi,
973
1016
  applyForce, applyTorqueApi, setExternalForce, applyGeneralizedForce,
974
1017
  getSensorData, getContacts, getBodies, getJoints, getGeoms, getSites,
975
1018
  getActuatorsApi, getSensors, getModelOption, setGravity, setTimestepApi,
@@ -3,9 +3,27 @@
3
3
  * SPDX-License-Identifier: Apache-2.0
4
4
  */
5
5
 
6
- import { MujocoData, MujocoModel, MujocoModule } from '../types';
6
+ import type {
7
+ ActuatedJointInfo,
8
+ ActuatorInfo,
9
+ ControlGroupInfo,
10
+ ControlGroupSelector,
11
+ ControlJointInfo,
12
+ JointInfo,
13
+ MujocoData,
14
+ MujocoModel,
15
+ MujocoModule,
16
+ ResourceSelector,
17
+ } from '../types';
7
18
  import { SceneConfig, SceneObject, XmlPatch } from '../types';
8
19
 
20
+ const JOINT_TYPE_NAMES: Record<number, string> = {
21
+ 0: 'free',
22
+ 1: 'ball',
23
+ 2: 'slide',
24
+ 3: 'hinge',
25
+ };
26
+
9
27
  /**
10
28
  * Reads a null-terminated C string from MuJoCo's WASM memory.
11
29
  */
@@ -120,6 +138,330 @@ export function getActuatedScalarQposAdr(mjModel: MujocoModel, actuatorId: numbe
120
138
  return mjModel.jnt_qposadr[jointId];
121
139
  }
122
140
 
141
+ function getScalarJointDim(jointType: number): 0 | 1 {
142
+ return jointType === 2 || jointType === 3 ? 1 : 0;
143
+ }
144
+
145
+ function unlimitedRange(): [number, number] {
146
+ return [-Infinity, Infinity];
147
+ }
148
+
149
+ function isScalarJoint(mjModel: MujocoModel, jointId: number): boolean {
150
+ return jointId >= 0 && jointId < mjModel.njnt && getScalarJointDim(mjModel.jnt_type[jointId]) === 1;
151
+ }
152
+
153
+ function getActuatorJointId(mjModel: MujocoModel, actuatorId: number): number {
154
+ if (actuatorId < 0 || actuatorId >= mjModel.nu) return -1;
155
+ const trnType = mjModel.actuator_trntype?.[actuatorId];
156
+ if (trnType !== undefined && trnType !== 0 && trnType !== 1) return -1;
157
+ const jointId = mjModel.actuator_trnid[2 * actuatorId];
158
+ return isScalarJoint(mjModel, jointId) ? jointId : -1;
159
+ }
160
+
161
+ function getJointInfo(mjModel: MujocoModel, jointId: number): JointInfo {
162
+ const type = mjModel.jnt_type[jointId];
163
+ const range: [number, number] = [mjModel.jnt_range[2 * jointId], mjModel.jnt_range[2 * jointId + 1]];
164
+ return {
165
+ id: jointId,
166
+ name: getName(mjModel, mjModel.name_jntadr[jointId]),
167
+ type,
168
+ typeName: JOINT_TYPE_NAMES[type] ?? `unknown(${type})`,
169
+ range,
170
+ limited: range[0] < range[1],
171
+ bodyId: mjModel.jnt_bodyid[jointId],
172
+ qposAdr: mjModel.jnt_qposadr[jointId],
173
+ dofAdr: mjModel.jnt_dofadr[jointId],
174
+ };
175
+ }
176
+
177
+ function getActuatorInfo(mjModel: MujocoModel, actuatorId: number): ActuatorInfo {
178
+ const hasRange = mjModel.actuator_ctrlrange[2 * actuatorId] < mjModel.actuator_ctrlrange[2 * actuatorId + 1];
179
+ return {
180
+ id: actuatorId,
181
+ name: getName(mjModel, mjModel.name_actuatoradr[actuatorId]),
182
+ range: hasRange
183
+ ? [mjModel.actuator_ctrlrange[2 * actuatorId], mjModel.actuator_ctrlrange[2 * actuatorId + 1]]
184
+ : unlimitedRange(),
185
+ };
186
+ }
187
+
188
+ function includesResourceName(names: readonly string[], name: string): boolean {
189
+ return names.includes(name);
190
+ }
191
+
192
+ function matchesSelector<TInfo extends { name: string }, TName extends string>(
193
+ info: TInfo,
194
+ selector: ResourceSelector<TInfo, TName>
195
+ ): boolean {
196
+ if (typeof selector === 'string') return info.name === selector;
197
+ if (selector instanceof RegExp) return selector.test(info.name);
198
+ if (Array.isArray(selector)) return includesResourceName(selector, info.name);
199
+ if (typeof selector === 'function') return selector(info);
200
+ return false;
201
+ }
202
+
203
+ function orderedJointIdsFromSelector(
204
+ mjModel: MujocoModel,
205
+ selector: ResourceSelector<JointInfo, string>
206
+ ): number[] {
207
+ if (typeof selector === 'string') {
208
+ const id = findJointByName(mjModel, selector);
209
+ return id >= 0 && isScalarJoint(mjModel, id) ? [id] : [];
210
+ }
211
+ if (Array.isArray(selector)) {
212
+ return selector
213
+ .map((name) => findJointByName(mjModel, name))
214
+ .filter((id) => id >= 0 && isScalarJoint(mjModel, id));
215
+ }
216
+ const ids: number[] = [];
217
+ for (let i = 0; i < mjModel.njnt; i++) {
218
+ if (!isScalarJoint(mjModel, i)) continue;
219
+ const info = getJointInfo(mjModel, i);
220
+ if (matchesSelector(info, selector)) ids.push(i);
221
+ }
222
+ return ids;
223
+ }
224
+
225
+ function orderedActuatorIdsFromSelector(
226
+ mjModel: MujocoModel,
227
+ selector: ResourceSelector<ActuatorInfo, string>
228
+ ): number[] {
229
+ if (typeof selector === 'string') {
230
+ const id = findActuatorByName(mjModel, selector);
231
+ return id >= 0 && getActuatorJointId(mjModel, id) >= 0 ? [id] : [];
232
+ }
233
+ if (Array.isArray(selector)) {
234
+ return selector
235
+ .map((name) => findActuatorByName(mjModel, name))
236
+ .filter((id) => id >= 0 && getActuatorJointId(mjModel, id) >= 0);
237
+ }
238
+ const ids: number[] = [];
239
+ for (let i = 0; i < mjModel.nu; i++) {
240
+ if (getActuatorJointId(mjModel, i) < 0) continue;
241
+ const info = getActuatorInfo(mjModel, i);
242
+ if (matchesSelector(info, selector)) ids.push(i);
243
+ }
244
+ return ids;
245
+ }
246
+
247
+ function inferScalarJointChain(mjModel: MujocoModel, bodyId: number): number[] {
248
+ if (bodyId < 0 || bodyId >= mjModel.nbody) return [];
249
+ const chainByBody: number[][] = [];
250
+ let current = bodyId;
251
+ const seen = new Set<number>();
252
+
253
+ while (current >= 0 && current < mjModel.nbody && !seen.has(current)) {
254
+ seen.add(current);
255
+ const joints: number[] = [];
256
+ const jointCount = mjModel.body_jntnum[current] ?? 0;
257
+ const jointStart = mjModel.body_jntadr[current] ?? -1;
258
+ for (let i = 0; i < jointCount; i++) {
259
+ const jointId = jointStart + i;
260
+ if (isScalarJoint(mjModel, jointId)) joints.push(jointId);
261
+ }
262
+ if (joints.length) chainByBody.push(joints);
263
+ const parent = mjModel.body_parentid[current];
264
+ if (parent === current) break;
265
+ current = parent;
266
+ }
267
+
268
+ return chainByBody.reverse().flat();
269
+ }
270
+
271
+ function unique(values: number[]): number[] {
272
+ const seen = new Set<number>();
273
+ const result: number[] = [];
274
+ for (const value of values) {
275
+ if (seen.has(value)) continue;
276
+ seen.add(value);
277
+ result.push(value);
278
+ }
279
+ return result;
280
+ }
281
+
282
+ function findActuatorForJoint(mjModel: MujocoModel, jointId: number, preferredActuatorIds?: number[]): number {
283
+ const search = preferredActuatorIds ?? Array.from({ length: mjModel.nu }, (_, i) => i);
284
+ for (const actuatorId of search) {
285
+ if (getActuatorJointId(mjModel, actuatorId) === jointId) return actuatorId;
286
+ }
287
+ return -1;
288
+ }
289
+
290
+ function buildControlGroup(
291
+ mjModel: MujocoModel,
292
+ jointIds: number[],
293
+ preferredActuatorIds?: number[]
294
+ ): ControlGroupInfo | null {
295
+ const ids = unique(jointIds).filter((id) => isScalarJoint(mjModel, id));
296
+ if (!ids.length) return null;
297
+
298
+ const joints: ControlJointInfo[] = [];
299
+ const actuators: ActuatorInfo[] = [];
300
+ const qposAdr: number[] = [];
301
+ const dofAdr: number[] = [];
302
+ const ctrlAdr: number[] = [];
303
+
304
+ for (const jointId of ids) {
305
+ const actuatorId = findActuatorForJoint(mjModel, jointId, preferredActuatorIds);
306
+ const joint = getJointInfo(mjModel, jointId);
307
+ qposAdr.push(joint.qposAdr);
308
+ dofAdr.push(joint.dofAdr);
309
+
310
+ if (actuatorId >= 0) {
311
+ const actuator = getActuatorInfo(mjModel, actuatorId);
312
+ actuators.push(actuator);
313
+ ctrlAdr.push(actuatorId);
314
+ joints.push({
315
+ ...joint,
316
+ actuatorId,
317
+ actuatorName: actuator.name,
318
+ ctrlAdr: actuatorId,
319
+ ctrlRange: actuator.range,
320
+ });
321
+ } else {
322
+ joints.push({
323
+ ...joint,
324
+ actuatorId: null,
325
+ actuatorName: null,
326
+ ctrlAdr: null,
327
+ ctrlRange: null,
328
+ });
329
+ }
330
+ }
331
+
332
+ return {
333
+ joints,
334
+ actuators,
335
+ qposAdr,
336
+ dofAdr,
337
+ ctrlAdr,
338
+ readQpos(data: MujocoData) {
339
+ return new Float64Array(qposAdr.map((adr) => data.qpos[adr] ?? 0));
340
+ },
341
+ readCtrl(data: MujocoData) {
342
+ return new Float64Array(joints.map((joint) => joint.ctrlAdr === null ? 0 : data.ctrl[joint.ctrlAdr] ?? 0));
343
+ },
344
+ writeQpos(data: MujocoData, values: ArrayLike<number>) {
345
+ for (let i = 0; i < Math.min(values.length, qposAdr.length); i++) {
346
+ data.qpos[qposAdr[i]] = values[i];
347
+ }
348
+ },
349
+ writeCtrl(data: MujocoData, values: ArrayLike<number>) {
350
+ for (let i = 0; i < Math.min(values.length, joints.length); i++) {
351
+ const adr = joints[i].ctrlAdr;
352
+ if (adr !== null) data.ctrl[adr] = values[i];
353
+ }
354
+ },
355
+ };
356
+ }
357
+
358
+ export function getActuatedJoints(mjModel: MujocoModel): ActuatedJointInfo[] {
359
+ const result: ActuatedJointInfo[] = [];
360
+ for (let actuatorId = 0; actuatorId < mjModel.nu; actuatorId++) {
361
+ const jointId = getActuatorJointId(mjModel, actuatorId);
362
+ if (jointId < 0) continue;
363
+ const actuator = getActuatorInfo(mjModel, actuatorId);
364
+ result.push({
365
+ ...getJointInfo(mjModel, jointId),
366
+ actuatorId,
367
+ actuatorName: actuator.name,
368
+ ctrlAdr: actuatorId,
369
+ ctrlRange: actuator.range,
370
+ });
371
+ }
372
+ return result;
373
+ }
374
+
375
+ export function getControlMap(mjModel: MujocoModel): ControlGroupInfo {
376
+ const actuatorIds = Array.from({ length: mjModel.nu }, (_, i) => i)
377
+ .filter((id) => getActuatorJointId(mjModel, id) >= 0);
378
+ const jointIds = actuatorIds.map((id) => getActuatorJointId(mjModel, id));
379
+ return buildControlGroup(mjModel, jointIds, actuatorIds) ?? createContiguousControlGroup(mjModel, 0);
380
+ }
381
+
382
+ export function resolveControlGroup(
383
+ mjModel: MujocoModel,
384
+ selector: ControlGroupSelector
385
+ ): ControlGroupInfo | null {
386
+ if (selector.actuators) {
387
+ const actuatorIds = orderedActuatorIdsFromSelector(mjModel, selector.actuators);
388
+ const jointIds = actuatorIds.map((id) => getActuatorJointId(mjModel, id));
389
+ return buildControlGroup(mjModel, jointIds, actuatorIds);
390
+ }
391
+
392
+ if (selector.joints) {
393
+ return buildControlGroup(mjModel, orderedJointIdsFromSelector(mjModel, selector.joints));
394
+ }
395
+
396
+ if (selector.siteName) {
397
+ const siteId = findSiteByName(mjModel, selector.siteName);
398
+ const bodyId = siteId >= 0 ? (mjModel.site_bodyid?.[siteId] ?? -1) : -1;
399
+ return buildControlGroup(mjModel, inferScalarJointChain(mjModel, bodyId));
400
+ }
401
+
402
+ if (selector.bodyName) {
403
+ return buildControlGroup(mjModel, inferScalarJointChain(mjModel, findBodyByName(mjModel, selector.bodyName)));
404
+ }
405
+
406
+ return getControlMap(mjModel);
407
+ }
408
+
409
+ export function createContiguousControlGroup(mjModel: MujocoModel, count: number): ControlGroupInfo {
410
+ const n = Math.max(0, Math.min(count, mjModel.nq, mjModel.nu));
411
+ const joints: ControlJointInfo[] = [];
412
+ const actuators: ActuatorInfo[] = [];
413
+ const qposAdr: number[] = [];
414
+ const dofAdr: number[] = [];
415
+ const ctrlAdr: number[] = [];
416
+
417
+ for (let i = 0; i < n; i++) {
418
+ qposAdr.push(i);
419
+ dofAdr.push(i);
420
+ ctrlAdr.push(i);
421
+ const jointId = Array.from({ length: mjModel.njnt }, (_, id) => id)
422
+ .find((id) => mjModel.jnt_qposadr[id] === i);
423
+ const actuator = getActuatorInfo(mjModel, i);
424
+ actuators.push(actuator);
425
+ joints.push({
426
+ ...(jointId !== undefined ? getJointInfo(mjModel, jointId) : {
427
+ id: i,
428
+ name: `qpos${i}`,
429
+ type: 3,
430
+ typeName: 'hinge',
431
+ range: unlimitedRange(),
432
+ limited: false,
433
+ bodyId: -1,
434
+ qposAdr: i,
435
+ dofAdr: i,
436
+ }),
437
+ actuatorId: i,
438
+ actuatorName: actuator.name,
439
+ ctrlAdr: i,
440
+ ctrlRange: actuator.range,
441
+ });
442
+ }
443
+
444
+ return {
445
+ joints,
446
+ actuators,
447
+ qposAdr,
448
+ dofAdr,
449
+ ctrlAdr,
450
+ readQpos(data: MujocoData) {
451
+ return new Float64Array(qposAdr.map((adr) => data.qpos[adr] ?? 0));
452
+ },
453
+ readCtrl(data: MujocoData) {
454
+ return new Float64Array(ctrlAdr.map((adr) => data.ctrl[adr] ?? 0));
455
+ },
456
+ writeQpos(data: MujocoData, values: ArrayLike<number>) {
457
+ for (let i = 0; i < Math.min(values.length, qposAdr.length); i++) data.qpos[qposAdr[i]] = values[i];
458
+ },
459
+ writeCtrl(data: MujocoData, values: ArrayLike<number>) {
460
+ for (let i = 0; i < Math.min(values.length, ctrlAdr.length); i++) data.ctrl[ctrlAdr[i]] = values[i];
461
+ },
462
+ };
463
+ }
464
+
123
465
  /**
124
466
  * Convert a SceneObject config to MuJoCo XML.
125
467
  */