Skip to main content

oxiphysics_geometry/
robot_geometry.rs

1// Copyright 2026 COOLJAPAN OU (Team KitaSan)
2// SPDX-License-Identifier: Apache-2.0
3
4//! Robot geometry: DH parameters, forward/inverse kinematics, Jacobians,
5//! workspace computation, collision checking, and self-collision detection.
6//!
7//! All transforms are represented as 4×4 homogeneous matrices stored in
8//! row-major order as `[f64; 16]`. Joint arrays use plain `[f64; 3]` vectors
9//! for positions and axes. No external linear-algebra crate is used.
10
11use rand::RngExt;
12use std::f64::consts::PI;
13
14// ---------------------------------------------------------------------------
15// Low-level math helpers
16// ---------------------------------------------------------------------------
17
18/// Dot product of two 3-vectors.
19#[inline]
20fn dot3(a: [f64; 3], b: [f64; 3]) -> f64 {
21    a[0] * b[0] + a[1] * b[1] + a[2] * b[2]
22}
23
24/// Vector subtraction.
25#[inline]
26fn sub3(a: [f64; 3], b: [f64; 3]) -> [f64; 3] {
27    [a[0] - b[0], a[1] - b[1], a[2] - b[2]]
28}
29
30/// Vector addition.
31#[inline]
32fn add3(a: [f64; 3], b: [f64; 3]) -> [f64; 3] {
33    [a[0] + b[0], a[1] + b[1], a[2] + b[2]]
34}
35
36/// Scalar multiplication of a 3-vector.
37#[inline]
38fn scale3(a: [f64; 3], s: f64) -> [f64; 3] {
39    [a[0] * s, a[1] * s, a[2] * s]
40}
41
42/// Euclidean length of a 3-vector.
43#[inline]
44fn len3(a: [f64; 3]) -> f64 {
45    dot3(a, a).sqrt()
46}
47
48/// Cross product.
49#[inline]
50fn cross3(a: [f64; 3], b: [f64; 3]) -> [f64; 3] {
51    [
52        a[1] * b[2] - a[2] * b[1],
53        a[2] * b[0] - a[0] * b[2],
54        a[0] * b[1] - a[1] * b[0],
55    ]
56}
57
58// ---------------------------------------------------------------------------
59// 4×4 homogeneous matrix (row-major)
60// ---------------------------------------------------------------------------
61
62/// A 4×4 homogeneous transformation matrix stored row-major.
63///
64/// Index layout: `m[row * 4 + col]`.
65pub type Mat4 = [f64; 16];
66
67/// Returns the 4×4 identity matrix.
68pub fn mat4_identity() -> Mat4 {
69    let mut m = [0.0f64; 16];
70    m[0] = 1.0;
71    m[5] = 1.0;
72    m[10] = 1.0;
73    m[15] = 1.0;
74    m
75}
76
77/// Multiplies two 4×4 row-major matrices.
78pub fn mat4_mul(a: &Mat4, b: &Mat4) -> Mat4 {
79    let mut c = [0.0f64; 16];
80    for row in 0..4 {
81        for col in 0..4 {
82            let mut s = 0.0f64;
83            for k in 0..4 {
84                s += a[row * 4 + k] * b[k * 4 + col];
85            }
86            c[row * 4 + col] = s;
87        }
88    }
89    c
90}
91
92/// Transforms a 3-vector by a 4×4 homogeneous matrix (w = 1).
93pub fn mat4_transform_point(m: &Mat4, p: [f64; 3]) -> [f64; 3] {
94    [
95        m[0] * p[0] + m[1] * p[1] + m[2] * p[2] + m[3],
96        m[4] * p[0] + m[5] * p[1] + m[6] * p[2] + m[7],
97        m[8] * p[0] + m[9] * p[1] + m[10] * p[2] + m[11],
98    ]
99}
100
101/// Transforms a 3-direction (w = 0) by a 4×4 matrix.
102pub fn mat4_transform_dir(m: &Mat4, d: [f64; 3]) -> [f64; 3] {
103    [
104        m[0] * d[0] + m[1] * d[1] + m[2] * d[2],
105        m[4] * d[0] + m[5] * d[1] + m[6] * d[2],
106        m[8] * d[0] + m[9] * d[1] + m[10] * d[2],
107    ]
108}
109
110/// Extracts the translation component from a 4×4 matrix.
111pub fn mat4_translation(m: &Mat4) -> [f64; 3] {
112    [m[3], m[7], m[11]]
113}
114
115/// Builds a rotation matrix about the X axis.
116fn rot_x(angle: f64) -> Mat4 {
117    let c = angle.cos();
118    let s = angle.sin();
119    let mut m = mat4_identity();
120    m[5] = c;
121    m[6] = -s;
122    m[9] = s;
123    m[10] = c;
124    m
125}
126
127/// Builds a rotation matrix about the Z axis.
128fn rot_z(angle: f64) -> Mat4 {
129    let c = angle.cos();
130    let s = angle.sin();
131    let mut m = mat4_identity();
132    m[0] = c;
133    m[1] = -s;
134    m[4] = s;
135    m[5] = c;
136    m
137}
138
139/// Builds a pure translation matrix.
140fn trans(tx: f64, ty: f64, tz: f64) -> Mat4 {
141    let mut m = mat4_identity();
142    m[3] = tx;
143    m[7] = ty;
144    m[11] = tz;
145    m
146}
147
148// ---------------------------------------------------------------------------
149// Denavit-Hartenberg (DH) parameters
150// ---------------------------------------------------------------------------
151
152/// Standard Denavit-Hartenberg parameters for a single joint/link.
153///
154/// Convention: `T = Rz(θ) · Tz(d) · Tx(a) · Rx(α)`.
155#[derive(Debug, Clone, Copy)]
156pub struct DhParam {
157    /// Joint angle θ (radians) — variable for revolute joints.
158    pub theta: f64,
159    /// Link offset d (metres) — variable for prismatic joints.
160    pub d: f64,
161    /// Link length a (metres).
162    pub a: f64,
163    /// Link twist α (radians).
164    pub alpha: f64,
165}
166
167impl DhParam {
168    /// Creates a new DH parameter set.
169    pub fn new(theta: f64, d: f64, a: f64, alpha: f64) -> Self {
170        Self { theta, d, a, alpha }
171    }
172
173    /// Returns the 4×4 homogeneous transform for this DH frame.
174    pub fn transform(&self) -> Mat4 {
175        let rz = rot_z(self.theta);
176        let tz = trans(0.0, 0.0, self.d);
177        let tx = trans(self.a, 0.0, 0.0);
178        let rx = rot_x(self.alpha);
179        mat4_mul(&mat4_mul(&mat4_mul(&rz, &tz), &tx), &rx)
180    }
181}
182
183// ---------------------------------------------------------------------------
184// Joint types
185// ---------------------------------------------------------------------------
186
187/// Type of a robot joint.
188#[derive(Debug, Clone, Copy, PartialEq)]
189pub enum JointType {
190    /// Revolute joint — rotates about Z axis.
191    Revolute,
192    /// Prismatic joint — translates along Z axis.
193    Prismatic,
194    /// Fixed joint — no degree of freedom.
195    Fixed,
196}
197
198// ---------------------------------------------------------------------------
199// Joint limits
200// ---------------------------------------------------------------------------
201
202/// Angular or linear limits for a single joint.
203#[derive(Debug, Clone, Copy)]
204pub struct JointLimits {
205    /// Minimum joint value (radians or metres).
206    pub min: f64,
207    /// Maximum joint value (radians or metres).
208    pub max: f64,
209    /// Maximum joint velocity (rad/s or m/s).
210    pub max_velocity: f64,
211    /// Maximum joint torque/force (Nm or N).
212    pub max_effort: f64,
213}
214
215impl JointLimits {
216    /// Creates joint limits.
217    pub fn new(min: f64, max: f64, max_velocity: f64, max_effort: f64) -> Self {
218        Self {
219            min,
220            max,
221            max_velocity,
222            max_effort,
223        }
224    }
225
226    /// Returns true if `value` is within \[min, max\].
227    pub fn is_within(&self, value: f64) -> bool {
228        value >= self.min && value <= self.max
229    }
230
231    /// Clamps `value` to \[min, max\].
232    pub fn clamp(&self, value: f64) -> f64 {
233        value.clamp(self.min, self.max)
234    }
235}
236
237// ---------------------------------------------------------------------------
238// RobotLink
239// ---------------------------------------------------------------------------
240
241/// Describes a single link of a robot arm.
242#[derive(Debug, Clone)]
243pub struct RobotLink {
244    /// Human-readable name of the link.
245    pub name: String,
246    /// DH parameters relative to the parent frame.
247    pub dh: DhParam,
248    /// Type of the joint connecting to this link.
249    pub joint_type: JointType,
250    /// Joint limits (optional for fixed joints).
251    pub limits: Option<JointLimits>,
252    /// Capsule radius used for collision checking (metres).
253    pub collision_radius: f64,
254    /// Capsule half-length used for collision checking (metres).
255    pub collision_half_len: f64,
256}
257
258impl RobotLink {
259    /// Creates a new robot link.
260    pub fn new(
261        name: impl Into<String>,
262        dh: DhParam,
263        joint_type: JointType,
264        limits: Option<JointLimits>,
265        collision_radius: f64,
266        collision_half_len: f64,
267    ) -> Self {
268        Self {
269            name: name.into(),
270            dh,
271            joint_type,
272            limits,
273            collision_radius,
274            collision_half_len,
275        }
276    }
277}
278
279// ---------------------------------------------------------------------------
280// RobotArm — the main robot structure
281// ---------------------------------------------------------------------------
282
283/// A serial-chain robot arm described by a sequence of DH links.
284///
285/// Supports forward kinematics, Jacobian computation (analytical and numerical),
286/// Newton-Raphson inverse kinematics, workspace Monte-Carlo sampling,
287/// joint-limit checking, and self-collision detection.
288#[derive(Debug, Clone)]
289pub struct RobotArm {
290    /// Name of the robot.
291    pub name: String,
292    /// Ordered list of links (joint 0 is closest to base).
293    pub links: Vec<RobotLink>,
294    /// Base transform applied before all joint transforms.
295    pub base_transform: Mat4,
296}
297
298impl RobotArm {
299    /// Creates a new robot arm.
300    pub fn new(name: impl Into<String>, links: Vec<RobotLink>) -> Self {
301        Self {
302            name: name.into(),
303            links,
304            base_transform: mat4_identity(),
305        }
306    }
307
308    /// Sets the base transform and returns `self` for chaining.
309    pub fn with_base_transform(mut self, t: Mat4) -> Self {
310        self.base_transform = t;
311        self
312    }
313
314    /// Number of degrees of freedom (non-Fixed joints).
315    pub fn dof(&self) -> usize {
316        self.links
317            .iter()
318            .filter(|l| l.joint_type != JointType::Fixed)
319            .count()
320    }
321
322    /// Returns the DH parameter for link `i` with the joint variable (`q`)
323    /// applied depending on joint type.
324    fn dh_with_q(&self, link_idx: usize, q: f64) -> DhParam {
325        let link = &self.links[link_idx];
326        let mut dh = link.dh;
327        match link.joint_type {
328            JointType::Revolute => dh.theta += q,
329            JointType::Prismatic => dh.d += q,
330            JointType::Fixed => {}
331        }
332        dh
333    }
334
335    /// Computes all intermediate frames (base → end-effector) for a given joint
336    /// configuration `q`. Returns one matrix per link plus the base.
337    pub fn forward_frames(&self, q: &[f64]) -> Vec<Mat4> {
338        let mut frames = Vec::with_capacity(self.links.len() + 1);
339        frames.push(self.base_transform);
340        let mut q_iter = q.iter().copied();
341        for (i, link) in self.links.iter().enumerate() {
342            let qi = if link.joint_type == JointType::Fixed {
343                0.0
344            } else {
345                q_iter.next().unwrap_or(0.0)
346            };
347            let dh = self.dh_with_q(i, qi);
348            let t = mat4_mul(
349                frames.last().expect("collection should not be empty"),
350                &dh.transform(),
351            );
352            frames.push(t);
353        }
354        frames
355    }
356
357    /// Returns the end-effector transform for joint configuration `q`.
358    pub fn end_effector(&self, q: &[f64]) -> Mat4 {
359        let frames = self.forward_frames(q);
360        *frames.last().expect("collection should not be empty")
361    }
362
363    /// Returns the end-effector position `[x, y, z]` for joint configuration `q`.
364    pub fn end_effector_pos(&self, q: &[f64]) -> [f64; 3] {
365        mat4_translation(&self.end_effector(q))
366    }
367
368    // -----------------------------------------------------------------------
369    // Jacobian (numerical)
370    // -----------------------------------------------------------------------
371
372    /// Computes the 3×n positional Jacobian numerically (finite differences).
373    ///
374    /// Returns a flat row-major array of shape `3 × dof`.
375    pub fn jacobian_numerical(&self, q: &[f64]) -> Vec<f64> {
376        let n = q.len();
377        let eps = 1e-7;
378        let p0 = self.end_effector_pos(q);
379        let mut j = vec![0.0f64; 3 * n];
380        let mut qp = q.to_vec();
381        for i in 0..n {
382            qp[i] += eps;
383            let p1 = self.end_effector_pos(&qp);
384            qp[i] = q[i];
385            for row in 0..3 {
386                j[row * n + i] = (p1[row] - p0[row]) / eps;
387            }
388        }
389        j
390    }
391
392    /// Computes the full 6×n Jacobian (position + orientation) numerically.
393    ///
394    /// Orientation rows use angle-axis approximation via the rotation part of
395    /// the end-effector transform. Returns flat row-major `6 × dof`.
396    pub fn jacobian_6dof_numerical(&self, q: &[f64]) -> Vec<f64> {
397        let n = q.len();
398        let eps = 1e-7;
399        let t0 = self.end_effector(q);
400        let mut j = vec![0.0f64; 6 * n];
401        let mut qp = q.to_vec();
402        for i in 0..n {
403            qp[i] += eps;
404            let t1 = self.end_effector(&qp);
405            qp[i] = q[i];
406            // Position columns
407            for row in 0..3 {
408                j[row * n + i] = (t1[row * 4 + 3] - t0[row * 4 + 3]) / eps;
409            }
410            // Orientation columns (skew-symmetric R_delta)
411            let r_delta = mat4_mul(&mat4_transpose(&t0), &t1);
412            // vee map: extract angular velocity from skew part
413            let wx = (r_delta[6] - r_delta[9]) / (2.0 * eps);
414            let wy = (r_delta[8] - r_delta[2]) / (2.0 * eps);
415            let wz = (r_delta[1] - r_delta[4]) / (2.0 * eps);
416            j[3 * n + i] = wx;
417            j[4 * n + i] = wy;
418            j[5 * n + i] = wz;
419        }
420        j
421    }
422
423    /// Computes the 3×n analytical Jacobian using the geometric (cross-product) method.
424    ///
425    /// For revolute joints: `J_i = z_{i-1} × (p_e − p_{i-1})`.
426    /// For prismatic joints: `J_i = z_{i-1}`.
427    pub fn jacobian_analytical(&self, q: &[f64]) -> Vec<f64> {
428        let frames = self.forward_frames(q);
429        let n = q.len();
430        let p_e = mat4_translation(frames.last().expect("collection should not be empty"));
431        let mut j = vec![0.0f64; 3 * n];
432        let mut qi = 0usize;
433        for (i, link) in self.links.iter().enumerate() {
434            if link.joint_type == JointType::Fixed {
435                continue;
436            }
437            let frame = &frames[i]; // frame before this joint
438            // Z axis of this frame (third column of rotation)
439            let z = [frame[2], frame[6], frame[10]];
440            let p_i = mat4_translation(frame);
441            let col: [f64; 3] = match link.joint_type {
442                JointType::Revolute => cross3(z, sub3(p_e, p_i)),
443                JointType::Prismatic => z,
444                JointType::Fixed => unreachable!(),
445            };
446            for row in 0..3 {
447                j[row * n + qi] = col[row];
448            }
449            qi += 1;
450        }
451        j
452    }
453
454    // -----------------------------------------------------------------------
455    // Jacobian pseudo-inverse (Moore-Penrose via SVD-free damped LS)
456    // -----------------------------------------------------------------------
457
458    /// Computes the damped least-squares pseudo-inverse of a `3 × n` Jacobian.
459    ///
460    /// Uses the formula `J^+ = J^T (J J^T + λ²I)^{-1}` with closed-form
461    /// inversion for the 3×3 system.
462    pub fn jacobian_pseudoinverse(j: &[f64], n: usize, lambda: f64) -> Vec<f64> {
463        // J is 3×n.  Compute A = J J^T (3×3)
464        let mut a = [0.0f64; 9];
465        for r in 0..3 {
466            for c in 0..3 {
467                let mut s = 0.0f64;
468                for k in 0..n {
469                    s += j[r * n + k] * j[c * n + k];
470                }
471                a[r * 3 + c] = s;
472            }
473        }
474        // Add damping
475        let lam2 = lambda * lambda;
476        a[0] += lam2;
477        a[4] += lam2;
478        a[8] += lam2;
479        // Invert 3×3
480        let inv = mat3_inverse(&a);
481        // J^+ = J^T * inv  (n×3)
482        let mut jp = vec![0.0f64; n * 3];
483        for r in 0..n {
484            for c in 0..3 {
485                let mut s = 0.0f64;
486                for k in 0..3 {
487                    s += j[k * n + r] * inv[k * 3 + c];
488                }
489                jp[r * 3 + c] = s;
490            }
491        }
492        jp
493    }
494
495    // -----------------------------------------------------------------------
496    // Inverse kinematics (Newton-Raphson)
497    // -----------------------------------------------------------------------
498
499    /// Attempts to solve inverse kinematics using Newton-Raphson iteration.
500    ///
501    /// Returns `Ok(q)` if converged within `max_iter` steps, or `Err` with the
502    /// best solution found.
503    pub fn ik_newton_raphson(
504        &self,
505        target: [f64; 3],
506        q_init: &[f64],
507        max_iter: usize,
508        tol: f64,
509        lambda: f64,
510    ) -> Result<Vec<f64>, Vec<f64>> {
511        let mut q = q_init.to_vec();
512        let n = q.len();
513        for _iter in 0..max_iter {
514            let p = self.end_effector_pos(&q);
515            let e = sub3(target, p);
516            if len3(e) < tol {
517                return Ok(q);
518            }
519            let j = self.jacobian_analytical(&q);
520            let jp = Self::jacobian_pseudoinverse(&j, n, lambda);
521            // dq = J^+ * e
522            for i in 0..n {
523                let dqi = jp[i * 3] * e[0] + jp[i * 3 + 1] * e[1] + jp[i * 3 + 2] * e[2];
524                q[i] += dqi;
525            }
526            // Enforce joint limits
527            for (i, link) in self.links.iter().enumerate() {
528                if link.joint_type == JointType::Fixed {
529                    continue;
530                }
531                let qi_idx = self.joint_index(i);
532                if let (Some(qi_idx), Some(lim)) = (qi_idx, &link.limits)
533                    && qi_idx < q.len()
534                {
535                    q[qi_idx] = lim.clamp(q[qi_idx]);
536                }
537            }
538        }
539        Err(q)
540    }
541
542    /// Returns the q-vector index for link `link_idx`, or `None` if fixed.
543    fn joint_index(&self, link_idx: usize) -> Option<usize> {
544        let mut idx = 0usize;
545        for (i, l) in self.links.iter().enumerate() {
546            if l.joint_type == JointType::Fixed {
547                continue;
548            }
549            if i == link_idx {
550                return Some(idx);
551            }
552            idx += 1;
553        }
554        None
555    }
556
557    // -----------------------------------------------------------------------
558    // Workspace Monte-Carlo
559    // -----------------------------------------------------------------------
560
561    /// Samples `n_samples` random joint configurations and returns the set of
562    /// reachable end-effector positions.
563    pub fn workspace_monte_carlo(&self, n_samples: usize) -> Vec<[f64; 3]> {
564        let mut rng = rand::rng();
565        let dof = self.dof();
566        let limits: Vec<JointLimits> = self
567            .links
568            .iter()
569            .filter(|l| l.joint_type != JointType::Fixed)
570            .map(|l| l.limits.unwrap_or(JointLimits::new(-PI, PI, 10.0, 100.0)))
571            .collect();
572        let mut points = Vec::with_capacity(n_samples);
573        for _ in 0..n_samples {
574            let q: Vec<f64> = (0..dof)
575                .map(|i| rng.random_range(limits[i].min..limits[i].max))
576                .collect();
577            points.push(self.end_effector_pos(&q));
578        }
579        points
580    }
581
582    /// Estimates the reachable workspace bounding box from a Monte-Carlo sample.
583    ///
584    /// Returns `(min_corner, max_corner)` or `None` if no samples.
585    pub fn workspace_bounding_box(&self, n_samples: usize) -> Option<([f64; 3], [f64; 3])> {
586        let pts = self.workspace_monte_carlo(n_samples);
587        if pts.is_empty() {
588            return None;
589        }
590        let mut mn = pts[0];
591        let mut mx = pts[0];
592        for p in &pts[1..] {
593            for k in 0..3 {
594                if p[k] < mn[k] {
595                    mn[k] = p[k];
596                }
597                if p[k] > mx[k] {
598                    mx[k] = p[k];
599                }
600            }
601        }
602        Some((mn, mx))
603    }
604
605    // -----------------------------------------------------------------------
606    // Collision helpers
607    // -----------------------------------------------------------------------
608
609    /// Returns all link capsule endpoints in world space for configuration `q`.
610    ///
611    /// Each entry is `(p_start, p_end, radius)` describing the capsule axis.
612    pub fn link_capsules(&self, q: &[f64]) -> Vec<([f64; 3], [f64; 3], f64)> {
613        let frames = self.forward_frames(q);
614        let mut caps = Vec::with_capacity(self.links.len());
615        for (i, link) in self.links.iter().enumerate() {
616            let frame = &frames[i + 1];
617            let center = mat4_translation(frame);
618            // Local capsule axis is along local Z
619            let z_world = [frame[2], frame[6], frame[10]];
620            let hl = link.collision_half_len;
621            let p_start = sub3(center, scale3(z_world, hl));
622            let p_end = add3(center, scale3(z_world, hl));
623            caps.push((p_start, p_end, link.collision_radius));
624        }
625        caps
626    }
627
628    /// Checks whether any robot link capsule intersects an obstacle sphere.
629    ///
630    /// Returns `true` if any link is in collision.
631    pub fn check_collision_sphere(
632        &self,
633        q: &[f64],
634        sphere_center: [f64; 3],
635        sphere_radius: f64,
636    ) -> bool {
637        for (a, b, r) in self.link_capsules(q) {
638            let dist = dist_point_segment(sphere_center, a, b);
639            if dist < r + sphere_radius {
640                return true;
641            }
642        }
643        false
644    }
645
646    /// Checks whether any robot link capsule intersects an axis-aligned box.
647    ///
648    /// Returns `true` if any link is in collision.
649    pub fn check_collision_aabb(&self, q: &[f64], box_min: [f64; 3], box_max: [f64; 3]) -> bool {
650        for (a, b, r) in self.link_capsules(q) {
651            if capsule_aabb_overlap(a, b, r, box_min, box_max) {
652                return true;
653            }
654        }
655        false
656    }
657
658    // -----------------------------------------------------------------------
659    // Self-collision detection
660    // -----------------------------------------------------------------------
661
662    /// Detects self-collision between non-adjacent link capsules.
663    ///
664    /// Links with indices that differ by 1 (adjacent) are always skipped.
665    /// Returns `true` if any non-adjacent pair of capsules overlaps.
666    pub fn check_self_collision(&self, q: &[f64]) -> bool {
667        let caps = self.link_capsules(q);
668        let n = caps.len();
669        for i in 0..n {
670            for j in (i + 2)..n {
671                let (a1, b1, r1) = caps[i];
672                let (a2, b2, r2) = caps[j];
673                let dist = dist_segment_segment(a1, b1, a2, b2);
674                if dist < r1 + r2 {
675                    return true;
676                }
677            }
678        }
679        false
680    }
681
682    // -----------------------------------------------------------------------
683    // Joint limit checking
684    // -----------------------------------------------------------------------
685
686    /// Returns `true` if all joint values in `q` satisfy the robot's joint limits.
687    pub fn joints_within_limits(&self, q: &[f64]) -> bool {
688        let mut qi = 0usize;
689        for link in &self.links {
690            if link.joint_type == JointType::Fixed {
691                continue;
692            }
693            if qi >= q.len() {
694                break;
695            }
696            if let Some(lim) = &link.limits
697                && !lim.is_within(q[qi])
698            {
699                return false;
700            }
701            qi += 1;
702        }
703        true
704    }
705
706    /// Clamps all joints in `q` to the robot's limits and returns the result.
707    pub fn clamp_joints(&self, q: &[f64]) -> Vec<f64> {
708        let mut out = q.to_vec();
709        let mut qi = 0usize;
710        for link in &self.links {
711            if link.joint_type == JointType::Fixed {
712                continue;
713            }
714            if qi >= out.len() {
715                break;
716            }
717            if let Some(lim) = &link.limits {
718                out[qi] = lim.clamp(out[qi]);
719            }
720            qi += 1;
721        }
722        out
723    }
724
725    // -----------------------------------------------------------------------
726    // Swept volume
727    // -----------------------------------------------------------------------
728
729    /// Computes a coarse AABB for the swept volume of the end-effector as joints
730    /// vary linearly from `q_start` to `q_end` using `n_steps` samples.
731    pub fn swept_volume_aabb(
732        &self,
733        q_start: &[f64],
734        q_end: &[f64],
735        n_steps: usize,
736    ) -> ([f64; 3], [f64; 3]) {
737        let n_steps = n_steps.max(2);
738        let mut mn = [f64::INFINITY; 3];
739        let mut mx = [f64::NEG_INFINITY; 3];
740        for step in 0..=n_steps {
741            let t = step as f64 / n_steps as f64;
742            let q: Vec<f64> = q_start
743                .iter()
744                .zip(q_end.iter())
745                .map(|(a, b)| a + t * (b - a))
746                .collect();
747            let p = self.end_effector_pos(&q);
748            for k in 0..3 {
749                if p[k] < mn[k] {
750                    mn[k] = p[k];
751                }
752                if p[k] > mx[k] {
753                    mx[k] = p[k];
754                }
755            }
756        }
757        (mn, mx)
758    }
759
760    // -----------------------------------------------------------------------
761    // Manipulability measure
762    // -----------------------------------------------------------------------
763
764    /// Computes Yoshikawa's manipulability measure `sqrt(det(J J^T))`.
765    ///
766    /// High values indicate configurations far from singularities.
767    pub fn manipulability(&self, q: &[f64]) -> f64 {
768        let n = q.len();
769        let j = self.jacobian_analytical(q);
770        // Compute J J^T (3×3)
771        let mut a = [0.0f64; 9];
772        for r in 0..3 {
773            for c in 0..3 {
774                let mut s = 0.0f64;
775                for k in 0..n {
776                    s += j[r * n + k] * j[c * n + k];
777                }
778                a[r * 3 + c] = s;
779            }
780        }
781        mat3_det(&a).abs().sqrt()
782    }
783}
784
785// ---------------------------------------------------------------------------
786// 3×3 matrix helpers
787// ---------------------------------------------------------------------------
788
789/// Computes the determinant of a 3×3 row-major matrix.
790pub fn mat3_det(m: &[f64; 9]) -> f64 {
791    m[0] * (m[4] * m[8] - m[5] * m[7]) - m[1] * (m[3] * m[8] - m[5] * m[6])
792        + m[2] * (m[3] * m[7] - m[4] * m[6])
793}
794
795/// Computes the inverse of a 3×3 row-major matrix.
796///
797/// Returns the zero matrix if the determinant is near zero.
798pub fn mat3_inverse(m: &[f64; 9]) -> [f64; 9] {
799    let det = mat3_det(m);
800    if det.abs() < 1e-14 {
801        return [0.0; 9];
802    }
803    let inv_det = 1.0 / det;
804    [
805        (m[4] * m[8] - m[5] * m[7]) * inv_det,
806        (m[2] * m[7] - m[1] * m[8]) * inv_det,
807        (m[1] * m[5] - m[2] * m[4]) * inv_det,
808        (m[5] * m[6] - m[3] * m[8]) * inv_det,
809        (m[0] * m[8] - m[2] * m[6]) * inv_det,
810        (m[2] * m[3] - m[0] * m[5]) * inv_det,
811        (m[3] * m[7] - m[4] * m[6]) * inv_det,
812        (m[1] * m[6] - m[0] * m[7]) * inv_det,
813        (m[0] * m[4] - m[1] * m[3]) * inv_det,
814    ]
815}
816
817/// Transposes a 4×4 row-major matrix.
818pub fn mat4_transpose(m: &Mat4) -> Mat4 {
819    let mut t = [0.0f64; 16];
820    for r in 0..4 {
821        for c in 0..4 {
822            t[c * 4 + r] = m[r * 4 + c];
823        }
824    }
825    t
826}
827
828// ---------------------------------------------------------------------------
829// Geometry primitives for collision
830// ---------------------------------------------------------------------------
831
832/// Minimum distance from point `p` to line segment `[a, b]`.
833pub fn dist_point_segment(p: [f64; 3], a: [f64; 3], b: [f64; 3]) -> f64 {
834    let ab = sub3(b, a);
835    let ap = sub3(p, a);
836    let t = dot3(ap, ab) / (dot3(ab, ab) + 1e-30);
837    let t = t.clamp(0.0, 1.0);
838    let closest = add3(a, scale3(ab, t));
839    len3(sub3(p, closest))
840}
841
842/// Minimum distance between two line segments `[a1,b1]` and `[a2,b2]`.
843pub fn dist_segment_segment(a1: [f64; 3], b1: [f64; 3], a2: [f64; 3], b2: [f64; 3]) -> f64 {
844    let d1 = sub3(b1, a1);
845    let d2 = sub3(b2, a2);
846    let r = sub3(a1, a2);
847    let a = dot3(d1, d1);
848    let e = dot3(d2, d2);
849    let f = dot3(d2, r);
850    let eps = 1e-14;
851
852    let (s, t) = if a < eps && e < eps {
853        (0.0f64, 0.0f64)
854    } else if a < eps {
855        (0.0f64, (f / e).clamp(0.0, 1.0))
856    } else {
857        let c = dot3(d1, r);
858        if e < eps {
859            (((-c) / a).clamp(0.0, 1.0), 0.0)
860        } else {
861            let b = dot3(d1, d2);
862            let denom = a * e - b * b;
863            let s = if denom.abs() > eps {
864                ((b * f - c * e) / denom).clamp(0.0, 1.0)
865            } else {
866                0.0
867            };
868            let t = (b * s + f) / e;
869            if t < 0.0 {
870                let s = ((-c) / a).clamp(0.0, 1.0);
871                (s, 0.0f64)
872            } else if t > 1.0 {
873                let s = ((b - c) / a).clamp(0.0, 1.0);
874                (s, 1.0f64)
875            } else {
876                (s, t)
877            }
878        }
879    };
880    let c1 = add3(a1, scale3(d1, s));
881    let c2 = add3(a2, scale3(d2, t));
882    len3(sub3(c1, c2))
883}
884
885/// Tests whether a capsule (axis `[a,b]`, radius `r`) overlaps an AABB.
886pub fn capsule_aabb_overlap(
887    a: [f64; 3],
888    b: [f64; 3],
889    r: f64,
890    box_min: [f64; 3],
891    box_max: [f64; 3],
892) -> bool {
893    // Closest point on segment to AABB center
894    let center = [
895        (box_min[0] + box_max[0]) * 0.5,
896        (box_min[1] + box_max[1]) * 0.5,
897        (box_min[2] + box_max[2]) * 0.5,
898    ];
899    let half = [
900        (box_max[0] - box_min[0]) * 0.5,
901        (box_max[1] - box_min[1]) * 0.5,
902        (box_max[2] - box_min[2]) * 0.5,
903    ];
904    let ab = sub3(b, a);
905    let ac = sub3(center, a);
906    let t = (dot3(ac, ab) / (dot3(ab, ab) + 1e-30)).clamp(0.0, 1.0);
907    let closest_on_seg = add3(a, scale3(ab, t));
908    // Clamp to box
909    let mut dist_sq = 0.0f64;
910    for k in 0..3 {
911        let v = closest_on_seg[k];
912        let lo = box_min[k];
913        let hi = box_max[k];
914        if v < lo {
915            dist_sq += (lo - v) * (lo - v);
916        } else if v > hi {
917            dist_sq += (v - hi) * (v - hi);
918        }
919    }
920    let _ = half; // used implicitly via box_min/box_max
921    dist_sq <= r * r
922}
923
924// ---------------------------------------------------------------------------
925// Preset robot constructors
926// ---------------------------------------------------------------------------
927
928/// Builds a 3-DOF planar robot arm (all joints revolute, links in XY plane).
929///
930/// `lengths`: link lengths in metres.
931pub fn build_planar_3dof(lengths: [f64; 3]) -> RobotArm {
932    let lim = JointLimits::new(-PI, PI, 3.0, 50.0);
933    let links = vec![
934        RobotLink::new(
935            "link1",
936            DhParam::new(0.0, 0.0, lengths[0], 0.0),
937            JointType::Revolute,
938            Some(lim),
939            0.03,
940            lengths[0] * 0.5,
941        ),
942        RobotLink::new(
943            "link2",
944            DhParam::new(0.0, 0.0, lengths[1], 0.0),
945            JointType::Revolute,
946            Some(lim),
947            0.03,
948            lengths[1] * 0.5,
949        ),
950        RobotLink::new(
951            "link3",
952            DhParam::new(0.0, 0.0, lengths[2], 0.0),
953            JointType::Revolute,
954            Some(lim),
955            0.03,
956            lengths[2] * 0.5,
957        ),
958    ];
959    RobotArm::new("planar_3dof", links)
960}
961
962/// Builds a 6-DOF robot arm using standard Puma-like DH parameters.
963pub fn build_6dof_puma_like() -> RobotArm {
964    let lim_base = JointLimits::new(-PI, PI, 2.0, 150.0);
965    let lim_elbow = JointLimits::new(-PI * 0.75, PI * 0.75, 2.0, 100.0);
966    let lim_wrist = JointLimits::new(-PI, PI, 3.0, 50.0);
967
968    let links = vec![
969        RobotLink::new(
970            "joint1",
971            DhParam::new(0.0, 0.36, 0.0, PI / 2.0),
972            JointType::Revolute,
973            Some(lim_base),
974            0.06,
975            0.18,
976        ),
977        RobotLink::new(
978            "joint2",
979            DhParam::new(0.0, 0.0, 0.43, 0.0),
980            JointType::Revolute,
981            Some(lim_elbow),
982            0.05,
983            0.215,
984        ),
985        RobotLink::new(
986            "joint3",
987            DhParam::new(0.0, 0.0, 0.0, PI / 2.0),
988            JointType::Revolute,
989            Some(lim_elbow),
990            0.05,
991            0.05,
992        ),
993        RobotLink::new(
994            "joint4",
995            DhParam::new(0.0, 0.43, 0.0, -PI / 2.0),
996            JointType::Revolute,
997            Some(lim_wrist),
998            0.04,
999            0.215,
1000        ),
1001        RobotLink::new(
1002            "joint5",
1003            DhParam::new(0.0, 0.0, 0.0, PI / 2.0),
1004            JointType::Revolute,
1005            Some(lim_wrist),
1006            0.04,
1007            0.04,
1008        ),
1009        RobotLink::new(
1010            "joint6",
1011            DhParam::new(0.0, 0.1, 0.0, 0.0),
1012            JointType::Revolute,
1013            Some(lim_wrist),
1014            0.03,
1015            0.05,
1016        ),
1017    ];
1018    RobotArm::new("puma_6dof", links)
1019}
1020
1021// ---------------------------------------------------------------------------
1022// URDF-like robot description (from struct)
1023// ---------------------------------------------------------------------------
1024
1025/// A joint in a URDF-like robot description.
1026#[derive(Debug, Clone)]
1027pub struct UrdfJoint {
1028    /// Joint name.
1029    pub name: String,
1030    /// Parent link name.
1031    pub parent: String,
1032    /// Child link name.
1033    pub child: String,
1034    /// Joint type.
1035    pub joint_type: JointType,
1036    /// Joint origin XYZ.
1037    pub origin_xyz: [f64; 3],
1038    /// Joint origin RPY.
1039    pub origin_rpy: [f64; 3],
1040    /// Joint axis.
1041    pub axis: [f64; 3],
1042    /// Optional limits.
1043    pub limits: Option<JointLimits>,
1044}
1045
1046/// A link in a URDF-like description.
1047#[derive(Debug, Clone)]
1048pub struct UrdfLink {
1049    /// Link name.
1050    pub name: String,
1051    /// Collision geometry radius (simplified capsule).
1052    pub collision_radius: f64,
1053    /// Collision geometry half-length.
1054    pub collision_half_len: f64,
1055}
1056
1057/// A complete URDF-like robot description parsed from structs.
1058#[derive(Debug, Clone)]
1059pub struct UrdfRobot {
1060    /// Robot name.
1061    pub name: String,
1062    /// All links.
1063    pub links: Vec<UrdfLink>,
1064    /// All joints.
1065    pub joints: Vec<UrdfJoint>,
1066}
1067
1068impl UrdfRobot {
1069    /// Converts this URDF-like description into a `RobotArm`.
1070    ///
1071    /// Only supports simple serial chains (first joint chain from base).
1072    pub fn to_robot_arm(&self) -> RobotArm {
1073        let arm_links: Vec<RobotLink> = self
1074            .joints
1075            .iter()
1076            .map(|jt| {
1077                let collision = self
1078                    .links
1079                    .iter()
1080                    .find(|l| l.name == jt.child)
1081                    .map(|l| (l.collision_radius, l.collision_half_len))
1082                    .unwrap_or((0.05, 0.1));
1083                // Build DH-approximated transform from RPY + XYZ
1084                let dh = rpy_xyz_to_dh(jt.origin_rpy, jt.origin_xyz);
1085                RobotLink::new(
1086                    &jt.name,
1087                    dh,
1088                    jt.joint_type,
1089                    jt.limits,
1090                    collision.0,
1091                    collision.1,
1092                )
1093            })
1094            .collect();
1095        RobotArm::new(&self.name, arm_links)
1096    }
1097}
1098
1099/// Approximates DH parameters from RPY and XYZ joint origin data.
1100///
1101/// This is a simplified mapping; full DH extraction requires more link data.
1102fn rpy_xyz_to_dh(rpy: [f64; 3], xyz: [f64; 3]) -> DhParam {
1103    let a = (xyz[0] * xyz[0] + xyz[1] * xyz[1]).sqrt();
1104    DhParam::new(rpy[2], xyz[2], a, rpy[0])
1105}
1106
1107// ---------------------------------------------------------------------------
1108// Velocity and acceleration analysis
1109// ---------------------------------------------------------------------------
1110
1111/// Computes the end-effector Cartesian velocity given joint velocities `dq`.
1112///
1113/// `v = J * dq`  (3-vector)
1114pub fn end_effector_velocity(jacobian: &[f64], dq: &[f64]) -> [f64; 3] {
1115    let n = dq.len();
1116    let mut v = [0.0f64; 3];
1117    for row in 0..3 {
1118        for k in 0..n {
1119            v[row] += jacobian[row * n + k] * dq[k];
1120        }
1121    }
1122    v
1123}
1124
1125/// Computes the minimum norm joint velocity for a desired Cartesian velocity.
1126///
1127/// Uses the damped pseudo-inverse: `dq = J^+ * v`.
1128pub fn joint_velocity_from_cartesian(
1129    jacobian: &[f64],
1130    n_dof: usize,
1131    v_desired: [f64; 3],
1132    lambda: f64,
1133) -> Vec<f64> {
1134    let jp = RobotArm::jacobian_pseudoinverse(jacobian, n_dof, lambda);
1135    let mut dq = vec![0.0f64; n_dof];
1136    for i in 0..n_dof {
1137        dq[i] =
1138            jp[i * 3] * v_desired[0] + jp[i * 3 + 1] * v_desired[1] + jp[i * 3 + 2] * v_desired[2];
1139    }
1140    dq
1141}
1142
1143// ---------------------------------------------------------------------------
1144// Singularity analysis
1145// ---------------------------------------------------------------------------
1146
1147/// Classifies the manipulability of a configuration.
1148#[derive(Debug, Clone, Copy, PartialEq)]
1149pub enum SingularityClass {
1150    /// Far from any singularity.
1151    Regular,
1152    /// Close to (but not at) a singularity.
1153    NearSingular,
1154    /// At or very close to a type-1 (boundary) singularity.
1155    BoundarySingular,
1156    /// At or very close to a type-2 (interior) singularity.
1157    InteriorSingular,
1158}
1159
1160/// Classifies the singularity of a configuration from its manipulability value.
1161pub fn classify_singularity(manipulability: f64) -> SingularityClass {
1162    if manipulability < 1e-6 {
1163        SingularityClass::InteriorSingular
1164    } else if manipulability < 1e-3 {
1165        SingularityClass::BoundarySingular
1166    } else if manipulability < 0.05 {
1167        SingularityClass::NearSingular
1168    } else {
1169        SingularityClass::Regular
1170    }
1171}
1172
1173// ---------------------------------------------------------------------------
1174// Condition number of Jacobian
1175// ---------------------------------------------------------------------------
1176
1177/// Estimates the condition number of the `3×n` Jacobian via the ratio of
1178/// the largest to smallest singular value approximation.
1179///
1180/// Uses power iteration to find the largest and smallest "effective"
1181/// singular values via `J J^T`.
1182pub fn jacobian_condition_number(jacobian: &[f64], n: usize) -> f64 {
1183    // Form J J^T (3×3)
1184    let mut a = [0.0f64; 9];
1185    for r in 0..3 {
1186        for c in 0..3 {
1187            let mut s = 0.0f64;
1188            for k in 0..n {
1189                s += jacobian[r * n + k] * jacobian[c * n + k];
1190            }
1191            a[r * 3 + c] = s;
1192        }
1193    }
1194    // Frobenius norm as proxy for max singular value (fast approximation)
1195    let frob: f64 = a.iter().map(|x| x * x).sum::<f64>().sqrt();
1196    let det = mat3_det(&a).abs();
1197    if frob < 1e-14 {
1198        return f64::INFINITY;
1199    }
1200    // min_sv ≈ det / (frob^2) for 3×3 case
1201    let min_sv_approx = det / (frob * frob + 1e-30);
1202    frob / (min_sv_approx + 1e-30)
1203}
1204
1205// ---------------------------------------------------------------------------
1206// Path planning helpers
1207// ---------------------------------------------------------------------------
1208
1209/// Generates a linear interpolation path in joint space.
1210///
1211/// Returns `n_steps + 1` joint configurations from `q_start` to `q_end`.
1212pub fn joint_space_path(q_start: &[f64], q_end: &[f64], n_steps: usize) -> Vec<Vec<f64>> {
1213    let n_steps = n_steps.max(1);
1214    (0..=n_steps)
1215        .map(|step| {
1216            let t = step as f64 / n_steps as f64;
1217            q_start
1218                .iter()
1219                .zip(q_end.iter())
1220                .map(|(a, b)| a + t * (b - a))
1221                .collect()
1222        })
1223        .collect()
1224}
1225
1226/// Checks whether every configuration along a straight-line joint-space path
1227/// is within joint limits and collision-free with respect to a sphere obstacle.
1228pub fn path_collision_free(
1229    arm: &RobotArm,
1230    path: &[Vec<f64>],
1231    sphere_center: [f64; 3],
1232    sphere_radius: f64,
1233) -> bool {
1234    for q in path {
1235        if arm.check_collision_sphere(q, sphere_center, sphere_radius) {
1236            return false;
1237        }
1238        if !arm.joints_within_limits(q) {
1239            return false;
1240        }
1241    }
1242    true
1243}
1244
1245// ---------------------------------------------------------------------------
1246// Torque / statics analysis
1247// ---------------------------------------------------------------------------
1248
1249/// Computes the joint torques required to produce a given end-effector force.
1250///
1251/// Uses the static relationship `τ = J^T f`.
1252pub fn joint_torques_from_force(jacobian: &[f64], n_dof: usize, force: [f64; 3]) -> Vec<f64> {
1253    let mut tau = vec![0.0f64; n_dof];
1254    for i in 0..n_dof {
1255        tau[i] = jacobian[i] * force[0]
1256            + jacobian[n_dof + i] * force[1]
1257            + jacobian[2 * n_dof + i] * force[2];
1258    }
1259    tau
1260}
1261
1262// ---------------------------------------------------------------------------
1263// Reachability map
1264// ---------------------------------------------------------------------------
1265
1266/// A coarse voxel reachability map for a robot arm.
1267///
1268/// Populated by Monte-Carlo workspace sampling.
1269#[derive(Debug, Clone)]
1270pub struct ReachabilityMap {
1271    /// World-space origin of the voxel grid.
1272    pub origin: [f64; 3],
1273    /// Size of each voxel in metres.
1274    pub voxel_size: f64,
1275    /// Number of voxels along each axis.
1276    pub dims: [usize; 3],
1277    /// Flat array of occupancy counts.
1278    pub counts: Vec<u32>,
1279}
1280
1281impl ReachabilityMap {
1282    /// Creates an empty reachability map.
1283    pub fn new(origin: [f64; 3], voxel_size: f64, dims: [usize; 3]) -> Self {
1284        let total = dims[0] * dims[1] * dims[2];
1285        Self {
1286            origin,
1287            voxel_size,
1288            dims,
1289            counts: vec![0u32; total],
1290        }
1291    }
1292
1293    /// Converts a world position to a voxel index, returning `None` if outside.
1294    pub fn world_to_voxel(&self, p: [f64; 3]) -> Option<[usize; 3]> {
1295        let mut idx = [0usize; 3];
1296        for k in 0..3 {
1297            let v = (p[k] - self.origin[k]) / self.voxel_size;
1298            if v < 0.0 || v >= self.dims[k] as f64 {
1299                return None;
1300            }
1301            idx[k] = v as usize;
1302        }
1303        Some(idx)
1304    }
1305
1306    /// Increments the occupancy count for the voxel at world position `p`.
1307    pub fn add_point(&mut self, p: [f64; 3]) {
1308        if let Some(idx) = self.world_to_voxel(p) {
1309            let flat = idx[0] * self.dims[1] * self.dims[2] + idx[1] * self.dims[2] + idx[2];
1310            self.counts[flat] = self.counts[flat].saturating_add(1);
1311        }
1312    }
1313
1314    /// Populates the map from a Monte-Carlo workspace sample.
1315    pub fn populate(&mut self, arm: &RobotArm, n_samples: usize) {
1316        let pts = arm.workspace_monte_carlo(n_samples);
1317        for p in pts {
1318            self.add_point(p);
1319        }
1320    }
1321
1322    /// Returns the total number of non-zero voxels (reachable cells).
1323    pub fn reachable_count(&self) -> usize {
1324        self.counts.iter().filter(|&&c| c > 0).count()
1325    }
1326}
1327
1328// ---------------------------------------------------------------------------
1329// Unit tests
1330// ---------------------------------------------------------------------------
1331
1332#[cfg(test)]
1333mod tests {
1334    use super::*;
1335
1336    fn planar_arm() -> RobotArm {
1337        build_planar_3dof([0.5, 0.4, 0.3])
1338    }
1339
1340    fn puma_arm() -> RobotArm {
1341        build_6dof_puma_like()
1342    }
1343
1344    // --- DH parameter tests ---
1345
1346    #[test]
1347    fn test_dh_identity_at_zero() {
1348        let dh = DhParam::new(0.0, 0.0, 0.0, 0.0);
1349        let t = dh.transform();
1350        let ident = mat4_identity();
1351        for i in 0..16 {
1352            assert!(
1353                (t[i] - ident[i]).abs() < 1e-12,
1354                "DH identity mismatch at {i}"
1355            );
1356        }
1357    }
1358
1359    #[test]
1360    fn test_dh_pure_translation_a() {
1361        let a = 1.0;
1362        let dh = DhParam::new(0.0, 0.0, a, 0.0);
1363        let t = dh.transform();
1364        // Should translate by a along X
1365        assert!((t[3] - a).abs() < 1e-12);
1366        assert!(t[7].abs() < 1e-12);
1367        assert!(t[11].abs() < 1e-12);
1368    }
1369
1370    #[test]
1371    fn test_dh_pure_translation_d() {
1372        let d = 2.0;
1373        let dh = DhParam::new(0.0, d, 0.0, 0.0);
1374        let t = dh.transform();
1375        // Should translate by d along Z
1376        assert!((t[11] - d).abs() < 1e-12);
1377    }
1378
1379    #[test]
1380    fn test_dh_rotation_theta() {
1381        let dh = DhParam::new(PI / 2.0, 0.0, 0.0, 0.0);
1382        let t = dh.transform();
1383        // Rz(pi/2): cos -> 0, sin -> 1
1384        assert!(t[0].abs() < 1e-12); // cos
1385        assert!((t[1] + 1.0).abs() < 1e-12); // -sin
1386        assert!((t[4] - 1.0).abs() < 1e-12); // sin
1387    }
1388
1389    #[test]
1390    fn test_mat4_mul_identity() {
1391        let ident = mat4_identity();
1392        let a = rot_z(0.5);
1393        let result = mat4_mul(&a, &ident);
1394        for i in 0..16 {
1395            assert!(
1396                (result[i] - a[i]).abs() < 1e-12,
1397                "mul ident mismatch at {i}"
1398            );
1399        }
1400    }
1401
1402    #[test]
1403    fn test_mat4_transpose_roundtrip() {
1404        let m = rot_z(1.2);
1405        let tt = mat4_transpose(&mat4_transpose(&m));
1406        for i in 0..16 {
1407            assert!((tt[i] - m[i]).abs() < 1e-12);
1408        }
1409    }
1410
1411    // --- Forward kinematics ---
1412
1413    #[test]
1414    fn test_fk_zero_config_planar_x() {
1415        let arm = planar_arm();
1416        let q = vec![0.0f64; 3];
1417        let pos = arm.end_effector_pos(&q);
1418        // All links along X: pos ~ [0.5+0.4+0.3, 0, 0]
1419        assert!((pos[0] - 1.2).abs() < 1e-10);
1420        assert!(pos[1].abs() < 1e-10);
1421        assert!(pos[2].abs() < 1e-10);
1422    }
1423
1424    #[test]
1425    fn test_fk_pi_fold() {
1426        let arm = planar_arm();
1427        // With q2 = PI, end-effector folds back
1428        let q = vec![0.0, PI, 0.0];
1429        let pos = arm.end_effector_pos(&q);
1430        // link1(0.5) + link2*cos(pi)(-0.4) + link3*cos(pi)(-0.3) ≈ 0.5-0.4-0.3 = -0.2
1431        assert!((pos[0] - (-0.2)).abs() < 1e-8);
1432    }
1433
1434    #[test]
1435    fn test_fk_frames_count() {
1436        let arm = planar_arm();
1437        let q = vec![0.0f64; 3];
1438        let frames = arm.forward_frames(&q);
1439        // 1 base + 3 links = 4
1440        assert_eq!(frames.len(), 4);
1441    }
1442
1443    #[test]
1444    fn test_dof_count() {
1445        let arm = planar_arm();
1446        assert_eq!(arm.dof(), 3);
1447    }
1448
1449    #[test]
1450    fn test_dof_puma() {
1451        let arm = puma_arm();
1452        assert_eq!(arm.dof(), 6);
1453    }
1454
1455    // --- Joint limits ---
1456
1457    #[test]
1458    fn test_joint_limits_within() {
1459        let lim = JointLimits::new(-PI, PI, 3.0, 50.0);
1460        assert!(lim.is_within(0.0));
1461        assert!(lim.is_within(-PI));
1462        assert!(lim.is_within(PI));
1463        assert!(!lim.is_within(PI + 0.001));
1464    }
1465
1466    #[test]
1467    fn test_joint_limits_clamp() {
1468        let lim = JointLimits::new(-1.0, 1.0, 1.0, 10.0);
1469        assert_eq!(lim.clamp(2.0), 1.0);
1470        assert_eq!(lim.clamp(-2.0), -1.0);
1471        assert_eq!(lim.clamp(0.5), 0.5);
1472    }
1473
1474    #[test]
1475    fn test_joints_within_limits_planar() {
1476        let arm = planar_arm();
1477        assert!(arm.joints_within_limits(&[0.0, 0.0, 0.0]));
1478        assert!(!arm.joints_within_limits(&[4.0, 0.0, 0.0])); // > PI
1479    }
1480
1481    #[test]
1482    fn test_clamp_joints_planar() {
1483        let arm = planar_arm();
1484        let clamped = arm.clamp_joints(&[5.0, -5.0, 0.0]);
1485        assert!((clamped[0] - PI).abs() < 1e-12);
1486        assert!((clamped[1] - (-PI)).abs() < 1e-12);
1487    }
1488
1489    // --- Jacobian tests ---
1490
1491    #[test]
1492    fn test_jacobian_numerical_size() {
1493        let arm = planar_arm();
1494        let q = vec![0.1, 0.2, 0.3];
1495        let j = arm.jacobian_numerical(&q);
1496        assert_eq!(j.len(), 3 * 3);
1497    }
1498
1499    #[test]
1500    fn test_jacobian_analytical_matches_numerical() {
1501        let arm = planar_arm();
1502        let q = vec![0.2, -0.3, 0.5];
1503        let jn = arm.jacobian_numerical(&q);
1504        let ja = arm.jacobian_analytical(&q);
1505        for i in 0..9 {
1506            assert!(
1507                (jn[i] - ja[i]).abs() < 1e-4,
1508                "Jacobian mismatch at {i}: numerical={} analytical={}",
1509                jn[i],
1510                ja[i]
1511            );
1512        }
1513    }
1514
1515    #[test]
1516    fn test_jacobian_pseudoinverse_identity_check() {
1517        // For a simple scalar case: J = [1,0,0; 0,1,0; 0,0,1], pinv = identity
1518        let j: Vec<f64> = vec![1.0, 0.0, 0.0, 0.0, 1.0, 0.0, 0.0, 0.0, 1.0];
1519        let jp = RobotArm::jacobian_pseudoinverse(&j, 3, 0.0001);
1520        // jp should be approximately identity (3x3 = n=3, result is 3x3 n×3)
1521        assert!((jp[0] - 1.0).abs() < 1e-3);
1522        assert!((jp[4] - 1.0).abs() < 1e-3);
1523        assert!((jp[8] - 1.0).abs() < 1e-3);
1524    }
1525
1526    // --- IK tests ---
1527
1528    #[test]
1529    fn test_ik_reachable_target() {
1530        let arm = planar_arm();
1531        let target = [0.8, 0.4, 0.0];
1532        let q_init = vec![0.1f64, 0.2, 0.1];
1533        let result = arm.ik_newton_raphson(target, &q_init, 200, 1e-6, 0.01);
1534        let q = match result {
1535            Ok(q) | Err(q) => q,
1536        };
1537        let pos = arm.end_effector_pos(&q);
1538        assert!(
1539            len3(sub3(target, pos)) < 0.05,
1540            "IK did not converge close enough"
1541        );
1542    }
1543
1544    #[test]
1545    fn test_ik_at_zero_config() {
1546        let arm = planar_arm();
1547        let target = arm.end_effector_pos(&[0.0, 0.0, 0.0]);
1548        let q_init = vec![0.01f64, 0.01, 0.01];
1549        let result = arm.ik_newton_raphson(target, &q_init, 200, 1e-8, 0.001);
1550        let q = match result {
1551            Ok(q) | Err(q) => q,
1552        };
1553        let pos = arm.end_effector_pos(&q);
1554        assert!(len3(sub3(target, pos)) < 1e-4);
1555    }
1556
1557    // --- Collision tests ---
1558
1559    #[test]
1560    fn test_dist_point_segment_basic() {
1561        let d = dist_point_segment([0.0, 1.0, 0.0], [0.0, 0.0, 0.0], [1.0, 0.0, 0.0]);
1562        assert!((d - 1.0).abs() < 1e-12);
1563    }
1564
1565    #[test]
1566    fn test_dist_point_segment_on_segment() {
1567        let d = dist_point_segment([0.5, 0.0, 0.0], [0.0, 0.0, 0.0], [1.0, 0.0, 0.0]);
1568        assert!(d.abs() < 1e-12);
1569    }
1570
1571    #[test]
1572    fn test_collision_sphere_no_hit() {
1573        let arm = planar_arm();
1574        let q = vec![0.0f64; 3];
1575        // Sphere far away
1576        let hit = arm.check_collision_sphere(&q, [10.0, 10.0, 10.0], 0.01);
1577        assert!(!hit);
1578    }
1579
1580    #[test]
1581    fn test_collision_sphere_hit() {
1582        let arm = planar_arm();
1583        let q = vec![0.0f64; 3];
1584        // Sphere at robot base position
1585        let hit = arm.check_collision_sphere(&q, [0.25, 0.0, 0.0], 0.3);
1586        assert!(hit);
1587    }
1588
1589    #[test]
1590    fn test_self_collision_straight() {
1591        let arm = planar_arm();
1592        // Straight configuration — no self-collision expected
1593        let q = vec![0.0f64; 3];
1594        assert!(!arm.check_self_collision(&q));
1595    }
1596
1597    #[test]
1598    fn test_capsule_aabb_no_overlap() {
1599        let no_overlap = capsule_aabb_overlap(
1600            [10.0, 0.0, 0.0],
1601            [11.0, 0.0, 0.0],
1602            0.1,
1603            [-1.0, -1.0, -1.0],
1604            [1.0, 1.0, 1.0],
1605        );
1606        assert!(!no_overlap);
1607    }
1608
1609    #[test]
1610    fn test_capsule_aabb_overlap() {
1611        let overlap = capsule_aabb_overlap(
1612            [-0.5, 0.0, 0.0],
1613            [0.5, 0.0, 0.0],
1614            0.1,
1615            [-1.0, -1.0, -1.0],
1616            [1.0, 1.0, 1.0],
1617        );
1618        assert!(overlap);
1619    }
1620
1621    // --- Swept volume ---
1622
1623    #[test]
1624    fn test_swept_volume_contains_endpoints() {
1625        let arm = planar_arm();
1626        let q0 = vec![0.0f64; 3];
1627        let q1 = vec![PI / 4.0, PI / 4.0, PI / 4.0];
1628        let (mn, mx) = arm.swept_volume_aabb(&q0, &q1, 20);
1629        let p0 = arm.end_effector_pos(&q0);
1630        let p1 = arm.end_effector_pos(&q1);
1631        for k in 0..3 {
1632            assert!(p0[k] >= mn[k] - 1e-9 && p0[k] <= mx[k] + 1e-9);
1633            assert!(p1[k] >= mn[k] - 1e-9 && p1[k] <= mx[k] + 1e-9);
1634        }
1635    }
1636
1637    // --- Workspace ---
1638
1639    #[test]
1640    fn test_workspace_monte_carlo_count() {
1641        let arm = planar_arm();
1642        let pts = arm.workspace_monte_carlo(100);
1643        assert_eq!(pts.len(), 100);
1644    }
1645
1646    #[test]
1647    fn test_workspace_bounding_box_some() {
1648        let arm = planar_arm();
1649        let bb = arm.workspace_bounding_box(200);
1650        assert!(bb.is_some());
1651        let (mn, mx) = bb.unwrap();
1652        for k in 0..3 {
1653            assert!(mn[k] <= mx[k]);
1654        }
1655    }
1656
1657    // --- Manipulability ---
1658
1659    #[test]
1660    fn test_manipulability_positive_planar() {
1661        let arm = planar_arm();
1662        let m = arm.manipulability(&[0.3, 0.4, 0.5]);
1663        assert!(m >= 0.0);
1664    }
1665
1666    #[test]
1667    fn test_manipulability_near_singular() {
1668        let arm = planar_arm();
1669        // Fully extended: all q = 0 → rank-deficient in 2D embedded in 3D
1670        let m = arm.manipulability(&[0.0, 0.0, 0.0]);
1671        // In 3D, planar arm has zero z-component, so det can be 0
1672        assert!(m >= 0.0);
1673    }
1674
1675    #[test]
1676    fn test_singularity_classification() {
1677        assert_eq!(
1678            classify_singularity(0.0),
1679            SingularityClass::InteriorSingular
1680        );
1681        assert_eq!(classify_singularity(0.1), SingularityClass::Regular);
1682        assert_eq!(
1683            classify_singularity(1e-4),
1684            SingularityClass::BoundarySingular
1685        );
1686        assert_eq!(classify_singularity(0.01), SingularityClass::NearSingular);
1687    }
1688
1689    // --- Reachability map ---
1690
1691    #[test]
1692    fn test_reachability_map_populate() {
1693        let arm = planar_arm();
1694        let mut rmap = ReachabilityMap::new([-2.0, -2.0, -0.1], 0.1, [40, 40, 2]);
1695        rmap.populate(&arm, 500);
1696        assert!(rmap.reachable_count() > 0);
1697    }
1698
1699    #[test]
1700    fn test_reachability_map_voxel_oob() {
1701        let rmap = ReachabilityMap::new([0.0, 0.0, 0.0], 0.1, [10, 10, 10]);
1702        assert!(rmap.world_to_voxel([1.5, 0.5, 0.5]).is_none());
1703    }
1704
1705    // --- Path planning helpers ---
1706
1707    #[test]
1708    fn test_joint_space_path_length() {
1709        let path = joint_space_path(&[0.0, 0.0], &[1.0, 1.0], 10);
1710        assert_eq!(path.len(), 11);
1711    }
1712
1713    #[test]
1714    fn test_joint_space_path_endpoints() {
1715        let q0 = vec![0.0f64, 0.5];
1716        let q1 = vec![1.0f64, -0.5];
1717        let path = joint_space_path(&q0, &q1, 5);
1718        for (a, b) in path[0].iter().zip(q0.iter()) {
1719            assert!((a - b).abs() < 1e-12);
1720        }
1721        for (a, b) in path.last().unwrap().iter().zip(q1.iter()) {
1722            assert!((a - b).abs() < 1e-12);
1723        }
1724    }
1725
1726    // --- Torque analysis ---
1727
1728    #[test]
1729    fn test_joint_torques_zero_force() {
1730        let arm = planar_arm();
1731        let q = vec![0.0f64; 3];
1732        let j = arm.jacobian_analytical(&q);
1733        let tau = joint_torques_from_force(&j, 3, [0.0, 0.0, 0.0]);
1734        for t in &tau {
1735            assert!(t.abs() < 1e-12);
1736        }
1737    }
1738
1739    // --- URDF-like struct ---
1740
1741    #[test]
1742    fn test_urdf_to_robot_arm() {
1743        let robot = UrdfRobot {
1744            name: "test_bot".into(),
1745            links: vec![
1746                UrdfLink {
1747                    name: "base".into(),
1748                    collision_radius: 0.05,
1749                    collision_half_len: 0.1,
1750                },
1751                UrdfLink {
1752                    name: "link1".into(),
1753                    collision_radius: 0.04,
1754                    collision_half_len: 0.2,
1755                },
1756            ],
1757            joints: vec![UrdfJoint {
1758                name: "joint1".into(),
1759                parent: "base".into(),
1760                child: "link1".into(),
1761                joint_type: JointType::Revolute,
1762                origin_xyz: [0.0, 0.0, 0.2],
1763                origin_rpy: [0.0, 0.0, 0.0],
1764                axis: [0.0, 0.0, 1.0],
1765                limits: Some(JointLimits::new(-PI, PI, 2.0, 50.0)),
1766            }],
1767        };
1768        let arm = robot.to_robot_arm();
1769        assert_eq!(arm.links.len(), 1);
1770        assert_eq!(arm.dof(), 1);
1771    }
1772
1773    // --- Velocity from Cartesian ---
1774
1775    #[test]
1776    fn test_end_effector_velocity_zero_dq() {
1777        let arm = planar_arm();
1778        let q = vec![0.2f64, 0.3, 0.1];
1779        let j = arm.jacobian_analytical(&q);
1780        let v = end_effector_velocity(&j, &[0.0, 0.0, 0.0]);
1781        for vi in &v {
1782            assert!(vi.abs() < 1e-12);
1783        }
1784    }
1785
1786    #[test]
1787    fn test_joint_velocity_from_cartesian_zero() {
1788        let arm = planar_arm();
1789        let q = vec![0.2f64, 0.3, 0.1];
1790        let j = arm.jacobian_analytical(&q);
1791        let dq = joint_velocity_from_cartesian(&j, 3, [0.0, 0.0, 0.0], 0.01);
1792        for d in &dq {
1793            assert!(d.abs() < 1e-10);
1794        }
1795    }
1796
1797    // --- Segment–segment distance ---
1798
1799    #[test]
1800    fn test_segment_segment_parallel() {
1801        let d = dist_segment_segment(
1802            [0.0, 0.0, 0.0],
1803            [1.0, 0.0, 0.0],
1804            [0.0, 1.0, 0.0],
1805            [1.0, 1.0, 0.0],
1806        );
1807        assert!((d - 1.0).abs() < 1e-10);
1808    }
1809
1810    #[test]
1811    fn test_segment_segment_crossing() {
1812        let d = dist_segment_segment(
1813            [-1.0, 0.0, 0.0],
1814            [1.0, 0.0, 0.0],
1815            [0.0, -1.0, 0.5],
1816            [0.0, 1.0, 0.5],
1817        );
1818        // Distance should be 0.5 (along Z)
1819        assert!((d - 0.5).abs() < 1e-10);
1820    }
1821
1822    // --- mat3 helpers ---
1823
1824    #[test]
1825    fn test_mat3_det_identity() {
1826        let ident = [1.0, 0.0, 0.0, 0.0, 1.0, 0.0, 0.0, 0.0, 1.0];
1827        assert!((mat3_det(&ident) - 1.0).abs() < 1e-12);
1828    }
1829
1830    #[test]
1831    fn test_mat3_inverse_identity() {
1832        let ident = [1.0, 0.0, 0.0, 0.0, 1.0, 0.0, 0.0, 0.0, 1.0];
1833        let inv = mat3_inverse(&ident);
1834        for i in 0..9 {
1835            assert!((inv[i] - ident[i]).abs() < 1e-12);
1836        }
1837    }
1838
1839    #[test]
1840    fn test_mat3_inverse_roundtrip() {
1841        let m = [2.0, 1.0, 0.0, 0.5, 3.0, 1.0, 0.0, 1.0, 4.0];
1842        let inv = mat3_inverse(&m);
1843        // m * inv should be identity
1844        for r in 0..3 {
1845            for c in 0..3 {
1846                let mut s = 0.0f64;
1847                for k in 0..3 {
1848                    s += m[r * 3 + k] * inv[k * 3 + c];
1849                }
1850                let expected = if r == c { 1.0 } else { 0.0 };
1851                assert!((s - expected).abs() < 1e-10, "m*inv[{r},{c}]={s}");
1852            }
1853        }
1854    }
1855}