1use glam::{Affine3A, Mat3A, Vec3A};
2
3use crate::{DekeError, SRobotQ};
4
5#[inline(always)]
6const fn fast_sin_cos(x: f32) -> (f32, f32) {
7 const FRAC_2_PI: f32 = std::f32::consts::FRAC_2_PI;
8 const PI_2_HI: f32 = 1.570_796_4_f32;
9 const PI_2_LO: f32 = -4.371_139e-8_f32;
10
11 const S1: f32 = -0.166_666_67;
12 const S2: f32 = 0.008_333_294;
13 const S3: f32 = -0.000_198_074_14;
14
15 const C1: f32 = -0.5;
16 const C2: f32 = 0.041_666_52;
17 const C3: f32 = -0.001_388_523_4;
18
19 let q = (x * FRAC_2_PI).round();
20 let qi = q as i32;
21 let r = x - q * PI_2_HI - q * PI_2_LO;
22 let r2 = r * r;
23
24 let sin_r = r * (1.0 + r2 * (S1 + r2 * (S2 + r2 * S3)));
25 let cos_r = 1.0 + r2 * (C1 + r2 * (C2 + r2 * C3));
26
27 let (s, c) = match qi & 3 {
28 0 => (sin_r, cos_r),
29 1 => (cos_r, -sin_r),
30 2 => (-sin_r, -cos_r),
31 3 => (-cos_r, sin_r),
32 _ => unsafe { std::hint::unreachable_unchecked() },
33 };
34
35 (s, c)
36}
37
38#[inline]
39const fn const_sqrt(x: f64) -> f64 {
40 if x < 0.0 || x.is_nan() { return f64::NAN; }
41 if x == 0.0 || x == f64::INFINITY { return x; }
42
43 let bits = x.to_bits();
46 let exp = ((bits >> 52) & 0x7ff) as i64;
47 let new_exp = ((exp - 1023) / 2 + 1023) as u64;
48 let mut guess = f64::from_bits((new_exp << 52) | (bits & 0x000f_ffff_ffff_ffff));
49
50 let mut prev = 0.0;
51 while guess != prev {
52 prev = guess;
53 guess = (guess + x / guess) * 0.5;
54 }
55 guess
56}
57
58pub trait FKChain<const N: usize>: Clone + Send + Sync {
59 type Error: Into<DekeError>;
60 fn dof(&self) -> usize {
61 N
62 }
63 fn max_reach(&self) -> Result<f32, Self::Error> {
65 let (_, p, p_ee) = self.joint_axes_positions(&SRobotQ::zeros())?;
66 let mut total = 0.0f32;
67 let mut prev = p[0];
68 for i in 1..N {
69 total += (p[i] - prev).length();
70 prev = p[i];
71 }
72 total += (p_ee - prev).length();
73 Ok(total)
74 }
75
76 fn fk(&self, q: &SRobotQ<N>) -> Result<[Affine3A; N], Self::Error>;
77 fn fk_end(&self, q: &SRobotQ<N>) -> Result<Affine3A, Self::Error>;
78 fn joint_axes_positions(
81 &self,
82 q: &SRobotQ<N>,
83 ) -> Result<([Vec3A; N], [Vec3A; N], Vec3A), Self::Error>;
84
85 fn jacobian(&self, q: &SRobotQ<N>) -> Result<[[f32; N]; 6], Self::Error> {
88 let (z, p, p_ee) = self.joint_axes_positions(q)?;
89 let mut j = [[0.0f32; N]; 6];
90 for i in 0..N {
91 let dp = p_ee - p[i];
92 let c = z[i].cross(dp);
93 j[0][i] = c.x;
94 j[1][i] = c.y;
95 j[2][i] = c.z;
96 j[3][i] = z[i].x;
97 j[4][i] = z[i].y;
98 j[5][i] = z[i].z;
99 }
100 Ok(j)
101 }
102
103 fn jacobian_dot(
105 &self,
106 q: &SRobotQ<N>,
107 qdot: &SRobotQ<N>,
108 ) -> Result<[[f32; N]; 6], Self::Error> {
109 let (z, p, p_ee) = self.joint_axes_positions(q)?;
110
111 let mut omega = Vec3A::ZERO;
112 let mut z_dot = [Vec3A::ZERO; N];
113 let mut p_dot = [Vec3A::ZERO; N];
114 let mut pdot_acc = Vec3A::ZERO;
115
116 for i in 0..N {
117 p_dot[i] = pdot_acc;
118 z_dot[i] = omega.cross(z[i]);
119 omega += qdot.0[i] * z[i];
120 let next_p = if i + 1 < N { p[i + 1] } else { p_ee };
121 pdot_acc += omega.cross(next_p - p[i]);
122 }
123 let p_ee_dot = pdot_acc;
124
125 let mut jd = [[0.0f32; N]; 6];
126 for i in 0..N {
127 let dp = p_ee - p[i];
128 let dp_dot = p_ee_dot - p_dot[i];
129 let c1 = z_dot[i].cross(dp);
130 let c2 = z[i].cross(dp_dot);
131 jd[0][i] = c1.x + c2.x;
132 jd[1][i] = c1.y + c2.y;
133 jd[2][i] = c1.z + c2.z;
134 jd[3][i] = z_dot[i].x;
135 jd[4][i] = z_dot[i].y;
136 jd[5][i] = z_dot[i].z;
137 }
138 Ok(jd)
139 }
140
141 fn jacobian_ddot(
143 &self,
144 q: &SRobotQ<N>,
145 qdot: &SRobotQ<N>,
146 qddot: &SRobotQ<N>,
147 ) -> Result<[[f32; N]; 6], Self::Error> {
148 let (z, p, p_ee) = self.joint_axes_positions(q)?;
149
150 let mut omega = Vec3A::ZERO;
151 let mut omega_dot = Vec3A::ZERO;
152 let mut z_dot = [Vec3A::ZERO; N];
153 let mut z_ddot = [Vec3A::ZERO; N];
154 let mut p_dot = [Vec3A::ZERO; N];
155 let mut p_ddot = [Vec3A::ZERO; N];
156 let mut pdot_acc = Vec3A::ZERO;
157 let mut pddot_acc = Vec3A::ZERO;
158
159 for i in 0..N {
160 p_dot[i] = pdot_acc;
161 p_ddot[i] = pddot_acc;
162 let zd = omega.cross(z[i]);
163 z_dot[i] = zd;
164 z_ddot[i] = omega_dot.cross(z[i]) + omega.cross(zd);
165 omega_dot += qddot.0[i] * z[i] + qdot.0[i] * zd;
166 omega += qdot.0[i] * z[i];
167 let next_p = if i + 1 < N { p[i + 1] } else { p_ee };
168 let delta = next_p - p[i];
169 let delta_dot = omega.cross(delta);
170 pdot_acc += delta_dot;
171 pddot_acc += omega_dot.cross(delta) + omega.cross(delta_dot);
172 }
173 let p_ee_dot = pdot_acc;
174 let p_ee_ddot = pddot_acc;
175
176 let mut jdd = [[0.0f32; N]; 6];
177 for i in 0..N {
178 let dp = p_ee - p[i];
179 let dp_dot = p_ee_dot - p_dot[i];
180 let dp_ddot = p_ee_ddot - p_ddot[i];
181 let c1 = z_ddot[i].cross(dp);
182 let c2 = z_dot[i].cross(dp_dot);
183 let c3 = z[i].cross(dp_ddot);
184 jdd[0][i] = c1.x + 2.0 * c2.x + c3.x;
185 jdd[1][i] = c1.y + 2.0 * c2.y + c3.y;
186 jdd[2][i] = c1.z + 2.0 * c2.z + c3.z;
187 jdd[3][i] = z_ddot[i].x;
188 jdd[4][i] = z_ddot[i].y;
189 jdd[5][i] = z_ddot[i].z;
190 }
191 Ok(jdd)
192 }
193}
194
195#[inline(always)]
196#[cfg(debug_assertions)]
197fn check_finite<const N: usize>(q: &SRobotQ<N>) -> Result<(), DekeError> {
198 if q.any_non_finite() {
199 return Err(DekeError::JointsNonFinite);
200 }
201 Ok(())
202}
203
204#[inline(always)]
205#[cfg(not(debug_assertions))]
206fn check_finite<const N: usize>(_: &SRobotQ<N>) -> Result<(), std::convert::Infallible> {
207 Ok(())
208}
209
210#[inline(always)]
211const fn abs_f32(x: f32) -> f32 {
212 if x < 0.0 { -x } else { x }
213}
214
215#[derive(Debug, Clone, Copy)]
221struct AffineRaw {
222 c0: [f32; 3],
223 c1: [f32; 3],
224 c2: [f32; 3],
225 t: [f32; 3],
226}
227
228impl AffineRaw {
229 const IDENTITY: Self = Self {
230 c0: [1.0, 0.0, 0.0],
231 c1: [0.0, 1.0, 0.0],
232 c2: [0.0, 0.0, 1.0],
233 t: [0.0, 0.0, 0.0],
234 };
235
236 #[inline(always)]
238 const fn mul(self, other: Self) -> Self {
239 let nc0 = [
240 self.c0[0] * other.c0[0] + self.c1[0] * other.c0[1] + self.c2[0] * other.c0[2],
241 self.c0[1] * other.c0[0] + self.c1[1] * other.c0[1] + self.c2[1] * other.c0[2],
242 self.c0[2] * other.c0[0] + self.c1[2] * other.c0[1] + self.c2[2] * other.c0[2],
243 ];
244 let nc1 = [
245 self.c0[0] * other.c1[0] + self.c1[0] * other.c1[1] + self.c2[0] * other.c1[2],
246 self.c0[1] * other.c1[0] + self.c1[1] * other.c1[1] + self.c2[1] * other.c1[2],
247 self.c0[2] * other.c1[0] + self.c1[2] * other.c1[1] + self.c2[2] * other.c1[2],
248 ];
249 let nc2 = [
250 self.c0[0] * other.c2[0] + self.c1[0] * other.c2[1] + self.c2[0] * other.c2[2],
251 self.c0[1] * other.c2[0] + self.c1[1] * other.c2[1] + self.c2[1] * other.c2[2],
252 self.c0[2] * other.c2[0] + self.c1[2] * other.c2[1] + self.c2[2] * other.c2[2],
253 ];
254 let nt = [
255 self.c0[0] * other.t[0]
256 + self.c1[0] * other.t[1]
257 + self.c2[0] * other.t[2]
258 + self.t[0],
259 self.c0[1] * other.t[0]
260 + self.c1[1] * other.t[1]
261 + self.c2[1] * other.t[2]
262 + self.t[1],
263 self.c0[2] * other.t[0]
264 + self.c1[2] * other.t[1]
265 + self.c2[2] * other.t[2]
266 + self.t[2],
267 ];
268 Self {
269 c0: nc0,
270 c1: nc1,
271 c2: nc2,
272 t: nt,
273 }
274 }
275
276 #[inline(always)]
277 const fn is_identity(&self) -> bool {
278 const EPS: f32 = 1e-6;
279 abs_f32(self.c0[0] - 1.0) <= EPS
280 && abs_f32(self.c0[1]) <= EPS
281 && abs_f32(self.c0[2]) <= EPS
282 && abs_f32(self.c1[0]) <= EPS
283 && abs_f32(self.c1[1] - 1.0) <= EPS
284 && abs_f32(self.c1[2]) <= EPS
285 && abs_f32(self.c2[0]) <= EPS
286 && abs_f32(self.c2[1]) <= EPS
287 && abs_f32(self.c2[2] - 1.0) <= EPS
288 && abs_f32(self.t[0]) <= EPS
289 && abs_f32(self.t[1]) <= EPS
290 && abs_f32(self.t[2]) <= EPS
291 }
292
293 #[inline(always)]
296 const fn from_xyz_rpy(xyz: (f64, f64, f64), rpy: (f64, f64, f64)) -> Self {
297 let (ox, oy, oz) = xyz;
298 let (roll, pitch, yaw) = rpy;
299 let (sr, cr) = fast_sin_cos(roll as f32);
300 let (sp, cp) = fast_sin_cos(pitch as f32);
301 let (sy, cy) = fast_sin_cos(yaw as f32);
302 Self {
303 c0: [cy * cp, sy * cp, -sp],
304 c1: [cy * sp * sr - sy * cr, sy * sp * sr + cy * cr, cp * sr],
305 c2: [cy * sp * cr + sy * sr, sy * sp * cr - cy * sr, cp * cr],
306 t: [ox as f32, oy as f32, oz as f32],
307 }
308 }
309
310 #[inline(always)]
311 const fn to_affine3a(self) -> Affine3A {
312 Affine3A {
313 matrix3: Mat3A::from_cols(
314 Vec3A::new(self.c0[0], self.c0[1], self.c0[2]),
315 Vec3A::new(self.c1[0], self.c1[1], self.c1[2]),
316 Vec3A::new(self.c2[0], self.c2[1], self.c2[2]),
317 ),
318 translation: Vec3A::new(self.t[0], self.t[1], self.t[2]),
319 }
320 }
321
322 #[inline(always)]
323 const fn c0_vec3a(&self) -> Vec3A {
324 Vec3A::new(self.c0[0], self.c0[1], self.c0[2])
325 }
326
327 #[inline(always)]
328 const fn c1_vec3a(&self) -> Vec3A {
329 Vec3A::new(self.c1[0], self.c1[1], self.c1[2])
330 }
331
332 #[inline(always)]
333 const fn c2_vec3a(&self) -> Vec3A {
334 Vec3A::new(self.c2[0], self.c2[1], self.c2[2])
335 }
336
337 #[inline(always)]
338 const fn t_vec3a(&self) -> Vec3A {
339 Vec3A::new(self.t[0], self.t[1], self.t[2])
340 }
341}
342
343#[inline(always)]
347fn accumulate(
348 acc_m: &mut Mat3A,
349 acc_t: &mut Vec3A,
350 local_c0: Vec3A,
351 local_c1: Vec3A,
352 local_c2: Vec3A,
353 local_t: Vec3A,
354) {
355 let new_c0 = *acc_m * local_c0;
356 let new_c1 = *acc_m * local_c1;
357 let new_c2 = *acc_m * local_c2;
358 *acc_t = *acc_m * local_t + *acc_t;
359 *acc_m = Mat3A::from_cols(new_c0, new_c1, new_c2);
360}
361
362#[derive(Debug, Clone, Copy)]
363pub struct DHJoint {
364 pub a: f32,
365 pub alpha: f32,
366 pub d: f32,
367 pub theta_offset: f32,
368}
369
370#[derive(Debug, Clone)]
374pub struct DHChain<const N: usize> {
375 a: [f32; N],
376 d: [f32; N],
377 sin_alpha: [f32; N],
378 cos_alpha: [f32; N],
379 theta_offset: [f32; N],
380}
381
382impl<const N: usize> DHChain<N> {
383 pub const fn new(joints: [DHJoint; N]) -> Self {
384 let mut a = [0.0; N];
385 let mut d = [0.0; N];
386 let mut sin_alpha = [0.0; N];
387 let mut cos_alpha = [0.0; N];
388 let mut theta_offset = [0.0; N];
389
390 let mut i = 0;
391 while i < N {
392 a[i] = joints[i].a;
393 d[i] = joints[i].d;
394 let (sa, ca) = fast_sin_cos(joints[i].alpha);
395 sin_alpha[i] = sa;
396 cos_alpha[i] = ca;
397 theta_offset[i] = joints[i].theta_offset;
398 i += 1;
399 }
400
401 Self {
402 a,
403 d,
404 sin_alpha,
405 cos_alpha,
406 theta_offset,
407 }
408 }
409
410 pub const fn from_dh(params: &[[f64; N]; 4]) -> Self {
416 let mut a = [0.0f32; N];
417 let mut d = [0.0f32; N];
418 let mut sin_alpha = [0.0f32; N];
419 let mut cos_alpha = [0.0f32; N];
420 let mut theta_offset = [0.0f32; N];
421
422 let mut i = 0;
423 while i < N {
424 a[i] = params[0][i] as f32;
425 let (sa, ca) = fast_sin_cos(params[1][i] as f32);
426 sin_alpha[i] = sa;
427 cos_alpha[i] = ca;
428 d[i] = params[2][i] as f32;
429 theta_offset[i] = params[3][i] as f32;
430 i += 1;
431 }
432
433 Self {
434 a,
435 d,
436 sin_alpha,
437 cos_alpha,
438 theta_offset,
439 }
440 }
441}
442
443impl<const N: usize> FKChain<N> for DHChain<N> {
444 #[cfg(debug_assertions)]
445 type Error = DekeError;
446 #[cfg(not(debug_assertions))]
447 type Error = std::convert::Infallible;
448
449 fn fk(&self, q: &SRobotQ<N>) -> Result<[Affine3A; N], Self::Error> {
456 check_finite::<N>(q)?;
457 let mut out = [Affine3A::IDENTITY; N];
458 let mut c0 = Vec3A::X;
459 let mut c1 = Vec3A::Y;
460 let mut c2 = Vec3A::Z;
461 let mut t = Vec3A::ZERO;
462
463 let mut i = 0;
464 while i < N {
465 let (st, ct) = fast_sin_cos(q.0[i] + self.theta_offset[i]);
466 let sa = self.sin_alpha[i];
467 let ca = self.cos_alpha[i];
468
469 let new_c0 = ct * c0 + st * c1;
470 let perp = ct * c1 - st * c0;
471
472 let new_c1 = ca * perp + sa * c2;
473 let new_c2 = ca * c2 - sa * perp;
474
475 t = self.a[i] * new_c0 + self.d[i] * c2 + t;
476
477 c0 = new_c0;
478 c1 = new_c1;
479 c2 = new_c2;
480
481 out[i] = Affine3A {
482 matrix3: Mat3A::from_cols(c0, c1, c2),
483 translation: t,
484 };
485 i += 1;
486 }
487 Ok(out)
488 }
489
490 fn fk_end(&self, q: &SRobotQ<N>) -> Result<Affine3A, Self::Error> {
491 check_finite::<N>(q)?;
492 let mut c0 = Vec3A::X;
493 let mut c1 = Vec3A::Y;
494 let mut c2 = Vec3A::Z;
495 let mut t = Vec3A::ZERO;
496
497 let mut i = 0;
498 while i < N {
499 let (st, ct) = fast_sin_cos(q.0[i] + self.theta_offset[i]);
500 let sa = self.sin_alpha[i];
501 let ca = self.cos_alpha[i];
502
503 let new_c0 = ct * c0 + st * c1;
504 let perp = ct * c1 - st * c0;
505
506 let new_c1 = ca * perp + sa * c2;
507 let new_c2 = ca * c2 - sa * perp;
508
509 t = self.a[i] * new_c0 + self.d[i] * c2 + t;
510
511 c0 = new_c0;
512 c1 = new_c1;
513 c2 = new_c2;
514 i += 1;
515 }
516
517 Ok(Affine3A {
518 matrix3: Mat3A::from_cols(c0, c1, c2),
519 translation: t,
520 })
521 }
522
523 fn joint_axes_positions(
524 &self,
525 q: &SRobotQ<N>,
526 ) -> Result<([Vec3A; N], [Vec3A; N], Vec3A), Self::Error> {
527 let frames = self.fk(q)?;
528 let mut axes = [Vec3A::Z; N];
529 let mut positions = [Vec3A::ZERO; N];
530
531 for i in 1..N {
532 axes[i] = frames[i - 1].matrix3.z_axis;
533 positions[i] = frames[i - 1].translation;
534 }
535
536 Ok((axes, positions, frames[N - 1].translation))
537 }
538}
539
540#[derive(Debug, Clone, Copy)]
541pub struct HPJoint {
542 pub a: f32,
543 pub alpha: f32,
544 pub beta: f32,
545 pub d: f32,
546 pub theta_offset: f32,
547}
548
549#[derive(Debug, Clone)]
556pub struct HPChain<const N: usize> {
557 a: [f32; N],
558 d: [f32; N],
559 sin_alpha: [f32; N],
560 cos_alpha: [f32; N],
561 sin_beta: [f32; N],
562 cos_beta: [f32; N],
563 theta_offset: [f32; N],
564}
565
566impl<const N: usize> HPChain<N> {
567 pub const fn new(joints: [HPJoint; N]) -> Self {
568 let mut a = [0.0; N];
569 let mut d = [0.0; N];
570 let mut sin_alpha = [0.0; N];
571 let mut cos_alpha = [0.0; N];
572 let mut sin_beta = [0.0; N];
573 let mut cos_beta = [0.0; N];
574 let mut theta_offset = [0.0; N];
575
576 let mut i = 0;
577 while i < N {
578 a[i] = joints[i].a;
579 d[i] = joints[i].d;
580 let (sa, ca) = fast_sin_cos(joints[i].alpha);
581 sin_alpha[i] = sa;
582 cos_alpha[i] = ca;
583 let (sb, cb) = fast_sin_cos(joints[i].beta);
584 sin_beta[i] = sb;
585 cos_beta[i] = cb;
586 theta_offset[i] = joints[i].theta_offset;
587 i += 1;
588 }
589
590 Self {
591 a,
592 d,
593 sin_alpha,
594 cos_alpha,
595 sin_beta,
596 cos_beta,
597 theta_offset,
598 }
599 }
600
601 pub const fn from_hp(h: &[[f32; N]; 3], p: &[[f32; N]; 3]) -> Self {
618
619 let mut a = [0.0f32; N];
620 let mut d = [0.0f32; N];
621 let mut sin_alpha = [0.0f32; N];
622 let mut cos_alpha = [0.0f32; N];
623 let mut sin_beta = [0.0f32; N];
624 let mut cos_beta = [0.0f32; N];
625
626 let mut c0 = [1.0f32, 0.0, 0.0];
627 let mut c1 = [0.0f32, 1.0, 0.0];
628 let mut c2 = [0.0f32, 0.0, 1.0];
629
630 const EPS: f32 = 1e-12;
631
632 let mut i = 0;
633 while i < N {
634 let hx = h[0][i];
635 let hy = h[1][i];
636 let hz = h[2][i];
637 let px = p[0][i];
638 let py = p[1][i];
639 let pz = p[2][i];
640
641 let vx = c0[0] * hx + c0[1] * hy + c0[2] * hz;
642 let vy = c1[0] * hx + c1[1] * hy + c1[2] * hz;
643 let vz = c2[0] * hx + c2[1] * hy + c2[2] * hz;
644 let ux = c0[0] * px + c0[1] * py + c0[2] * pz;
645 let uy = c1[0] * px + c1[1] * py + c1[2] * pz;
646 let uz = c2[0] * px + c2[1] * py + c2[2] * pz;
647
648 let sb = vx;
649 let cb = const_sqrt((vy * vy + vz * vz) as f64) as f32;
650
651 let (sa, ca) = if cb > EPS {
652 (-vy / cb, vz / cb)
653 } else {
654 (0.0, 1.0)
655 };
656
657 let big_a = ux;
658 let big_b = sa * uy - ca * uz;
659 let ai = cb * big_a + sb * big_b;
660 let di = sb * big_a - cb * big_b;
661
662 a[i] = ai;
663 d[i] = di;
664 sin_alpha[i] = sa;
665 cos_alpha[i] = ca;
666 sin_beta[i] = sb;
667 cos_beta[i] = cb;
668
669 let sasb = sa * sb;
670 let casb = ca * sb;
671 let sacb = sa * cb;
672 let cacb = ca * cb;
673 let new_c0 = [
674 cb * c0[0] + sasb * c1[0] - casb * c2[0],
675 cb * c0[1] + sasb * c1[1] - casb * c2[1],
676 cb * c0[2] + sasb * c1[2] - casb * c2[2],
677 ];
678 let new_c1 = [
679 ca * c1[0] + sa * c2[0],
680 ca * c1[1] + sa * c2[1],
681 ca * c1[2] + sa * c2[2],
682 ];
683 let new_c2 = [
684 sb * c0[0] - sacb * c1[0] + cacb * c2[0],
685 sb * c0[1] - sacb * c1[1] + cacb * c2[1],
686 sb * c0[2] - sacb * c1[2] + cacb * c2[2],
687 ];
688 c0 = new_c0;
689 c1 = new_c1;
690 c2 = new_c2;
691
692 i += 1;
693 }
694
695 Self {
696 a,
697 d,
698 sin_alpha,
699 cos_alpha,
700 sin_beta,
701 cos_beta,
702 theta_offset: [0.0f32; N],
703 }
704 }
705
706 #[inline(always)]
719 fn local_frame(&self, i: usize, st: f32, ct: f32) -> (Vec3A, Vec3A, Vec3A, Vec3A) {
720 let sa = self.sin_alpha[i];
721 let ca = self.cos_alpha[i];
722 let sb = self.sin_beta[i];
723 let cb = self.cos_beta[i];
724 let ai = self.a[i];
725 let di = self.d[i];
726
727 let sa_sb = sa * sb;
728 let sa_cb = sa * cb;
729 let ca_sb = ca * sb;
730 let ca_cb = ca * cb;
731
732 let c0 = Vec3A::new(ct * cb - st * sa_sb, st * cb + ct * sa_sb, -ca_sb);
733 let c1 = Vec3A::new(-st * ca, ct * ca, sa);
734 let c2 = Vec3A::new(ct * sb + st * sa_cb, st * sb - ct * sa_cb, ca_cb);
735 let t = Vec3A::new(
736 ai * c0.x + di * c2.x,
737 ai * c0.y + di * c2.y,
738 ai * c0.z + di * c2.z,
739 );
740
741 (c0, c1, c2, t)
742 }
743}
744
745impl<const N: usize> FKChain<N> for HPChain<N> {
746 #[cfg(debug_assertions)]
747 type Error = DekeError;
748 #[cfg(not(debug_assertions))]
749 type Error = std::convert::Infallible;
750
751 fn fk(&self, q: &SRobotQ<N>) -> Result<[Affine3A; N], Self::Error> {
752 check_finite::<N>(q)?;
753 let mut out = [Affine3A::IDENTITY; N];
754 let mut acc_m = Mat3A::IDENTITY;
755 let mut acc_t = Vec3A::ZERO;
756
757 let mut i = 0;
758 while i < N {
759 let (st, ct) = fast_sin_cos(q.0[i] + self.theta_offset[i]);
760 let (c0, c1, c2, t) = self.local_frame(i, st, ct);
761 accumulate(&mut acc_m, &mut acc_t, c0, c1, c2, t);
762
763 out[i] = Affine3A {
764 matrix3: acc_m,
765 translation: acc_t,
766 };
767 i += 1;
768 }
769 Ok(out)
770 }
771
772 fn fk_end(&self, q: &SRobotQ<N>) -> Result<Affine3A, Self::Error> {
773 check_finite(q)?;
774 let mut acc_m = Mat3A::IDENTITY;
775 let mut acc_t = Vec3A::ZERO;
776
777 let mut i = 0;
778 while i < N {
779 let (st, ct) = fast_sin_cos(q.0[i] + self.theta_offset[i]);
780 let (c0, c1, c2, t) = self.local_frame(i, st, ct);
781 accumulate(&mut acc_m, &mut acc_t, c0, c1, c2, t);
782 i += 1;
783 }
784
785 Ok(Affine3A {
786 matrix3: acc_m,
787 translation: acc_t,
788 })
789 }
790
791 fn joint_axes_positions(
792 &self,
793 q: &SRobotQ<N>,
794 ) -> Result<([Vec3A; N], [Vec3A; N], Vec3A), Self::Error> {
795 let frames = self.fk(q)?;
796 let mut axes = [Vec3A::Z; N];
797 let mut positions = [Vec3A::ZERO; N];
798
799 for i in 1..N {
800 axes[i] = frames[i - 1].matrix3.z_axis;
801 positions[i] = frames[i - 1].translation;
802 }
803
804 Ok((axes, positions, frames[N - 1].translation))
805 }
806}
807
808#[derive(Debug, Clone, Copy, PartialEq)]
812pub enum URDFJointType {
813 Fixed,
814 Revolute { axis: (f64, f64, f64) },
815 Prismatic { axis: (f64, f64, f64) },
816}
817
818#[derive(Debug, Clone, Copy)]
821pub struct URDFJoint {
822 pub r#type: URDFJointType,
823 pub xyz: (f64, f64, f64),
824 pub rpy: (f64, f64, f64),
825}
826
827impl URDFJoint {
828 pub const fn fixed(xyz: (f64, f64, f64), rpy: (f64, f64, f64)) -> Self {
829 Self {
830 r#type: URDFJointType::Fixed,
831 xyz,
832 rpy,
833 }
834 }
835
836 pub const fn revolute(
837 xyz: (f64, f64, f64),
838 rpy: (f64, f64, f64),
839 axis: (f64, f64, f64),
840 ) -> Self {
841 Self {
842 r#type: URDFJointType::Revolute { axis },
843 xyz,
844 rpy,
845 }
846 }
847
848 pub const fn prismatic(
849 xyz: (f64, f64, f64),
850 rpy: (f64, f64, f64),
851 axis: (f64, f64, f64),
852 ) -> Self {
853 Self {
854 r#type: URDFJointType::Prismatic { axis },
855 xyz,
856 rpy,
857 }
858 }
859
860 pub const fn origin_affine(&self) -> Affine3A {
863 AffineRaw::from_xyz_rpy(self.xyz, self.rpy).to_affine3a()
864 }
865}
866
867#[derive(Debug, Clone, Copy, PartialEq, thiserror::Error)]
872pub enum URDFBuildError {
873 #[error(
874 "URDF joint at index {index} has an unexpected type: expected {expected}, found {found}"
875 )]
876 JointTypeMismatch {
877 index: usize,
878 expected: &'static str,
879 found: &'static str,
880 },
881 #[error("URDFChain<{expected}> requires {expected} revolute joints, found {found}")]
882 RevoluteCountMismatch { expected: usize, found: usize },
883}
884
885impl From<URDFBuildError> for DekeError {
886 fn from(e: URDFBuildError) -> Self {
887 match e {
888 URDFBuildError::JointTypeMismatch {
889 index,
890 expected,
891 found,
892 } => DekeError::URDFJointTypeMismatch {
893 index,
894 expected,
895 found,
896 },
897 URDFBuildError::RevoluteCountMismatch { expected, found } => {
898 DekeError::URDFRevoluteCountMismatch { expected, found }
899 }
900 }
901 }
902}
903
904const fn joint_kind_name(k: URDFJointType) -> &'static str {
905 match k {
906 URDFJointType::Fixed => "Fixed",
907 URDFJointType::Revolute { .. } => "Revolute",
908 URDFJointType::Prismatic { .. } => "Prismatic",
909 }
910}
911
912const fn compose_fixed_joints_raw(joints: &[URDFJoint]) -> Result<AffineRaw, URDFBuildError> {
913 let mut acc = AffineRaw::IDENTITY;
914 let n = joints.len();
915 let mut i = 0;
916 while i < n {
917 let j = &joints[i];
918 if !matches!(j.r#type, URDFJointType::Fixed) {
919 return Err(URDFBuildError::JointTypeMismatch {
920 index: i,
921 expected: "Fixed",
922 found: joint_kind_name(j.r#type),
923 });
924 }
925 acc = acc.mul(AffineRaw::from_xyz_rpy(j.xyz, j.rpy));
926 i += 1;
927 }
928 Ok(acc)
929}
930
931pub const fn compose_fixed_joints(joints: &[URDFJoint]) -> Result<Affine3A, URDFBuildError> {
935 match compose_fixed_joints_raw(joints) {
936 Ok(a) => Ok(a.to_affine3a()),
937 Err(e) => Err(e),
938 }
939}
940
941#[derive(Debug, Clone, Copy)]
943enum JointAxis {
944 Z,
945 Y(f32),
946 X(f32),
947}
948
949#[derive(Debug, Clone)]
960pub struct URDFChain<const N: usize> {
961 fr_c0: [Vec3A; N],
962 fr_c1: [Vec3A; N],
963 fr_c2: [Vec3A; N],
964 fr_identity: [bool; N],
965 fixed_trans: [Vec3A; N],
966 axis: [JointAxis; N],
967 prefix_c0: Vec3A,
968 prefix_c1: Vec3A,
969 prefix_c2: Vec3A,
970 prefix_t: Vec3A,
971 prefix_identity: bool,
972 suffix_c0: Vec3A,
973 suffix_c1: Vec3A,
974 suffix_c2: Vec3A,
975 suffix_t: Vec3A,
976 suffix_identity: bool,
977}
978
979impl<const N: usize> URDFChain<N> {
980 pub const fn new(joints: [URDFJoint; N]) -> Result<Self, URDFBuildError> {
985 let mut fr_c0 = [Vec3A::X; N];
986 let mut fr_c1 = [Vec3A::Y; N];
987 let mut fr_c2 = [Vec3A::Z; N];
988 let mut fr_identity = [true; N];
989 let mut fixed_trans = [Vec3A::ZERO; N];
990 let mut axis = [JointAxis::Z; N];
991
992 let mut i = 0;
993 while i < N {
994 let (ox, oy, oz) = joints[i].xyz;
995 let (roll, pitch, yaw) = joints[i].rpy;
996
997 let is_identity = roll.abs() < 1e-10 && pitch.abs() < 1e-10 && yaw.abs() < 1e-10;
998 fr_identity[i] = is_identity;
999
1000 if !is_identity {
1001 let (sr, cr) = fast_sin_cos(roll as f32);
1002 let (sp, cp) = fast_sin_cos(pitch as f32);
1003 let (sy, cy) = fast_sin_cos(yaw as f32);
1004 fr_c0[i] = Vec3A::new(cy * cp, sy * cp, -sp);
1005 fr_c1[i] = Vec3A::new(cy * sp * sr - sy * cr, sy * sp * sr + cy * cr, cp * sr);
1006 fr_c2[i] = Vec3A::new(cy * sp * cr + sy * sr, sy * sp * cr - cy * sr, cp * cr);
1007 }
1008
1009 fixed_trans[i] = Vec3A::new(ox as f32, oy as f32, oz as f32);
1010
1011 let (ax, ay, az) = match joints[i].r#type {
1012 URDFJointType::Revolute { axis } => axis,
1013 _ => {
1014 return Err(URDFBuildError::JointTypeMismatch {
1015 index: i,
1016 expected: "Revolute",
1017 found: joint_kind_name(joints[i].r#type),
1018 });
1019 }
1020 };
1021 if az.abs() > 0.5 {
1022 axis[i] = JointAxis::Z;
1023 } else if ay.abs() > 0.5 {
1024 axis[i] = JointAxis::Y(ay.signum() as f32);
1025 } else {
1026 axis[i] = JointAxis::X(ax.signum() as f32);
1027 }
1028 i += 1;
1029 }
1030
1031 Ok(Self {
1032 fr_c0,
1033 fr_c1,
1034 fr_c2,
1035 fr_identity,
1036 fixed_trans,
1037 axis,
1038 prefix_c0: Vec3A::X,
1039 prefix_c1: Vec3A::Y,
1040 prefix_c2: Vec3A::Z,
1041 prefix_t: Vec3A::ZERO,
1042 prefix_identity: true,
1043 suffix_c0: Vec3A::X,
1044 suffix_c1: Vec3A::Y,
1045 suffix_c2: Vec3A::Z,
1046 suffix_t: Vec3A::ZERO,
1047 suffix_identity: true,
1048 })
1049 }
1050
1051 pub const fn from_urdf(joints: &[URDFJoint]) -> Result<Self, URDFBuildError> {
1069 let mut fr_c0 = [Vec3A::X; N];
1070 let mut fr_c1 = [Vec3A::Y; N];
1071 let mut fr_c2 = [Vec3A::Z; N];
1072 let mut fr_identity = [true; N];
1073 let mut fixed_trans = [Vec3A::ZERO; N];
1074 let mut axis_out = [JointAxis::Z; N];
1075
1076 let mut pending = AffineRaw::IDENTITY;
1077 let mut prefix = AffineRaw::IDENTITY;
1078 let mut prefix_set = false;
1079 let mut r_count = 0usize;
1080
1081 let n = joints.len();
1082 let mut i = 0;
1083 while i < n {
1084 let joint = &joints[i];
1085 match joint.r#type {
1086 URDFJointType::Fixed => {
1087 pending = pending.mul(AffineRaw::from_xyz_rpy(joint.xyz, joint.rpy));
1088 }
1089 URDFJointType::Revolute { axis } => {
1090 if r_count >= N {
1091 return Err(URDFBuildError::RevoluteCountMismatch {
1092 expected: N,
1093 found: r_count + 1,
1094 });
1095 }
1096 let local = AffineRaw::from_xyz_rpy(joint.xyz, joint.rpy);
1097 let effective = if !prefix_set {
1098 prefix = pending;
1099 prefix_set = true;
1100 local
1101 } else {
1102 pending.mul(local)
1103 };
1104
1105 fr_identity[r_count] = effective.is_identity();
1106 fr_c0[r_count] = effective.c0_vec3a();
1107 fr_c1[r_count] = effective.c1_vec3a();
1108 fr_c2[r_count] = effective.c2_vec3a();
1109 fixed_trans[r_count] = effective.t_vec3a();
1110
1111 let (ax, ay, az) = axis;
1112 axis_out[r_count] = if az.abs() > 0.5 {
1113 JointAxis::Z
1114 } else if ay.abs() > 0.5 {
1115 JointAxis::Y(ay.signum() as f32)
1116 } else {
1117 JointAxis::X(ax.signum() as f32)
1118 };
1119
1120 pending = AffineRaw::IDENTITY;
1121 r_count += 1;
1122 }
1123 URDFJointType::Prismatic { .. } => {
1124 return Err(URDFBuildError::JointTypeMismatch {
1125 index: i,
1126 expected: "Fixed or Revolute",
1127 found: "Prismatic",
1128 });
1129 }
1130 }
1131 i += 1;
1132 }
1133 if r_count != N {
1134 return Err(URDFBuildError::RevoluteCountMismatch {
1135 expected: N,
1136 found: r_count,
1137 });
1138 }
1139
1140 let prefix_identity = !prefix_set || prefix.is_identity();
1141 let suffix_identity = pending.is_identity();
1142
1143 Ok(Self {
1144 fr_c0,
1145 fr_c1,
1146 fr_c2,
1147 fr_identity,
1148 fixed_trans,
1149 axis: axis_out,
1150 prefix_c0: prefix.c0_vec3a(),
1151 prefix_c1: prefix.c1_vec3a(),
1152 prefix_c2: prefix.c2_vec3a(),
1153 prefix_t: prefix.t_vec3a(),
1154 prefix_identity,
1155 suffix_c0: pending.c0_vec3a(),
1156 suffix_c1: pending.c1_vec3a(),
1157 suffix_c2: pending.c2_vec3a(),
1158 suffix_t: pending.t_vec3a(),
1159 suffix_identity,
1160 })
1161 }
1162
1163 pub const fn with_fixed_prefix(
1173 mut self,
1174 joints: &[URDFJoint],
1175 ) -> Result<Self, URDFBuildError> {
1176 if joints.is_empty() {
1177 self.prefix_c0 = Vec3A::X;
1178 self.prefix_c1 = Vec3A::Y;
1179 self.prefix_c2 = Vec3A::Z;
1180 self.prefix_t = Vec3A::ZERO;
1181 self.prefix_identity = true;
1182 } else {
1183 let a = match compose_fixed_joints_raw(joints) {
1184 Ok(a) => a,
1185 Err(e) => return Err(e),
1186 };
1187 self.prefix_identity = a.is_identity();
1188 self.prefix_c0 = a.c0_vec3a();
1189 self.prefix_c1 = a.c1_vec3a();
1190 self.prefix_c2 = a.c2_vec3a();
1191 self.prefix_t = a.t_vec3a();
1192 }
1193 Ok(self)
1194 }
1195
1196 pub const fn with_fixed_suffix(
1210 mut self,
1211 joints: &[URDFJoint],
1212 ) -> Result<Self, URDFBuildError> {
1213 if joints.is_empty() {
1214 self.suffix_c0 = Vec3A::X;
1215 self.suffix_c1 = Vec3A::Y;
1216 self.suffix_c2 = Vec3A::Z;
1217 self.suffix_t = Vec3A::ZERO;
1218 self.suffix_identity = true;
1219 } else {
1220 let a = match compose_fixed_joints_raw(joints) {
1221 Ok(a) => a,
1222 Err(e) => return Err(e),
1223 };
1224 self.suffix_identity = a.is_identity();
1225 self.suffix_c0 = a.c0_vec3a();
1226 self.suffix_c1 = a.c1_vec3a();
1227 self.suffix_c2 = a.c2_vec3a();
1228 self.suffix_t = a.t_vec3a();
1229 }
1230 Ok(self)
1231 }
1232
1233 pub const fn with_fixed_joints(
1235 self,
1236 prefix: &[URDFJoint],
1237 suffix: &[URDFJoint],
1238 ) -> Result<Self, URDFBuildError> {
1239 match self.with_fixed_prefix(prefix) {
1240 Ok(s) => s.with_fixed_suffix(suffix),
1241 Err(e) => Err(e),
1242 }
1243 }
1244
1245 #[inline(always)]
1246 fn initial_frame(&self) -> (Vec3A, Vec3A, Vec3A, Vec3A) {
1247 if self.prefix_identity {
1248 (Vec3A::X, Vec3A::Y, Vec3A::Z, Vec3A::ZERO)
1249 } else {
1250 (self.prefix_c0, self.prefix_c1, self.prefix_c2, self.prefix_t)
1251 }
1252 }
1253
1254 #[inline(always)]
1255 fn apply_suffix(
1256 &self,
1257 c0: &mut Vec3A,
1258 c1: &mut Vec3A,
1259 c2: &mut Vec3A,
1260 t: &mut Vec3A,
1261 ) {
1262 let st = self.suffix_t;
1263 *t = st.x * *c0 + st.y * *c1 + st.z * *c2 + *t;
1264
1265 let fc0 = self.suffix_c0;
1266 let fc1 = self.suffix_c1;
1267 let fc2 = self.suffix_c2;
1268 let new_c0 = fc0.x * *c0 + fc0.y * *c1 + fc0.z * *c2;
1269 let new_c1 = fc1.x * *c0 + fc1.y * *c1 + fc1.z * *c2;
1270 let new_c2 = fc2.x * *c0 + fc2.y * *c1 + fc2.z * *c2;
1271 *c0 = new_c0;
1272 *c1 = new_c1;
1273 *c2 = new_c2;
1274 }
1275
1276 #[inline(always)]
1278 fn accumulate_joint(
1279 &self,
1280 i: usize,
1281 st: f32,
1282 ct: f32,
1283 c0: &mut Vec3A,
1284 c1: &mut Vec3A,
1285 c2: &mut Vec3A,
1286 t: &mut Vec3A,
1287 ) {
1288 let ft = self.fixed_trans[i];
1289 *t = ft.x * *c0 + ft.y * *c1 + ft.z * *c2 + *t;
1290
1291 let (f0, f1, f2) = if self.fr_identity[i] {
1292 (*c0, *c1, *c2)
1293 } else {
1294 let fc0 = self.fr_c0[i];
1295 let fc1 = self.fr_c1[i];
1296 let fc2 = self.fr_c2[i];
1297 (
1298 fc0.x * *c0 + fc0.y * *c1 + fc0.z * *c2,
1299 fc1.x * *c0 + fc1.y * *c1 + fc1.z * *c2,
1300 fc2.x * *c0 + fc2.y * *c1 + fc2.z * *c2,
1301 )
1302 };
1303
1304 match self.axis[i] {
1305 JointAxis::Z => {
1306 let new_c0 = ct * f0 + st * f1;
1307 let new_c1 = ct * f1 - st * f0;
1308 *c0 = new_c0;
1309 *c1 = new_c1;
1310 *c2 = f2;
1311 }
1312 JointAxis::Y(s) => {
1313 let sst = s * st;
1314 let new_c0 = ct * f0 - sst * f2;
1315 let new_c2 = sst * f0 + ct * f2;
1316 *c0 = new_c0;
1317 *c1 = f1;
1318 *c2 = new_c2;
1319 }
1320 JointAxis::X(s) => {
1321 let sst = s * st;
1322 let new_c1 = ct * f1 + sst * f2;
1323 let new_c2 = ct * f2 - sst * f1;
1324 *c0 = f0;
1325 *c1 = new_c1;
1326 *c2 = new_c2;
1327 }
1328 }
1329 }
1330}
1331
1332impl<const N: usize> FKChain<N> for URDFChain<N> {
1333 #[cfg(debug_assertions)]
1334 type Error = DekeError;
1335 #[cfg(not(debug_assertions))]
1336 type Error = std::convert::Infallible;
1337
1338 fn fk(&self, q: &SRobotQ<N>) -> Result<[Affine3A; N], Self::Error> {
1339 check_finite(q)?;
1340 let mut out = [Affine3A::IDENTITY; N];
1341 let (mut c0, mut c1, mut c2, mut t) = self.initial_frame();
1342
1343 let mut i = 0;
1344 while i < N {
1345 let (st, ct) = fast_sin_cos(q.0[i]);
1346 self.accumulate_joint(i, st, ct, &mut c0, &mut c1, &mut c2, &mut t);
1347
1348 out[i] = Affine3A {
1349 matrix3: Mat3A::from_cols(c0, c1, c2),
1350 translation: t,
1351 };
1352 i += 1;
1353 }
1354
1355 if N > 0 && !self.suffix_identity {
1356 self.apply_suffix(&mut c0, &mut c1, &mut c2, &mut t);
1357 out[N - 1] = Affine3A {
1358 matrix3: Mat3A::from_cols(c0, c1, c2),
1359 translation: t,
1360 };
1361 }
1362 Ok(out)
1363 }
1364
1365 fn fk_end(&self, q: &SRobotQ<N>) -> Result<Affine3A, Self::Error> {
1366 check_finite(q)?;
1367 let (mut c0, mut c1, mut c2, mut t) = self.initial_frame();
1368
1369 let mut i = 0;
1370 while i < N {
1371 let (st, ct) = fast_sin_cos(q.0[i]);
1372 self.accumulate_joint(i, st, ct, &mut c0, &mut c1, &mut c2, &mut t);
1373 i += 1;
1374 }
1375
1376 if !self.suffix_identity {
1377 self.apply_suffix(&mut c0, &mut c1, &mut c2, &mut t);
1378 }
1379
1380 Ok(Affine3A {
1381 matrix3: Mat3A::from_cols(c0, c1, c2),
1382 translation: t,
1383 })
1384 }
1385
1386 fn joint_axes_positions(
1387 &self,
1388 q: &SRobotQ<N>,
1389 ) -> Result<([Vec3A; N], [Vec3A; N], Vec3A), Self::Error> {
1390 check_finite(q)?;
1391 let mut frames = [Affine3A::IDENTITY; N];
1392 let (mut c0, mut c1, mut c2, mut t) = self.initial_frame();
1393
1394 let mut i = 0;
1395 while i < N {
1396 let (st, ct) = fast_sin_cos(q.0[i]);
1397 self.accumulate_joint(i, st, ct, &mut c0, &mut c1, &mut c2, &mut t);
1398 frames[i] = Affine3A {
1399 matrix3: Mat3A::from_cols(c0, c1, c2),
1400 translation: t,
1401 };
1402 i += 1;
1403 }
1404
1405 let mut axes = [Vec3A::ZERO; N];
1406 let mut positions = [Vec3A::ZERO; N];
1407
1408 for i in 0..N {
1409 axes[i] = match self.axis[i] {
1410 JointAxis::Z => frames[i].matrix3.z_axis,
1411 JointAxis::Y(s) => s * frames[i].matrix3.y_axis,
1412 JointAxis::X(s) => s * frames[i].matrix3.x_axis,
1413 };
1414 positions[i] = frames[i].translation;
1415 }
1416
1417 let p_ee = if N == 0 {
1418 Vec3A::ZERO
1419 } else if !self.suffix_identity {
1420 self.apply_suffix(&mut c0, &mut c1, &mut c2, &mut t);
1421 t
1422 } else {
1423 frames[N - 1].translation
1424 };
1425
1426 Ok((axes, positions, p_ee))
1427 }
1428}
1429
1430#[derive(Debug, Clone)]
1437pub struct TransformedFK<const N: usize, FK: FKChain<N>> {
1438 inner: FK,
1439 prefix: Option<Affine3A>,
1440 suffix: Option<Affine3A>,
1441}
1442
1443impl<const N: usize, FK: FKChain<N>> TransformedFK<N, FK> {
1444 pub const fn new(inner: FK) -> Self {
1445 Self {
1446 inner,
1447 prefix: None,
1448 suffix: None,
1449 }
1450 }
1451
1452 pub const fn with_prefix(mut self, prefix: Affine3A) -> Self {
1453 self.prefix = Some(prefix);
1454 self
1455 }
1456
1457 pub const fn with_suffix(mut self, suffix: Affine3A) -> Self {
1458 self.suffix = Some(suffix);
1459 self
1460 }
1461
1462 pub const fn with_prefix_opt(mut self, prefix: Option<Affine3A>) -> Self {
1466 self.prefix = prefix;
1467 self
1468 }
1469
1470 pub const fn with_suffix_opt(mut self, suffix: Option<Affine3A>) -> Self {
1474 self.suffix = suffix;
1475 self
1476 }
1477
1478 pub fn with_prefix_joints(mut self, joints: &[URDFJoint]) -> Result<Self, URDFBuildError> {
1483 if joints.is_empty() {
1484 self.prefix = None;
1485 Ok(self)
1486 } else {
1487 self.prefix = Some(compose_fixed_joints(joints)?);
1488 Ok(self)
1489 }
1490 }
1491
1492 pub fn with_suffix_joints(mut self, joints: &[URDFJoint]) -> Result<Self, URDFBuildError> {
1497 if joints.is_empty() {
1498 self.suffix = None;
1499 Ok(self)
1500 } else {
1501 self.suffix = Some(compose_fixed_joints(joints)?);
1502 Ok(self)
1503 }
1504 }
1505
1506 pub fn set_prefix(&mut self, prefix: Option<Affine3A>) {
1507 self.prefix = prefix;
1508 }
1509
1510 pub fn set_suffix(&mut self, suffix: Option<Affine3A>) {
1511 self.suffix = suffix;
1512 }
1513
1514 pub fn prefix(&self) -> Option<&Affine3A> {
1515 self.prefix.as_ref()
1516 }
1517
1518 pub fn suffix(&self) -> Option<&Affine3A> {
1519 self.suffix.as_ref()
1520 }
1521
1522 pub fn inner(&self) -> &FK {
1523 &self.inner
1524 }
1525}
1526
1527impl<const N: usize, FK: FKChain<N>> FKChain<N> for TransformedFK<N, FK> {
1528 type Error = FK::Error;
1529
1530 fn max_reach(&self) -> Result<f32, Self::Error> {
1531 let mut reach = self.inner.max_reach()?;
1532 if let Some(suf) = &self.suffix {
1533 reach += Vec3A::from(suf.translation).length();
1534 }
1535 Ok(reach)
1536 }
1537
1538 fn fk(&self, q: &SRobotQ<N>) -> Result<[Affine3A; N], Self::Error> {
1539 let mut frames = self.inner.fk(q)?;
1540 if let Some(pre) = &self.prefix {
1541 for f in &mut frames {
1542 *f = *pre * *f;
1543 }
1544 }
1545 Ok(frames)
1546 }
1547
1548 fn fk_end(&self, q: &SRobotQ<N>) -> Result<Affine3A, Self::Error> {
1549 let mut end = self.inner.fk_end(q)?;
1550 if let Some(pre) = &self.prefix {
1551 end = *pre * end;
1552 }
1553 if let Some(suf) = &self.suffix {
1554 end = end * *suf;
1555 }
1556 Ok(end)
1557 }
1558
1559 fn joint_axes_positions(
1560 &self,
1561 q: &SRobotQ<N>,
1562 ) -> Result<([Vec3A; N], [Vec3A; N], Vec3A), Self::Error> {
1563 let (mut axes, mut positions, inner_p_ee) = self.inner.joint_axes_positions(q)?;
1564
1565 if let Some(pre) = &self.prefix {
1566 let rot = pre.matrix3;
1567 let t = Vec3A::from(pre.translation);
1568 for i in 0..N {
1569 axes[i] = rot * axes[i];
1570 positions[i] = rot * positions[i] + t;
1571 }
1572 }
1573
1574 let p_ee = if self.prefix.is_some() || self.suffix.is_some() {
1575 self.fk_end(q)?.translation
1576 } else {
1577 inner_p_ee
1578 };
1579
1580 Ok((axes, positions, p_ee))
1581 }
1582}
1583
1584#[derive(Debug, Clone)]
1598pub struct PrismaticFK<const M: usize, const N: usize, FK: FKChain<N>> {
1599 inner: FK,
1600 axis: Vec3A,
1601 q_index_first: bool,
1602}
1603
1604impl<const M: usize, const N: usize, FK: FKChain<N>> PrismaticFK<M, N, FK> {
1605 pub const fn new(inner: FK, axis: Vec3A, q_index_first: bool) -> Self {
1606 const { assert!(M == N + 1, "M must equal N + 1") };
1607 Self {
1608 inner,
1609 axis,
1610 q_index_first,
1611 }
1612 }
1613
1614 pub fn inner(&self) -> &FK {
1615 &self.inner
1616 }
1617
1618 pub fn axis(&self) -> Vec3A {
1619 self.axis
1620 }
1621
1622 pub fn q_index_first(&self) -> bool {
1623 self.q_index_first
1624 }
1625
1626 fn split_q(&self, q: &SRobotQ<M>) -> (f32, SRobotQ<N>) {
1627 let mut inner = [0.0f32; N];
1628 if self.q_index_first {
1629 inner.copy_from_slice(&q.0[1..M]);
1630 (q.0[0], SRobotQ(inner))
1631 } else {
1632 inner.copy_from_slice(&q.0[..N]);
1633 (q.0[M - 1], SRobotQ(inner))
1634 }
1635 }
1636
1637 fn prismatic_col(&self) -> usize {
1638 if self.q_index_first { 0 } else { N }
1639 }
1640
1641 fn revolute_offset(&self) -> usize {
1642 if self.q_index_first { 1 } else { 0 }
1643 }
1644}
1645
1646impl<const M: usize, const N: usize, FK: FKChain<N>> FKChain<M> for PrismaticFK<M, N, FK> {
1647 type Error = FK::Error;
1648
1649 fn fk(&self, q: &SRobotQ<M>) -> Result<[Affine3A; M], Self::Error> {
1650 let (q_p, inner_q) = self.split_q(q);
1651 let offset = q_p * self.axis;
1652 let inner_frames = self.inner.fk(&inner_q)?;
1653 let mut out = [Affine3A::IDENTITY; M];
1654
1655 out[0] = Affine3A::from_translation(offset.into());
1656 for i in 0..N {
1657 let mut f = inner_frames[i];
1658 f.translation += offset;
1659 out[i + 1] = f;
1660 }
1661
1662 Ok(out)
1663 }
1664
1665 fn fk_end(&self, q: &SRobotQ<M>) -> Result<Affine3A, Self::Error> {
1666 let (q_p, inner_q) = self.split_q(q);
1667 let mut end = self.inner.fk_end(&inner_q)?;
1668 end.translation += q_p * self.axis;
1669 Ok(end)
1670 }
1671
1672 fn joint_axes_positions(
1673 &self,
1674 q: &SRobotQ<M>,
1675 ) -> Result<([Vec3A; M], [Vec3A; M], Vec3A), Self::Error> {
1676 let (q_p, inner_q) = self.split_q(q);
1677 let offset = q_p * self.axis;
1678 let (inner_axes, inner_pos, inner_p_ee) = self.inner.joint_axes_positions(&inner_q)?;
1679
1680 let mut axes = [Vec3A::ZERO; M];
1681 let mut positions = [Vec3A::ZERO; M];
1682
1683 axes[0] = self.axis;
1684 for i in 0..N {
1685 axes[i + 1] = inner_axes[i];
1686 positions[i + 1] = inner_pos[i] + offset;
1687 }
1688
1689 Ok((axes, positions, inner_p_ee + offset))
1690 }
1691
1692 fn jacobian(&self, q: &SRobotQ<M>) -> Result<[[f32; M]; 6], Self::Error> {
1693 let (_q_p, inner_q) = self.split_q(q);
1694 let inner_j = self.inner.jacobian(&inner_q)?;
1695 let p_col = self.prismatic_col();
1696 let r_off = self.revolute_offset();
1697
1698 let mut j = [[0.0f32; M]; 6];
1699 j[0][p_col] = self.axis.x;
1700 j[1][p_col] = self.axis.y;
1701 j[2][p_col] = self.axis.z;
1702
1703 for row in 0..6 {
1704 for col in 0..N {
1705 j[row][col + r_off] = inner_j[row][col];
1706 }
1707 }
1708
1709 Ok(j)
1710 }
1711
1712 fn jacobian_dot(
1713 &self,
1714 q: &SRobotQ<M>,
1715 qdot: &SRobotQ<M>,
1716 ) -> Result<[[f32; M]; 6], Self::Error> {
1717 let (_q_p, inner_q) = self.split_q(q);
1718 let (_qdot_p, inner_qdot) = self.split_q(qdot);
1719 let inner_jd = self.inner.jacobian_dot(&inner_q, &inner_qdot)?;
1720 let r_off = self.revolute_offset();
1721
1722 let mut jd = [[0.0f32; M]; 6];
1723 for row in 0..6 {
1724 for col in 0..N {
1725 jd[row][col + r_off] = inner_jd[row][col];
1726 }
1727 }
1728
1729 Ok(jd)
1730 }
1731
1732 fn jacobian_ddot(
1733 &self,
1734 q: &SRobotQ<M>,
1735 qdot: &SRobotQ<M>,
1736 qddot: &SRobotQ<M>,
1737 ) -> Result<[[f32; M]; 6], Self::Error> {
1738 let (_q_p, inner_q) = self.split_q(q);
1739 let (_qdot_p, inner_qdot) = self.split_q(qdot);
1740 let (_qddot_p, inner_qddot) = self.split_q(qddot);
1741 let inner_jdd = self
1742 .inner
1743 .jacobian_ddot(&inner_q, &inner_qdot, &inner_qddot)?;
1744 let r_off = self.revolute_offset();
1745
1746 let mut jdd = [[0.0f32; M]; 6];
1747 for row in 0..6 {
1748 for col in 0..N {
1749 jdd[row][col + r_off] = inner_jdd[row][col];
1750 }
1751 }
1752
1753 Ok(jdd)
1754 }
1755}