@operato/scene-manufacturing 10.0.0-beta.2 → 10.0.0-beta.22

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.
@@ -0,0 +1,971 @@
1
+ /*
2
+ * Copyright © HatioLab Inc. All rights reserved.
3
+ *
4
+ * Robot arm 3D — articulated chain renderer.
5
+ *
6
+ * Build pipeline:
7
+ * 1. Resolve chain (state.chain | preset | default 6-axis-industrial).
8
+ * 2. Resolve style (state.style preset, with per-property overrides).
9
+ * 3. Resolve joint values (state.joints array OR object map; missing
10
+ * entries default to 0 and clamp to chain[i].range).
11
+ * 4. If state.target is present, run CCDIK to solve joint values
12
+ * reaching that target; commit the solved values back via the
13
+ * smoothing controller (next tick converges to them).
14
+ * 5. Forward-kinematics walk → emit one Object3D per joint frame,
15
+ * each carrying its joint housing mesh + the link mesh extending
16
+ * along local +Z to the next frame.
17
+ * 6. Add gripper at the end-effector frame.
18
+ * 7. Optional reach sphere (wireframe).
19
+ *
20
+ * Joint frames are real Object3D children, so the rotation set via
21
+ * `frame.rotation.<axis> = jointValue` on each frame produces the right
22
+ * world-space pose without explicit matrix math at render time. CCDIK
23
+ * runs in matrix math (separate from this scene-graph walk) when needed.
24
+ */
25
+ import * as THREE from 'three';
26
+ import { RealObjectGroup, resolveMaterial3d, applyMaterial3dProps } from '@hatiolab/things-scene';
27
+ import { STYLES, CHAIN_PRESETS, DEFAULT_GRIPPER } from './robot-arm-styles.js';
28
+ import { solveCCDIK, maxReach, isSixAxisZYYZYZ, resolveBaseYaw, analyticalIk6Axis } from './robot-arm-ik.js';
29
+ const _AXIS_VEC = {
30
+ x: new THREE.Vector3(1, 0, 0),
31
+ y: new THREE.Vector3(0, 1, 0),
32
+ z: new THREE.Vector3(0, 0, 1)
33
+ };
34
+ const DEG2RAD = Math.PI / 180;
35
+ const RAD2DEG = 180 / Math.PI;
36
+ /**
37
+ * Length (chain-local units) of the virtual end-extension used to bias
38
+ * CCDIK toward "gripper pointing world-down". Longer = stronger orientation
39
+ * bias but reduces effective reach; shorter = closer to position-only.
40
+ * 30 is a moderate default that handles typical pick-and-place poses
41
+ * without sacrificing reach for normal-sized arms.
42
+ */
43
+ const DESCENT_BIAS = 30;
44
+ /** Raycast no-op — assigned to non-interactive helper meshes (e.g. the
45
+ * reach-sphere visualization) so clicks pass through to the real body. */
46
+ const NO_RAYCAST = () => { };
47
+ export class RobotArm3D extends RealObjectGroup {
48
+ _smoothing;
49
+ _animFrame;
50
+ _isAnimating = false;
51
+ _chain = [];
52
+ _jointFrames = [];
53
+ build() {
54
+ super.build();
55
+ const state = this.component.state;
56
+ // Geometry mapping (per user contract):
57
+ // width × height = robot footprint (the base pedestal occupies this)
58
+ // depth = robot height (= max reach when fully extended up)
59
+ //
60
+ // The chain preset's lengths are treated as PROPORTIONS — we scale them
61
+ // so the sum matches `effectiveDepth` (with a small base-height
62
+ // reservation). User can still override by passing absolute lengths via
63
+ // `state.chain[i].length`; the same scale is applied so `depth` stays
64
+ // the source of truth for overall robot height.
65
+ const baseHeight = this._baseHeight(state);
66
+ const targetReach = Math.max(this.effectiveDepth - baseHeight, 1);
67
+ const chain = this._resolveChain(state, targetReach);
68
+ const style = this._resolveStyle(state);
69
+ let joints = this._resolveJoints(chain, state);
70
+ // If a target is set, solve IK and use the solved joint values as the
71
+ // smoothing-controller's new target. CCDIK works in radians; convert
72
+ // both the input joints and the output back to user-facing units
73
+ // (degrees for revolute) before storing.
74
+ //
75
+ // CRITICAL: IK starts from smoothing.current (the visual joint pose
76
+ // mid-transit) when present, NOT from state-derived joints. CCDIK is
77
+ // path-dependent — different start poses converge to different valid
78
+ // solutions reaching the same TCP. If a rebuild happens DURING transit
79
+ // (e.g. `set('gripper', state:1)` closing the gripper after pick),
80
+ // re-solving from state joints (typically 0,0,0...) would produce a
81
+ // *different* solution than the path the arm was already on, snapping
82
+ // smoothing.target onto a new joint configuration. The arm — and any
83
+ // carried box — would then race toward that alternate solution,
84
+ // sometimes hitting `allReached` almost instantly (if the alternate
85
+ // happens to be close to current), which fires `tcp-reached`
86
+ // prematurely and makes pickAndPlace reparent the carrier to the
87
+ // place holder long before the arm has actually traveled there.
88
+ const target = state.target;
89
+ if (target && Number.isFinite(target.x) && Number.isFinite(target.y) && Number.isFinite(target.z)) {
90
+ const targetVec = new THREE.Vector3(target.x, target.y, target.z);
91
+ const targetYaw = Number.isFinite(target.yaw) ? target.yaw : undefined;
92
+ const ikStart = this._smoothing?.current?.slice() ?? joints;
93
+ const radJoints = this._toRadians(chain, ikStart);
94
+ const ikValues = this._solveIkDescent(chain, radJoints, targetVec, targetYaw);
95
+ const solvedUser = this._fromRadians(chain, ikValues);
96
+ this._smoothing = {
97
+ current: ikStart.slice(),
98
+ target: solvedUser.slice(),
99
+ speed: this._jointSpeed(state)
100
+ };
101
+ // visible position = current (interpolated by tick)
102
+ joints = ikStart.slice();
103
+ }
104
+ else if (this._smoothing) {
105
+ // no target — freeze where we are, NOT animate toward stale state
106
+ // joints (which may be 0,0,0... and unrelated to the visual pose).
107
+ this._smoothing.target = this._smoothing.current.slice();
108
+ }
109
+ this._chain = chain;
110
+ this._buildArm(chain, style, joints, baseHeight);
111
+ this._buildGripper(chain, style, state);
112
+ this._buildReachSphere(chain, state, baseHeight);
113
+ this._buildBase(state, style, baseHeight);
114
+ // Animation lifecycle (smooths joint values toward solved target).
115
+ this._stopAnimation();
116
+ if (this._smoothing) {
117
+ this._startAnimation();
118
+ }
119
+ // Re-mount any Carriable child whose object3d was orphaned by the
120
+ // build's `clear()`. Without this, ANY structural change while a
121
+ // carrier is held (most commonly the gripper-close `set('gripper',
122
+ // {state:1})` inside pickAndPlace) tears down `_endFrame` along with
123
+ // the carrier mounted onto it — the box vanishes mid-flight.
124
+ //
125
+ // The component-side child list survives a 3D rebuild (only the
126
+ // scene-graph was reset), so we walk it and re-execute the holder's
127
+ // attach-point policy. Uses `add()` (not `attach()`) because the
128
+ // orphaned object3d's matrixWorld is stale; we want the explicit
129
+ // localPosition/localRotation, not whatever world pose was last
130
+ // computed on the old gripper frame.
131
+ this._remountCarriers();
132
+ }
133
+ _remountCarriers() {
134
+ const holder = this.component;
135
+ if (typeof holder.attachPointFor !== 'function')
136
+ return;
137
+ const children = holder.components ?? holder.children ?? [];
138
+ for (const child of children) {
139
+ if (!child?.isCarriable)
140
+ continue;
141
+ const obj3d = child._realObject?.object3d;
142
+ if (!obj3d)
143
+ continue;
144
+ const point = holder.attachPointFor(child);
145
+ if (!point?.attach)
146
+ continue;
147
+ point.attach.add(obj3d);
148
+ const lp = point.localPosition ?? { x: 0, y: 0, z: 0 };
149
+ obj3d.position.set(lp.x, lp.y, lp.z);
150
+ if (point.localRotation) {
151
+ obj3d.rotation.set(point.localRotation.x, point.localRotation.y, point.localRotation.z);
152
+ }
153
+ else {
154
+ obj3d.quaternion.identity();
155
+ }
156
+ }
157
+ }
158
+ /**
159
+ * IK with a "point gripper downward" bias.
160
+ *
161
+ * CCDIK is position-only — it solves for joint values that put the
162
+ * end-effector at the target, without constraining the gripper's
163
+ * orientation. With no orientation constraint, valid solutions
164
+ * include twisted poses (gripper sideways / upside-down) — typical
165
+ * pick-and-place tasks then look broken: the box gets gripped at a
166
+ * wrong angle, or after release the carrier "launches" off because
167
+ * the gripper was facing some weird direction at the moment of
168
+ * release. The arm can also visibly "lock" near joint limits trying
169
+ * to satisfy a position-only target through a contorted path.
170
+ *
171
+ * Trick — augment the chain with a virtual rigid extension along the
172
+ * last frame's +Z, length L. When CCDIK puts this extended end at
173
+ * `target + L * (-Ẑ_chainLocal)` (i.e. the original target shifted
174
+ * downward by L in chain-local), the only way the chain can satisfy
175
+ * both placements simultaneously is by orienting the last frame's +Z
176
+ * to point in the chain-local -Z direction = world -Y direction =
177
+ * gripper pointing straight DOWN. Best-effort even when CCDIK can't
178
+ * fully converge — the solver pushes the chain in the right
179
+ * orientation, which matches what a real pick-and-place arm does.
180
+ */
181
+ _gripperTcpZ(style, state) {
182
+ const cfg = {
183
+ ...DEFAULT_GRIPPER,
184
+ ...(state.gripper ?? {}),
185
+ ...(state.gripperType ? { type: state.gripperType } : {})
186
+ };
187
+ if (cfg.type === 'none')
188
+ return 0;
189
+ const linkRadius = style.linkRadius;
190
+ switch (cfg.type) {
191
+ case 'parallel': {
192
+ const stroke = cfg.stroke ?? linkRadius * 1.8;
193
+ const fingerWidth = cfg.fingerWidth ?? linkRadius * 0.45;
194
+ const fingerLength = stroke * 1.2;
195
+ return fingerWidth * 1.8 + fingerLength;
196
+ }
197
+ case 'three-finger': {
198
+ const stroke = cfg.stroke ?? linkRadius * 1.5;
199
+ const fingerWidth = cfg.fingerWidth ?? linkRadius * 0.4;
200
+ const fingerLength = stroke * 1.2;
201
+ return fingerWidth * 1.5 + fingerLength;
202
+ }
203
+ case 'suction': {
204
+ const diameter = cfg.diameter ?? linkRadius * 2.4;
205
+ return diameter * 0.9;
206
+ }
207
+ case 'magnetic': {
208
+ const diameter = cfg.diameter ?? linkRadius * 2.6;
209
+ return diameter * 0.25;
210
+ }
211
+ }
212
+ return 0;
213
+ }
214
+ _solveIkDescent(chain, radJoints, targetVec, targetYaw) {
215
+ const state = this.component.state;
216
+ const style = this._resolveStyle(state);
217
+ const tcpZ = this._gripperTcpZ(style, state);
218
+ const augChain = chain.map((c, i) => i === chain.length - 1 ? { ...c, length: c.length + tcpZ } : c);
219
+ // Fast path: analytical IK for the standard 6-axis Z-Y-Y-Z-Y-Z chain
220
+ // (industrial + cobot presets). CCDIK is greedy and produces twisted
221
+ // poses; analytical IK is closed-form, deterministic, and gives the
222
+ // natural "elbow up, gripper straight down" pose every time.
223
+ //
224
+ // The implementation lives in `./robot-arm-ik.js` so the unit tests
225
+ // exercise THE SAME code that runs at scene-time. (An earlier version
226
+ // of this file kept a private duplicate, which silently drifted from
227
+ // the tested implementation — easy to introduce subtle bugs that
228
+ // tests miss.)
229
+ if (isSixAxisZYYZYZ(augChain)) {
230
+ const analytical = analyticalIk6Axis(augChain, targetVec, radJoints, targetYaw);
231
+ if (analytical)
232
+ return analytical;
233
+ }
234
+ const radChain = augChain.map((c, i) => {
235
+ const isLast = i === chain.length - 1;
236
+ const radRanges = c.type === 'revolute'
237
+ ? [c.range[0] * DEG2RAD, c.range[1] * DEG2RAD]
238
+ : c.range;
239
+ return {
240
+ ...c,
241
+ length: isLast ? c.length + DESCENT_BIAS : c.length,
242
+ range: radRanges
243
+ };
244
+ });
245
+ // Shift target downward (chain-local -Z = world -Y) by the bias length.
246
+ const augTarget = new THREE.Vector3(targetVec.x, targetVec.y, targetVec.z - DESCENT_BIAS);
247
+ // ── Lock joint 0 (base yaw) at the right value, run CCDIK on the rest ──
248
+ //
249
+ // CCDIK has two compounding weaknesses with joint 0 (base yaw, axis
250
+ // = chain-local Z):
251
+ //
252
+ // (a) Singularity when chain is straight along Z: v1 = tip - origin
253
+ // is parallel to the joint axis, projects to zero length on the
254
+ // perpendicular plane, and CCDIK SKIPs the joint entirely.
255
+ //
256
+ // (b) Even with the chain bent, CCDIK walking end→base may settle
257
+ // on a contorted solution where downstream joints (typically
258
+ // the wrist) compensate for an under-rotated joint 0 — the arm
259
+ // "self-pierces" reaching backwards over its own base instead
260
+ // of cleanly rotating to face the target.
261
+ //
262
+ // Fix: split into two phases.
263
+ // 1. Compute the base yaw analytically: `atan2(target.y, target.x)`
264
+ // — the unique angle that points the chain's pitch plane through
265
+ // the target.
266
+ // 2. Run CCDIK on the SUB-chain (joints 1..N-1) with a baseMatrix
267
+ // that already includes joint 0's rotation + the first link
268
+ // translation. Joint 0 is fixed — CCDIK can't unwind it.
269
+ //
270
+ // Result: base yaw is always correctly oriented, and the remaining
271
+ // joints handle pitch + wrist + descent bias on top of that.
272
+ const seedJoint0 = chain.length > 0 && chain[0].type === 'revolute' && chain[0].axis === 'z'
273
+ ? resolveBaseYaw(targetVec, radChain[0].range, radJoints[0] ?? 0)
274
+ : null;
275
+ if (seedJoint0 === null) {
276
+ // Chain doesn't have a Z-axis joint at index 0 (e.g. SCARA, prismatic
277
+ // first joint) — fall back to plain CCDIK on the full chain. The
278
+ // singularity above doesn't apply when joint 0 isn't around Z.
279
+ return solveCCDIK(radChain, radJoints, augTarget, undefined, {
280
+ maxIterations: 40,
281
+ damping: 0.5
282
+ }).values;
283
+ }
284
+ // Build base matrix: rotate around Z by seedJoint0, then translate
285
+ // along Z by chain[0].length (joint 0's link). This places the
286
+ // sub-chain's origin at frame 1.
287
+ const baseMatrix = new THREE.Matrix4()
288
+ .makeRotationZ(seedJoint0)
289
+ .multiply(new THREE.Matrix4().makeTranslation(0, 0, radChain[0].length));
290
+ const subChain = radChain.slice(1);
291
+ const subSeed = radJoints.slice(1);
292
+ const result = solveCCDIK(subChain, subSeed, augTarget, baseMatrix, {
293
+ maxIterations: 40,
294
+ damping: 0.5
295
+ });
296
+ return [seedJoint0, ...result.values];
297
+ }
298
+ // NOTE: `analyticalIk6Axis` and `resolveBaseYaw` previously lived as
299
+ // private duplicates here. They've been hoisted to `./robot-arm-ik.ts`
300
+ // so the unit tests in `test/ik-unit.test.mjs` exercise the same
301
+ // implementation that runs at scene-time. Don't reintroduce private
302
+ // copies — drift between "tested" and "shipping" code was a real
303
+ // source of bugs in this file's history.
304
+ // ─── Resolution helpers ──────────────────────────────────────────────
305
+ _resolveChain(state, targetReach) {
306
+ let raw;
307
+ if (Array.isArray(state.chain) && state.chain.length > 0) {
308
+ raw = state.chain;
309
+ }
310
+ else {
311
+ const presetName = (state.chainPreset ?? '6-axis-industrial');
312
+ raw = CHAIN_PRESETS[presetName] ?? CHAIN_PRESETS['6-axis-industrial'];
313
+ }
314
+ // Scale every link.length proportionally so the chain's total reach
315
+ // matches the requested depth. Preserves preset proportions (a SCARA
316
+ // stays SCARA-shaped at any depth). Prismatic ranges scale too —
317
+ // their travel distance is in the same length units.
318
+ const nominal = raw.reduce((s, c) => s + (c.length || 0), 0);
319
+ if (nominal <= 0)
320
+ return raw;
321
+ const scale = targetReach / nominal;
322
+ return raw.map(c => ({
323
+ ...c,
324
+ length: c.length * scale,
325
+ range: c.type === 'prismatic' ? [c.range[0] * scale, c.range[1] * scale] : c.range
326
+ }));
327
+ }
328
+ /**
329
+ * Base pedestal height — small reservation at the bottom of `depth` so
330
+ * the chain doesn't start at z=0 (which would clip into the floor).
331
+ * About 12% of depth, clamped to a sane range.
332
+ */
333
+ _baseHeight(state) {
334
+ const depth = this.effectiveDepth;
335
+ return Math.max(2, Math.min(depth * 0.12, 30));
336
+ }
337
+ /**
338
+ * Color resolution priority (high → low):
339
+ * 1. `state.fillStyle` → main link color (overrides style preset)
340
+ * 2. `state.color` → legacy / explicit hex int
341
+ * 3. style preset color
342
+ * Same for accent: state.strokeStyle → state.accentColor → preset accent.
343
+ * This way the user can keep a SCARA's box-link shape but recolor it via
344
+ * the standard fillStyle property without dropping into custom presets.
345
+ */
346
+ _resolveStyle(state) {
347
+ const baseStyle = STYLES[(state.style ?? 'industrial')] ?? STYLES.industrial;
348
+ return {
349
+ linkShape: state.linkShape ?? baseStyle.linkShape,
350
+ jointHousing: state.jointHousing ?? baseStyle.jointHousing,
351
+ color: pickColorish(state.fillStyle, state.color, baseStyle.color),
352
+ accentColor: pickColorish(state.strokeStyle, state.accentColor, baseStyle.accentColor),
353
+ linkRadius: typeof state.linkRadius === 'number' && Number.isFinite(state.linkRadius) && state.linkRadius > 0
354
+ ? state.linkRadius
355
+ : baseStyle.linkRadius
356
+ };
357
+ }
358
+ /**
359
+ * Resolution priority for each joint i:
360
+ * 1. state.jointN (e.g. state.joint0, state.joint1, ...) — written
361
+ * by the property panel's per-joint number inputs (one row per
362
+ * joint, range-clamped slider).
363
+ * 2. state.joints[i] — array form, useful for programmatic batch set.
364
+ * 3. state.joints[i] — object form ({0: v, 1: v, ...}).
365
+ * 4. 0 — fallback.
366
+ * Final value is range-clamped against the joint's own limits.
367
+ */
368
+ _resolveJoints(chain, state) {
369
+ const out = [];
370
+ const src = state.joints;
371
+ for (let i = 0; i < chain.length; i++) {
372
+ let v;
373
+ const flatKey = state[`joint${i}`];
374
+ if (Number.isFinite(flatKey)) {
375
+ v = flatKey;
376
+ }
377
+ else if (Array.isArray(src) && Number.isFinite(src[i])) {
378
+ v = src[i];
379
+ }
380
+ else if (src && typeof src === 'object' && Number.isFinite(src[i] ?? src[String(i)])) {
381
+ v = Number(src[i] ?? src[String(i)]);
382
+ }
383
+ else {
384
+ v = 0;
385
+ }
386
+ if (!Number.isFinite(v))
387
+ v = 0;
388
+ v = Math.max(chain[i].range[0], Math.min(chain[i].range[1], v));
389
+ out.push(v);
390
+ }
391
+ return out;
392
+ }
393
+ _jointSpeed(state) {
394
+ // Degrees per second the joint can travel during smoothing.
395
+ // Length-unit prismatic joints reuse this value as units/sec —
396
+ // typical smoothing speed scales similarly for both axis types.
397
+ //
398
+ // Default 45 deg/s — chosen to feel like a real industrial arm
399
+ // executing a careful pick-and-place rather than a fly-by. Higher
400
+ // speeds (90+) read as "rushed / unsafe" in a 3D scene where the
401
+ // viewer expects measured motion. User can override via
402
+ // `state.jointSpeed`.
403
+ const v = Number(state.jointSpeed ?? 45);
404
+ return Number.isFinite(v) && v > 0 ? v : 45;
405
+ }
406
+ /** Convert revolute joint values from degrees → radians. Prismatic
407
+ * values pass through untouched. */
408
+ _toRadians(chain, joints) {
409
+ return joints.map((v, i) => (chain[i].type === 'revolute' ? v * DEG2RAD : v));
410
+ }
411
+ /** Inverse of `_toRadians` — radians → degrees for revolute. */
412
+ _fromRadians(chain, joints) {
413
+ return joints.map((v, i) => (chain[i].type === 'revolute' ? v * RAD2DEG : v));
414
+ }
415
+ // ─── Geometry builders ───────────────────────────────────────────────
416
+ /**
417
+ * Build the chain as a tree of nested Object3Ds. Each link extends
418
+ * along its parent's +Z by `length` — applying the joint rotation BEFORE
419
+ * the translation. This way `rotateAround joint axis = rotate the
420
+ * downstream subtree`, which matches real arm kinematics.
421
+ */
422
+ _buildArm(chain, style, joints, baseHeight) {
423
+ const state = this.component.state;
424
+ const resolved = resolveMaterial3d(state.material3d);
425
+ const alpha = clamp(numOr(state.alpha, 1), 0, 1);
426
+ const linkMat = new THREE.MeshStandardMaterial({
427
+ color: style.color,
428
+ metalness: 0.45,
429
+ roughness: 0.45,
430
+ transparent: alpha < 1,
431
+ opacity: alpha
432
+ });
433
+ applyMaterial3dProps(linkMat, resolved);
434
+ const housingMat = new THREE.MeshStandardMaterial({
435
+ color: style.accentColor,
436
+ metalness: 0.55,
437
+ roughness: 0.4,
438
+ transparent: alpha < 1,
439
+ opacity: alpha
440
+ });
441
+ applyMaterial3dProps(housingMat, resolved);
442
+ // Three.js convention is +Y up — but our forward kinematics + CCDIK
443
+ // module is +Z up (matches IK math conventions). Wrap the whole arm
444
+ // in a group rotated -90° around X so chain-local +Z maps to world +Y.
445
+ // Lift by baseHeight so the chain origin sits ON TOP of the pedestal.
446
+ const armRoot = new THREE.Group();
447
+ armRoot.rotation.x = -Math.PI / 2;
448
+ armRoot.position.y = -this.effectiveDepth / 2 + baseHeight;
449
+ this.object3d.add(armRoot);
450
+ // Cache for worldToChainLocal — IK targets must be in this frame.
451
+ this._armRoot = armRoot;
452
+ this._jointFrames = [];
453
+ let currentParent = armRoot;
454
+ for (let i = 0; i < chain.length; i++) {
455
+ const link = chain[i];
456
+ // Joint frame — sits at the start of link i, rotates by jointValue.
457
+ const frame = new THREE.Object3D();
458
+ currentParent.add(frame);
459
+ this._jointFrames.push(frame);
460
+ this._applyJointValue(frame, link, joints[i]);
461
+ // Joint housing at the joint origin (frame's local origin).
462
+ const housing = this._buildJointHousing(style.jointHousing, style.linkRadius, housingMat);
463
+ if (housing)
464
+ frame.add(housing);
465
+ // Link mesh extends along local +Z by link.length. We mount it as a
466
+ // child of the frame so it inherits the joint rotation. The link
467
+ // itself sits with its base at z=0 and grows toward +Z.
468
+ const linkMesh = this._buildLinkMesh(style.linkShape, style.linkRadius, link.length, linkMat);
469
+ if (linkMesh)
470
+ frame.add(linkMesh);
471
+ // The next frame's parent is a translation forward by link.length.
472
+ const next = new THREE.Object3D();
473
+ next.position.set(0, 0, link.length);
474
+ frame.add(next);
475
+ currentParent = next;
476
+ }
477
+ // Save the end-effector parent so the gripper builder can mount onto it.
478
+ // Also exposed via `getGripperFrame()` so CarrierHolder.attachPointFor
479
+ // can return it — making any Carriable child mount onto the moving
480
+ // gripper TCP and follow IK automatically.
481
+ ;
482
+ this._endFrame = currentParent;
483
+ }
484
+ /**
485
+ * Frame at the gripper TCP (Tool Center Point) — the working point of
486
+ * the gripper, NOT the wrist. For jaw grippers this is the mid-point
487
+ * between finger tips; for suction/magnetic it's the contact face.
488
+ * Carriers held by the arm parent here so they sit at the gripping
489
+ * interface, not buried inside the gripper meshes.
490
+ *
491
+ * Falls back to `_endFrame` (wrist) until `_buildGripper` has run.
492
+ */
493
+ getGripperFrame() {
494
+ return this._tcpFrame ?? this._endFrame;
495
+ }
496
+ /**
497
+ * Convert a world-space point to the IK module's chain-local frame.
498
+ *
499
+ * Why this matters: CCDIK + forwardKinematics operate in `armRoot`'s
500
+ * local space (base joint at origin, +Z up — the IK math convention).
501
+ * `state.target` is interpreted in *that* frame. If a caller hands in
502
+ * a world position from another component (a parcel sitting somewhere
503
+ * in the scene), it must be projected through `armRoot`'s inverse
504
+ * world matrix first, otherwise the arm reaches toward "as if the
505
+ * world coords were base-relative" — a totally wrong direction once
506
+ * the robot itself isn't at the world origin.
507
+ *
508
+ * Returns the same `{x, y, z}` shape `state.target` accepts, which is
509
+ * already in chain-local space (no further conversion needed by
510
+ * pickAndPlace).
511
+ */
512
+ worldToChainLocal(worldX, worldY, worldZ) {
513
+ if (!this._armRoot)
514
+ return { x: 0, y: 0, z: 0 };
515
+ this._armRoot.updateWorldMatrix(true, false);
516
+ const v = new THREE.Vector3(worldX, worldY, worldZ);
517
+ v.applyMatrix4(new THREE.Matrix4().copy(this._armRoot.matrixWorld).invert());
518
+ return { x: v.x, y: v.y, z: v.z };
519
+ }
520
+ _armRoot;
521
+ /**
522
+ * Apply a joint value to its scene-graph frame. `value` is in *user
523
+ * units* (degrees for revolute, scene units for prismatic) — convert
524
+ * to radians at the math boundary.
525
+ */
526
+ _applyJointValue(frame, link, value) {
527
+ if (link.type === 'revolute') {
528
+ const ax = _AXIS_VEC[link.axis];
529
+ frame.quaternion.setFromAxisAngle(ax, value * DEG2RAD);
530
+ }
531
+ else {
532
+ frame.position.copy(_AXIS_VEC[link.axis]).multiplyScalar(value);
533
+ }
534
+ }
535
+ /** Cheap path: just refresh joint orientations without rebuilding the
536
+ * geometry tree. Used when only joint values changed. */
537
+ _refreshJointPoses(joints) {
538
+ for (let i = 0; i < this._chain.length; i++) {
539
+ const frame = this._jointFrames[i];
540
+ if (frame)
541
+ this._applyJointValue(frame, this._chain[i], joints[i]);
542
+ }
543
+ }
544
+ _buildJointHousing(kind, r, mat) {
545
+ const radius = r * 1.15;
546
+ switch (kind) {
547
+ case 'disk': {
548
+ const geo = new THREE.CylinderGeometry(radius, radius, r * 0.7, 24);
549
+ // disk axis = local Y by default; we want it perpendicular to the
550
+ // link's growth direction. Leaving it on local Y reads as a "wrist
551
+ // band" between two link segments — which is what cobot disks do.
552
+ return new THREE.Mesh(geo, mat);
553
+ }
554
+ case 'sphere': {
555
+ const geo = new THREE.SphereGeometry(radius, 16, 12);
556
+ return new THREE.Mesh(geo, mat);
557
+ }
558
+ case 'knuckle': {
559
+ // Asymmetric box — wider in two axes, narrow in third. Reads as
560
+ // industrial cast joint.
561
+ const geo = new THREE.BoxGeometry(radius * 2.1, radius * 1.4, radius * 1.8);
562
+ return new THREE.Mesh(geo, mat);
563
+ }
564
+ case 'none':
565
+ default:
566
+ return null;
567
+ }
568
+ }
569
+ _buildLinkMesh(shape, radius, length, mat) {
570
+ if (length <= 0.5)
571
+ return null;
572
+ let geo;
573
+ switch (shape) {
574
+ case 'cylinder':
575
+ geo = new THREE.CylinderGeometry(radius, radius, length, 16);
576
+ break;
577
+ case 'tapered':
578
+ geo = new THREE.CylinderGeometry(radius * 0.7, radius, length, 16);
579
+ break;
580
+ case 'tube':
581
+ geo = new THREE.CylinderGeometry(radius * 0.5, radius * 0.5, length, 12);
582
+ break;
583
+ case 'box':
584
+ geo = new THREE.BoxGeometry(radius * 1.6, radius * 1.6, length);
585
+ break;
586
+ case 'gltf':
587
+ // Placeholder — full GLTF link replacement is a v2 feature.
588
+ // Fall back to cylinder so the chain doesn't break visually.
589
+ geo = new THREE.CylinderGeometry(radius, radius, length, 16);
590
+ break;
591
+ default:
592
+ geo = new THREE.CylinderGeometry(radius, radius, length, 16);
593
+ }
594
+ // Three.js cylinder/box default axis = local +Y. Rotate to grow along
595
+ // local +Z (the chain-forward direction) and shift so the BASE sits at
596
+ // z=0 (rather than centered).
597
+ if (shape !== 'box') {
598
+ geo.rotateX(Math.PI / 2);
599
+ }
600
+ geo.translate(0, 0, length / 2);
601
+ const mesh = new THREE.Mesh(geo, mat);
602
+ mesh.castShadow = true;
603
+ return mesh;
604
+ }
605
+ // ─── Gripper ──────────────────────────────────────────────────────────
606
+ /**
607
+ * Build the gripper meshes onto `_endFrame` and place a TCP frame at
608
+ * the gripper's working point (between the finger tips for jaw types,
609
+ * at the cup/disk distal face for surface types). Carriers held by the
610
+ * arm mount onto this TCP frame, NOT onto `_endFrame` — `_endFrame` is
611
+ * the wrist (chain end-of-link) and the gripper extends from it in +Z,
612
+ * so a carrier at `_endFrame` origin would visually overlap the gripper
613
+ * meshes (the fingers/cup would pierce through the box).
614
+ */
615
+ _buildGripper(chain, style, state) {
616
+ const endFrame = this._endFrame;
617
+ if (!endFrame)
618
+ return;
619
+ // TCP frame — added unconditionally (even for gripper.type='none' or
620
+ // missing gripper) so carrier mount logic always has a stable target.
621
+ // Default at wrist (z=0); per-type builders override below.
622
+ const tcp = new THREE.Object3D();
623
+ endFrame.add(tcp);
624
+ this._tcpFrame = tcp;
625
+ const cfg = {
626
+ ...DEFAULT_GRIPPER,
627
+ ...(state.gripper ?? {}),
628
+ // gripperType nature property is a shortcut for {gripper: {type}} —
629
+ // expose it so the property panel's <select> works without nested object editing.
630
+ ...(state.gripperType ? { type: state.gripperType } : {})
631
+ };
632
+ if (cfg.type === 'none')
633
+ return;
634
+ const color = pickColorish(cfg.color, style.accentColor);
635
+ const resolved = resolveMaterial3d(state.material3d);
636
+ const alpha = clamp(numOr(state.alpha, 1), 0, 1);
637
+ const mat = new THREE.MeshStandardMaterial({
638
+ color,
639
+ metalness: 0.55,
640
+ roughness: 0.4,
641
+ transparent: alpha < 1,
642
+ opacity: alpha
643
+ });
644
+ applyMaterial3dProps(mat, resolved);
645
+ let tcpZ = 0;
646
+ switch (cfg.type) {
647
+ case 'parallel':
648
+ tcpZ = this._buildParallelGripper(endFrame, cfg, mat, style.linkRadius);
649
+ break;
650
+ case 'three-finger':
651
+ tcpZ = this._buildThreeFingerGripper(endFrame, cfg, mat, style.linkRadius);
652
+ break;
653
+ case 'suction':
654
+ tcpZ = this._buildSuctionGripper(endFrame, cfg, mat, style.linkRadius);
655
+ break;
656
+ case 'magnetic':
657
+ tcpZ = this._buildMagneticGripper(endFrame, cfg, mat, style.linkRadius);
658
+ break;
659
+ }
660
+ tcp.position.z = tcpZ;
661
+ }
662
+ _tcpFrame;
663
+ /**
664
+ * Each gripper sub-builder returns its TCP z-offset (in `_endFrame`'s
665
+ * local coordinates) — the point in space where a held carrier's grip
666
+ * face should land. The caller positions `_tcpFrame` at that z so
667
+ * carriers attach there directly.
668
+ */
669
+ _buildParallelGripper(parent, cfg, mat, linkRadius) {
670
+ // Default sizes scale with linkRadius so the gripper looks proportional
671
+ // to the arm. A heavy industrial 6-axis (linkRadius ~10) gets a chunky
672
+ // gripper; a slim cobot wrist (linkRadius ~3) gets a small one. User
673
+ // can still override via cfg.stroke / cfg.fingerWidth.
674
+ const stroke = cfg.stroke ?? linkRadius * 1.8;
675
+ const fingerWidth = cfg.fingerWidth ?? linkRadius * 0.45;
676
+ const fingerLength = stroke * 1.2;
677
+ const closure = THREE.MathUtils.clamp(cfg.state ?? 0, 0, 1); // 0 = open, 1 = closed
678
+ // Wrist plate
679
+ const plate = new THREE.Mesh(new THREE.BoxGeometry(stroke * 1.6, fingerWidth * 1.2, fingerWidth * 1.8), mat);
680
+ plate.position.set(0, 0, fingerWidth * 0.9);
681
+ parent.add(plate);
682
+ // Two fingers, opening width = stroke when state=0, fingerWidth when state=1
683
+ const halfOpen = (stroke / 2) * (1 - closure) + (fingerWidth / 2) * closure;
684
+ for (const sign of [-1, 1]) {
685
+ const finger = new THREE.Mesh(new THREE.BoxGeometry(fingerWidth, fingerWidth, fingerLength), mat);
686
+ finger.position.set(sign * halfOpen, 0, fingerWidth * 1.8 + fingerLength / 2);
687
+ parent.add(finger);
688
+ }
689
+ // TCP = finger-tip plane (carrier's top face docks against it).
690
+ return fingerWidth * 1.8 + fingerLength;
691
+ }
692
+ _buildThreeFingerGripper(parent, cfg, mat, linkRadius) {
693
+ const stroke = cfg.stroke ?? linkRadius * 1.5;
694
+ const fingerWidth = cfg.fingerWidth ?? linkRadius * 0.4;
695
+ const fingerLength = stroke * 1.2;
696
+ const closure = THREE.MathUtils.clamp(cfg.state ?? 0, 0, 1);
697
+ const radius = (stroke / 2) * (1 - closure) + (fingerWidth / 2) * closure;
698
+ // Wrist hub
699
+ const hub = new THREE.Mesh(new THREE.CylinderGeometry(stroke * 0.55, stroke * 0.55, fingerWidth * 1.5, 16), mat);
700
+ hub.rotation.x = Math.PI / 2;
701
+ hub.position.set(0, 0, fingerWidth * 0.75);
702
+ parent.add(hub);
703
+ // Three fingers around the axis
704
+ for (let i = 0; i < 3; i++) {
705
+ const angle = (i / 3) * Math.PI * 2;
706
+ const finger = new THREE.Mesh(new THREE.BoxGeometry(fingerWidth, fingerWidth, fingerLength), mat);
707
+ finger.position.set(Math.cos(angle) * radius, Math.sin(angle) * radius, fingerWidth * 1.5 + fingerLength / 2);
708
+ parent.add(finger);
709
+ }
710
+ return fingerWidth * 1.5 + fingerLength;
711
+ }
712
+ _buildSuctionGripper(parent, cfg, mat, linkRadius) {
713
+ const diameter = cfg.diameter ?? linkRadius * 2.4;
714
+ // Mounting stem
715
+ const stem = new THREE.Mesh(new THREE.CylinderGeometry(diameter * 0.25, diameter * 0.25, diameter * 0.5, 12), mat);
716
+ stem.rotation.x = Math.PI / 2;
717
+ stem.position.set(0, 0, diameter * 0.25);
718
+ parent.add(stem);
719
+ // Suction cup (cone, narrow end at the stem)
720
+ const cup = new THREE.Mesh(new THREE.CylinderGeometry(diameter / 2, diameter * 0.3, diameter * 0.4, 24, 1, true), mat);
721
+ cup.rotation.x = Math.PI / 2;
722
+ cup.position.set(0, 0, diameter * 0.5 + diameter * 0.2);
723
+ parent.add(cup);
724
+ // TCP = cup distal face (suction surface contacts the carrier here).
725
+ return diameter * 0.9;
726
+ }
727
+ _buildMagneticGripper(parent, cfg, mat, linkRadius) {
728
+ const diameter = cfg.diameter ?? linkRadius * 2.6;
729
+ // Disk magnet at the end
730
+ const disk = new THREE.Mesh(new THREE.CylinderGeometry(diameter / 2, diameter / 2, diameter * 0.25, 24), mat);
731
+ disk.rotation.x = Math.PI / 2;
732
+ disk.position.set(0, 0, diameter * 0.125);
733
+ parent.add(disk);
734
+ // TCP = disk distal face (magnet contacts the carrier here).
735
+ return diameter * 0.25;
736
+ }
737
+ // ─── Reach sphere visualization ──────────────────────────────────────
738
+ _buildReachSphere(chain, state, baseHeight) {
739
+ if (!state.showReachSphere)
740
+ return;
741
+ const reach = maxReach(chain);
742
+ if (reach <= 0)
743
+ return;
744
+ const geo = new THREE.SphereGeometry(reach, 24, 16);
745
+ const wire = new THREE.WireframeGeometry(geo);
746
+ const mat = new THREE.LineBasicMaterial({
747
+ color: 0x44aacc,
748
+ transparent: true,
749
+ opacity: 0.18
750
+ });
751
+ const wireMesh = new THREE.LineSegments(wire, mat);
752
+ // Center on the base joint (top of pedestal), in world-space y.
753
+ wireMesh.position.y = -this.effectiveDepth / 2 + baseHeight;
754
+ // Visualization-only — must not catch raycasts. The reach sphere
755
+ // surrounds the arm in 3D and would intercept clicks meant for the
756
+ // actual robot body. NO_RAYCAST keeps it visible but click-through.
757
+ wireMesh.raycast = NO_RAYCAST;
758
+ this.object3d.add(wireMesh);
759
+ geo.dispose();
760
+ }
761
+ // ─── Base / pedestal ─────────────────────────────────────────────────
762
+ /**
763
+ * Pedestal — sized from `state.width × state.height` (the 2D footprint).
764
+ * Cylindrical base whose radius fills ~90% of the smaller footprint
765
+ * dimension; a flared bottom (1.2× radius) gives the visual weight of
766
+ * a real industrial robot anchor.
767
+ */
768
+ _buildBase(state, style, baseHeight) {
769
+ const w = Math.max(Math.abs(numOr(state.width, 100)), 1);
770
+ const h2d = Math.max(Math.abs(numOr(state.height, 100)), 1);
771
+ const r = (Math.min(w, h2d) / 2) * 0.9;
772
+ const resolved = resolveMaterial3d(state.material3d);
773
+ const alpha = clamp(numOr(state.alpha, 1), 0, 1);
774
+ const mat = new THREE.MeshStandardMaterial({
775
+ color: style.accentColor,
776
+ metalness: 0.6,
777
+ roughness: 0.4,
778
+ transparent: alpha < 1,
779
+ opacity: alpha
780
+ });
781
+ applyMaterial3dProps(mat, resolved);
782
+ const base = new THREE.Mesh(new THREE.CylinderGeometry(r, r * 1.2, baseHeight, 24), mat);
783
+ base.position.set(0, -this.effectiveDepth / 2 + baseHeight / 2, 0);
784
+ base.castShadow = resolved.castShadow;
785
+ base.receiveShadow = resolved.receiveShadow;
786
+ this.object3d.add(base);
787
+ }
788
+ // ─── Animation: smooth joint values toward solved target ─────────────
789
+ _startAnimation() {
790
+ this._isAnimating = true;
791
+ let lastTime = performance.now();
792
+ const tick = () => {
793
+ if (!this._isAnimating || !this._smoothing)
794
+ return;
795
+ const now = performance.now();
796
+ const dt = Math.min((now - lastTime) / 1000, 0.1); // clamp for stability
797
+ lastTime = now;
798
+ const { current, target, speed } = this._smoothing;
799
+ const maxStep = speed * dt;
800
+ let allReached = true;
801
+ for (let i = 0; i < current.length; i++) {
802
+ const diff = (target[i] ?? 0) - current[i];
803
+ if (Math.abs(diff) > 1e-4)
804
+ allReached = false;
805
+ const step = Math.sign(diff) * Math.min(Math.abs(diff), maxStep);
806
+ current[i] += step;
807
+ // apply to live frame
808
+ const frame = this._jointFrames[i];
809
+ const link = this._chain[i];
810
+ if (frame && link)
811
+ this._applyJointValue(frame, link, current[i]);
812
+ }
813
+ this.component.invalidate?.();
814
+ if (allReached) {
815
+ this._stopAnimation();
816
+ this.component.trigger?.('tcp-reached', { component: this.component });
817
+ return;
818
+ }
819
+ this._animFrame = requestAnimationFrame(tick);
820
+ };
821
+ this._animFrame = requestAnimationFrame(tick);
822
+ }
823
+ _stopAnimation() {
824
+ this._isAnimating = false;
825
+ if (this._animFrame !== undefined) {
826
+ cancelAnimationFrame(this._animFrame);
827
+ this._animFrame = undefined;
828
+ }
829
+ }
830
+ /**
831
+ * Re-run IK toward a new target without rebuilding the scene graph.
832
+ *
833
+ * Mirrors the IK block of `build()` but operates on the *existing*
834
+ * joint frames and meshes. Critically does NOT call `update()` /
835
+ * `clear()` — those tear down `this.object3d`'s children, which would
836
+ * also detach the gripper frame and any Carriable currently mounted
837
+ * onto it. A pickAndPlace operation would lose its held carrier the
838
+ * instant the place target is committed.
839
+ *
840
+ * Falls back to a full `update()` only when the cached chain hasn't
841
+ * been built yet (build pre-condition).
842
+ */
843
+ _retargetIk() {
844
+ if (this._chain.length === 0 || this._jointFrames.length !== this._chain.length) {
845
+ this.update();
846
+ return;
847
+ }
848
+ const state = this.component.state;
849
+ const chain = this._chain;
850
+ const target = state.target;
851
+ const speed = this._jointSpeed(state);
852
+ // Starting pose for IK = where smoothing currently is (mid-flight)
853
+ // or the resolved joint values from state. Using mid-flight values
854
+ // makes consecutive `pnp` calls chain smoothly without snap-back.
855
+ const previous = this._smoothing?.current?.slice() ?? this._resolveJoints(chain, state);
856
+ if (target && Number.isFinite(target.x) && Number.isFinite(target.y) && Number.isFinite(target.z)) {
857
+ const targetVec = new THREE.Vector3(target.x, target.y, target.z);
858
+ const targetYaw = Number.isFinite(target.yaw) ? target.yaw : undefined;
859
+ const radJoints = this._toRadians(chain, previous);
860
+ const ikValues = this._solveIkDescent(chain, radJoints, targetVec, targetYaw);
861
+ const solvedUser = this._fromRadians(chain, ikValues);
862
+ this._smoothing = {
863
+ current: previous,
864
+ target: solvedUser.slice(),
865
+ speed
866
+ };
867
+ // Snap visible pose to the smoothing's "current" (= previous IK
868
+ // position). Without this, if external code mutated joint frames
869
+ // between ticks, the first tick would jump.
870
+ this._refreshJointPoses(previous);
871
+ this._stopAnimation();
872
+ this._startAnimation();
873
+ }
874
+ else {
875
+ // Target cleared — stop animating, freeze where we are.
876
+ if (this._smoothing) {
877
+ this._smoothing.target = this._smoothing.current.slice();
878
+ this._smoothing.speed = speed;
879
+ }
880
+ this._stopAnimation();
881
+ }
882
+ }
883
+ updateDimension() { }
884
+ onchange(after, before) {
885
+ // Structural changes — full rebuild.
886
+ if ('style' in after ||
887
+ 'chainPreset' in after ||
888
+ 'chain' in after ||
889
+ 'linkShape' in after ||
890
+ 'jointHousing' in after ||
891
+ 'linkRadius' in after ||
892
+ 'color' in after ||
893
+ 'accentColor' in after ||
894
+ 'fillStyle' in after ||
895
+ 'strokeStyle' in after ||
896
+ 'alpha' in after ||
897
+ 'material3d' in after ||
898
+ 'gripper' in after ||
899
+ 'gripperType' in after ||
900
+ 'showReachSphere' in after ||
901
+ 'width' in after ||
902
+ 'height' in after ||
903
+ 'depth' in after) {
904
+ this.update();
905
+ return;
906
+ }
907
+ // Target change → re-run IK + restart smoothing on the EXISTING
908
+ // scene graph. Critically NOT a full rebuild — `update()` calls
909
+ // `clear()` which detaches every child of `this.object3d`, including
910
+ // any Carriable currently mounted on the gripper frame. A pickAndPlace
911
+ // call would invisibly drop the held carrier the moment we set the
912
+ // place target, leaving no mesh between pick and place.
913
+ if ('target' in after || 'jointSpeed' in after) {
914
+ this._retargetIk();
915
+ return;
916
+ }
917
+ // Joint value change (state.joint0, state.joint1, ... or state.joints
918
+ // batch) — fast path: just refresh joint poses on the existing scene
919
+ // graph. NO mesh rebuild. This is what makes property-panel slider
920
+ // edits feel live. The match must be done explicitly because dynamic
921
+ // joint property names (joint0, joint1, ...) aren't in any static list.
922
+ const hasJoint = 'joints' in after || Object.keys(after).some(k => /^joint\d+$/.test(k));
923
+ if (hasJoint) {
924
+ const state = this.component.state;
925
+ // chain might be empty if build hasn't run yet (e.g. component just
926
+ // attached). Defer to a full update in that case.
927
+ if (this._chain.length === 0 || this._jointFrames.length !== this._chain.length) {
928
+ this.update();
929
+ return;
930
+ }
931
+ const joints = this._resolveJoints(this._chain, state);
932
+ this._refreshJointPoses(joints);
933
+ // smoothing's "current" should track the user's manual edits so the
934
+ // next IK target solves from where the user left things.
935
+ if (this._smoothing)
936
+ this._smoothing.current = joints.slice();
937
+ return;
938
+ }
939
+ super.onchange(after, before);
940
+ }
941
+ dispose() {
942
+ this._stopAnimation();
943
+ super.dispose();
944
+ }
945
+ updateAlpha() { }
946
+ }
947
+ /** Returns `v` if a finite number, otherwise `dflt`. */
948
+ function numOr(v, dflt) {
949
+ return typeof v === 'number' && Number.isFinite(v) ? v : dflt;
950
+ }
951
+ function clamp(v, lo, hi) {
952
+ return Math.max(lo, Math.min(hi, v));
953
+ }
954
+ /**
955
+ * Pick the first valid color in priority order. Accepts both color strings
956
+ * (CSS / hex) and hex int numbers — both are valid `THREE.ColorRepresentation`.
957
+ * Treats 'transparent' / empty strings as "skip me".
958
+ */
959
+ /** Returns a number-or-string color (StyleColor). Both flavors are valid
960
+ * THREE.ColorRepresentation, so they pass through to MeshStandardMaterial
961
+ * without conversion. */
962
+ function pickColorish(...candidates) {
963
+ for (const c of candidates) {
964
+ if (typeof c === 'string' && c && c !== 'transparent')
965
+ return c;
966
+ if (typeof c === 'number' && Number.isFinite(c))
967
+ return c;
968
+ }
969
+ return 0x888888;
970
+ }
971
+ //# sourceMappingURL=robot-arm-3d.js.map