1use crate::FrameIdString;
2use crate::error::{TransformError, TransformResult};
3use crate::transform::{StampedTransform, TransformStore};
4use crate::transform_payload::StampedFrameTransform;
5use crate::velocity::VelocityTransform;
6use crate::velocity_cache::VelocityTransformCache;
7use cu_spatial_payloads::Transform3D;
8use cu29::clock::{CuTime, RobotClock, Tov};
9use dashmap::DashMap;
10use petgraph::algo::dijkstra;
11use petgraph::graph::{DiGraph, NodeIndex};
12use serde::Serialize;
13use serde::de::DeserializeOwned;
14use std::collections::HashMap;
15use std::fmt::Debug;
16use std::ops::Neg;
17use std::time::Duration;
18
19pub trait HasInverse<T: Copy + Debug + 'static> {
21 fn inverse(&self) -> Self;
22}
23
24impl HasInverse<f32> for Transform3D<f32> {
25 fn inverse(&self) -> Self {
26 self.inverse()
27 }
28}
29
30impl HasInverse<f64> for Transform3D<f64> {
31 fn inverse(&self) -> Self {
32 self.inverse()
33 }
34}
35
36#[derive(Clone)]
38struct TransformCacheEntry<T: Copy + Debug + 'static> {
39 transform: Transform3D<T>,
41 time: CuTime,
43 last_access: CuTime,
45 path_hash: u64,
47}
48
49struct TransformCache<T: Copy + Debug + 'static> {
51 entries: DashMap<(FrameIdString, FrameIdString), TransformCacheEntry<T>>,
53 max_size: usize,
55 max_age_nanos: u64,
57 last_cleanup_cell: std::sync::Mutex<CuTime>,
59 cleanup_interval_nanos: u64,
61}
62
63impl<T: Copy + Debug + 'static> TransformCache<T> {
64 fn new(max_size: usize, max_age: Duration) -> Self {
65 Self {
66 entries: DashMap::with_capacity(max_size),
67 max_size,
68 max_age_nanos: max_age.as_nanos() as u64,
69 last_cleanup_cell: std::sync::Mutex::new(CuTime::from(0u64)),
70 cleanup_interval_nanos: 5_000_000_000, }
72 }
73
74 fn get(
76 &self,
77 from: &str,
78 to: &str,
79 time: CuTime,
80 path_hash: u64,
81 robot_clock: &RobotClock,
82 ) -> Option<Transform3D<T>> {
83 let key = (
84 FrameIdString::from(from).expect("Frame name too long"),
85 FrameIdString::from(to).expect("Frame name too long"),
86 );
87
88 if let Some(mut entry) = self.entries.get_mut(&key) {
89 let now = robot_clock.now();
90
91 if entry.time == time && entry.path_hash == path_hash {
93 let age = now.as_nanos().saturating_sub(entry.last_access.as_nanos());
95 if age <= self.max_age_nanos {
96 entry.last_access = now;
98 return Some(entry.transform);
99 }
100 }
101 }
102
103 None
104 }
105
106 fn insert(
108 &self,
109 from: &str,
110 to: &str,
111 transform: Transform3D<T>,
112 time: CuTime,
113 path_hash: u64,
114 robot_clock: &RobotClock,
115 ) {
116 let now = robot_clock.now();
117 let key = (
118 FrameIdString::from(from).expect("Frame name too long"),
119 FrameIdString::from(to).expect("Frame name too long"),
120 );
121
122 if self.entries.len() >= self.max_size {
124 let mut oldest_key = None;
126 let mut oldest_time = now;
127
128 for entry in self.entries.iter() {
129 if entry.last_access < oldest_time {
130 oldest_time = entry.last_access;
131 oldest_key = Some(*entry.key());
132 }
133 }
134
135 if let Some(key_to_remove) = oldest_key {
136 self.entries.remove(&key_to_remove);
137 }
138 }
139
140 self.entries.insert(
142 key,
143 TransformCacheEntry {
144 transform,
145 time,
146 last_access: now,
147 path_hash,
148 },
149 );
150 }
151
152 fn should_cleanup(&self, robot_clock: &RobotClock) -> bool {
154 let now = robot_clock.now();
155 let last_cleanup = *self.last_cleanup_cell.lock().unwrap();
156 let elapsed = now.as_nanos().saturating_sub(last_cleanup.as_nanos());
157 elapsed >= self.cleanup_interval_nanos
158 }
159
160 fn cleanup(&self, robot_clock: &RobotClock) {
162 let now = robot_clock.now();
163 let mut keys_to_remove = Vec::new();
164
165 for entry in self.entries.iter() {
167 let age = now.as_nanos().saturating_sub(entry.last_access.as_nanos());
168 if age > self.max_age_nanos {
169 keys_to_remove.push(*entry.key());
170 }
171 }
172
173 for key in keys_to_remove {
175 self.entries.remove(&key);
176 }
177
178 *self.last_cleanup_cell.lock().unwrap() = now;
180 }
181
182 fn clear(&self) {
184 self.entries.clear();
185 }
186}
187
188pub struct TransformTree<T: Copy + Debug + Default + 'static> {
189 graph: DiGraph<FrameIdString, ()>,
190 frame_indices: HashMap<FrameIdString, NodeIndex>,
191 transform_store: TransformStore<T>,
192 cache: TransformCache<T>,
194 velocity_cache: VelocityTransformCache<T>,
196}
197
198pub trait One {
200 fn one() -> Self;
202}
203
204impl One for f32 {
206 fn one() -> Self {
207 1.0
208 }
209}
210
211impl One for f64 {
212 fn one() -> Self {
213 1.0
214 }
215}
216
217impl One for i32 {
218 fn one() -> Self {
219 1
220 }
221}
222
223impl One for i64 {
224 fn one() -> Self {
225 1
226 }
227}
228
229impl One for u32 {
230 fn one() -> Self {
231 1
232 }
233}
234
235impl One for u64 {
236 fn one() -> Self {
237 1
238 }
239}
240
241impl<T: Copy + Debug + Default + One + Serialize + DeserializeOwned + 'static + Neg<Output = T>>
244 TransformTree<T>
245where
246 Transform3D<T>: Clone + HasInverse<T> + std::ops::Mul<Output = Transform3D<T>>,
247 T: std::ops::Add<Output = T>
248 + std::ops::Sub<Output = T>
249 + std::ops::Mul<Output = T>
250 + std::ops::Div<Output = T>
251 + std::ops::AddAssign
252 + std::ops::SubAssign
253 + num_traits::NumCast,
254{
255 const DEFAULT_CACHE_SIZE: usize = 100;
257
258 const DEFAULT_CACHE_AGE: Duration = Duration::from_secs(5);
260
261 pub fn new() -> Self {
263 Self {
264 graph: DiGraph::new(),
265 frame_indices: HashMap::new(),
266 transform_store: TransformStore::new(),
267 cache: TransformCache::new(Self::DEFAULT_CACHE_SIZE, Self::DEFAULT_CACHE_AGE),
268 velocity_cache: VelocityTransformCache::new(
269 Self::DEFAULT_CACHE_SIZE,
270 Self::DEFAULT_CACHE_AGE.as_nanos() as u64,
271 ),
272 }
273 }
274
275 pub fn with_cache_settings(cache_size: usize, cache_age: Duration) -> Self {
277 Self {
278 graph: DiGraph::new(),
279 frame_indices: HashMap::new(),
280 transform_store: TransformStore::new(),
281 cache: TransformCache::new(cache_size, cache_age),
282 velocity_cache: VelocityTransformCache::new(cache_size, cache_age.as_nanos() as u64),
283 }
284 }
285
286 pub fn clear_cache(&self) {
288 self.cache.clear();
289 self.velocity_cache.clear();
290 }
291
292 pub fn cleanup_cache(&self, robot_clock: &RobotClock) {
294 self.cache.cleanup(robot_clock);
295 self.velocity_cache.cleanup(robot_clock);
296 }
297
298 fn create_identity_transform() -> Transform3D<T> {
300 let mut mat = [[T::default(); 4]; 4];
301
302 let one = T::one();
304 mat[0][0] = one;
305 mat[1][1] = one;
306 mat[2][2] = one;
307 mat[3][3] = one;
308
309 Transform3D::from_matrix(mat)
310 }
311
312 fn ensure_frame(&mut self, frame_id: &str) -> NodeIndex {
313 let frame_id_string = FrameIdString::from(frame_id).expect("Frame name too long");
314 *self
315 .frame_indices
316 .entry(frame_id_string)
317 .or_insert_with(|| self.graph.add_node(frame_id_string))
318 }
319
320 pub fn add_transform(&mut self, sft: &StampedFrameTransform<T>) -> TransformResult<()>
322 where
323 T: bincode::Encode + bincode::Decode<()>,
324 {
325 let transform_msg = sft.payload().ok_or_else(|| {
326 TransformError::Unknown("Failed to get transform payload".to_string())
327 })?;
328
329 let timestamp = match sft.tov {
330 Tov::Time(time) => time,
331 Tov::Range(range) => range.start, _ => {
333 return Err(TransformError::Unknown(
334 "Invalid Time of Validity".to_string(),
335 ));
336 }
337 };
338
339 let parent_idx = self.ensure_frame(&transform_msg.parent_frame);
341 let child_idx = self.ensure_frame(&transform_msg.child_frame);
342
343 if self.would_create_cycle(parent_idx, child_idx) {
345 return Err(TransformError::CyclicTransformTree);
346 }
347
348 if !self.graph.contains_edge(parent_idx, child_idx) {
350 self.graph.add_edge(parent_idx, child_idx, ());
351 }
352
353 self.velocity_cache.clear();
355
356 let stamped = StampedTransform {
358 transform: transform_msg.transform,
359 stamp: timestamp,
360 parent_frame: transform_msg.parent_frame,
361 child_frame: transform_msg.child_frame,
362 };
363
364 self.transform_store.add_transform(stamped);
366 Ok(())
367 }
368
369 fn would_create_cycle(&self, parent: NodeIndex, child: NodeIndex) -> bool {
370 if self.graph.contains_edge(parent, child) {
371 return false;
372 }
373
374 matches!(dijkstra(&self.graph, child, Some(parent), |_| 1), result if result.contains_key(&parent))
375 }
376
377 pub fn find_path(
378 &self,
379 from_frame: &str,
380 to_frame: &str,
381 ) -> TransformResult<Vec<(FrameIdString, FrameIdString, bool)>> {
382 if from_frame == to_frame {
384 return Ok(Vec::new());
385 }
386
387 let from_frame_id = FrameIdString::from(from_frame).expect("Frame name too long");
388 let from_idx = self
389 .frame_indices
390 .get(&from_frame_id)
391 .ok_or(TransformError::FrameNotFound(from_frame.to_string()))?;
392
393 let to_frame_id = FrameIdString::from(to_frame).expect("Frame name too long");
394 let to_idx = self
395 .frame_indices
396 .get(&to_frame_id)
397 .ok_or(TransformError::FrameNotFound(to_frame.to_string()))?;
398
399 let mut undirected_graph = self.graph.clone();
401
402 let edges: Vec<_> = self.graph.edge_indices().collect();
404 for edge_idx in edges {
405 let (a, b) = self.graph.edge_endpoints(edge_idx).unwrap();
406 if !undirected_graph.contains_edge(b, a) {
407 undirected_graph.add_edge(b, a, ());
408 }
409 }
410
411 let path = dijkstra(&undirected_graph, *from_idx, Some(*to_idx), |_| 1);
413
414 if !path.contains_key(to_idx) {
415 return Err(TransformError::TransformNotFound {
416 from: from_frame.to_string(),
417 to: to_frame.to_string(),
418 });
419 }
420
421 let mut current = *to_idx;
423 let mut path_nodes = vec![current];
424
425 while current != *from_idx {
426 let mut found_next = false;
427
428 for neighbor in undirected_graph.neighbors(current) {
430 if path.contains_key(&neighbor) && path[&neighbor] < path[¤t] {
431 current = neighbor;
432 path_nodes.push(current);
433 found_next = true;
434 break;
435 }
436 }
437
438 if !found_next {
439 return Err(TransformError::TransformNotFound {
440 from: from_frame.to_string(),
441 to: to_frame.to_string(),
442 });
443 }
444 }
445
446 path_nodes.reverse();
447
448 let mut path_edges = Vec::new();
450 for i in 0..path_nodes.len() - 1 {
451 let parent_idx = path_nodes[i];
452 let child_idx = path_nodes[i + 1];
453
454 let parent_frame = self.graph[parent_idx];
455 let child_frame = self.graph[child_idx];
456
457 let is_forward = self.graph.contains_edge(parent_idx, child_idx);
459
460 if is_forward {
461 path_edges.push((parent_frame, child_frame, false));
463 } else {
464 path_edges.push((child_frame, parent_frame, true));
466 }
467 }
468
469 Ok(path_edges)
470 }
471
472 fn compute_path_hash(path: &[(FrameIdString, FrameIdString, bool)]) -> u64 {
474 use std::collections::hash_map::DefaultHasher;
475 use std::hash::{Hash, Hasher};
476
477 let mut hasher = DefaultHasher::new();
478
479 for (parent, child, inverse) in path {
480 parent.hash(&mut hasher);
481 child.hash(&mut hasher);
482 inverse.hash(&mut hasher);
483 }
484
485 hasher.finish()
486 }
487
488 pub fn lookup_transform(
489 &self,
490 from_frame: &str,
491 to_frame: &str,
492 time: CuTime,
493 robot_clock: &RobotClock,
494 ) -> TransformResult<Transform3D<T>> {
495 if from_frame == to_frame {
497 return Ok(Self::create_identity_transform());
498 }
499
500 let path = self.find_path(from_frame, to_frame)?;
502
503 if path.is_empty() {
504 return Ok(Self::create_identity_transform());
506 }
507
508 let path_hash = Self::compute_path_hash(&path);
510
511 if let Some(cached_transform) =
513 self.cache
514 .get(from_frame, to_frame, time, path_hash, robot_clock)
515 {
516 return Ok(cached_transform);
517 }
518
519 if self.cache.should_cleanup(robot_clock) {
521 self.cache.cleanup(robot_clock);
522 }
523
524 let mut result = Self::create_identity_transform();
528
529 for (parent, child, inverse) in &path {
531 let buffer = match self.transform_store.get_buffer(parent, child) {
533 Some(b) => b,
534 None => {
535 return Err(TransformError::TransformNotFound {
537 from: parent.to_string(),
538 to: child.to_string(),
539 });
540 }
541 };
542
543 let transform = buffer
544 .get_closest_transform(time)
545 .ok_or(TransformError::TransformTimeNotAvailable(time))?;
546
547 if *inverse {
549 let transform_to_apply = transform.transform.inverse();
552 result = transform_to_apply * result;
553 } else {
554 let transform_to_apply = transform.transform;
557 result = transform_to_apply * result;
558 }
559 }
560
561 self.cache
563 .insert(from_frame, to_frame, result, time, path_hash, robot_clock);
564
565 Ok(result)
566 }
567
568 pub fn lookup_velocity(
596 &self,
597 from_frame: &str,
598 to_frame: &str,
599 time: CuTime,
600 robot_clock: &RobotClock,
601 ) -> TransformResult<VelocityTransform<T>> {
602 if from_frame == to_frame {
604 return Ok(VelocityTransform::default());
605 }
606
607 let path = self.find_path(from_frame, to_frame)?;
609
610 if path.is_empty() {
611 return Ok(VelocityTransform::default());
613 }
614
615 let path_hash = Self::compute_path_hash(&path);
617
618 if let Some(cached_velocity) =
620 self.velocity_cache
621 .get(from_frame, to_frame, time, path_hash, robot_clock)
622 {
623 return Ok(cached_velocity);
624 }
625
626 if self.velocity_cache.should_cleanup(robot_clock) {
628 self.velocity_cache.cleanup(robot_clock);
629 }
630
631 let mut result = VelocityTransform::default();
635
636 for (parent, child, inverse) in &path {
638 let buffer = match self.transform_store.get_buffer(parent, child) {
640 Some(b) => b,
641 None => {
642 return Err(TransformError::TransformNotFound {
643 from: parent.to_string(),
644 to: child.to_string(),
645 });
646 }
647 };
648
649 let segment_velocity = buffer
651 .compute_velocity_at_time(time)
652 .ok_or(TransformError::TransformTimeNotAvailable(time))?;
653
654 let transform = buffer
656 .get_closest_transform(time)
657 .ok_or(TransformError::TransformTimeNotAvailable(time))?;
658
659 let position = [T::default(); 3]; if *inverse {
666 let inverse_transform = transform.transform.inverse();
668
669 let neg_velocity = VelocityTransform {
671 linear: [
672 -segment_velocity.linear[0],
673 -segment_velocity.linear[1],
674 -segment_velocity.linear[2],
675 ],
676 angular: [
677 -segment_velocity.angular[0],
678 -segment_velocity.angular[1],
679 -segment_velocity.angular[2],
680 ],
681 };
682
683 let transformed_velocity = crate::velocity::transform_velocity(
685 &neg_velocity,
686 &inverse_transform,
687 &position,
688 );
689
690 result.linear[0] += transformed_velocity.linear[0];
692 result.linear[1] += transformed_velocity.linear[1];
693 result.linear[2] += transformed_velocity.linear[2];
694
695 result.angular[0] += transformed_velocity.angular[0];
696 result.angular[1] += transformed_velocity.angular[1];
697 result.angular[2] += transformed_velocity.angular[2];
698 } else {
699 let transformed_velocity = crate::velocity::transform_velocity(
701 &segment_velocity,
702 &transform.transform,
703 &position,
704 );
705
706 result.linear[0] += transformed_velocity.linear[0];
708 result.linear[1] += transformed_velocity.linear[1];
709 result.linear[2] += transformed_velocity.linear[2];
710
711 result.angular[0] += transformed_velocity.angular[0];
712 result.angular[1] += transformed_velocity.angular[1];
713 result.angular[2] += transformed_velocity.angular[2];
714 }
715 }
716
717 self.velocity_cache.insert(
719 from_frame,
720 to_frame,
721 result.clone(),
722 time,
723 path_hash,
724 robot_clock,
725 );
726
727 Ok(result)
728 }
729}
730
731impl<T: Copy + Debug + Default + One + Serialize + DeserializeOwned + 'static + Neg<Output = T>>
732 Default for TransformTree<T>
733where
734 Transform3D<T>: Clone + HasInverse<T> + std::ops::Mul<Output = Transform3D<T>>,
735 T: std::ops::Add<Output = T>
736 + std::ops::Sub<Output = T>
737 + std::ops::Mul<Output = T>
738 + std::ops::Div<Output = T>
739 + std::ops::AddAssign
740 + std::ops::SubAssign
741 + num_traits::NumCast,
742{
743 fn default() -> Self {
744 Self::new()
745 }
746}
747
748#[cfg(test)]
749#[allow(deprecated)] mod tests {
751 use super::*;
752 use crate::test_utils::get_translation;
753 use crate::{FrameTransform, frame_id};
754 use cu29::clock::{CuDuration, RobotClock};
755
756 fn assert_approx_eq(actual: f32, expected: f32, epsilon: f32, message: &str) {
758 let diff = (actual - expected).abs();
759 assert!(
760 diff <= epsilon,
761 "{message}: expected {expected}, got {actual}, difference {diff} exceeds epsilon {epsilon}",
762 );
763 }
764
765 fn make_stamped(
766 parent: &str,
767 child: &str,
768 ts: CuDuration,
769 tf: Transform3D<f32>,
770 ) -> StampedFrameTransform<f32> {
771 let inner = FrameTransform {
772 transform: tf,
773 parent_frame: frame_id!(parent),
774 child_frame: frame_id!(child),
775 };
776 let mut stf = StampedFrameTransform::new(Some(inner));
777 stf.tov = ts.into();
778 stf
779 }
780
781 #[test]
784 fn test_add_transform() {
785 let mut tree = TransformTree::<f32>::new();
786
787 let inner = FrameTransform {
788 transform: Transform3D::default(),
789 parent_frame: frame_id!("world"),
790 child_frame: frame_id!("robot"),
791 };
792 let mut stf = StampedFrameTransform::new(Some(inner));
793 stf.tov = CuDuration(1000).into();
794
795 assert!(tree.add_transform(&stf).is_ok());
796 }
797
798 #[test]
799 fn test_cyclic_transforms() {
800 let mut tree = TransformTree::<f32>::new();
801
802 let transform1 = make_stamped("world", "robot", 1000.into(), Transform3D::default());
803 let transform2 = make_stamped("robot", "sensor", 1000.into(), Transform3D::default());
804 let transform3 = make_stamped("sensor", "world", 1000.into(), Transform3D::default());
805
806 assert!(tree.add_transform(&transform1).is_ok());
807 assert!(tree.add_transform(&transform2).is_ok());
808
809 let result = tree.add_transform(&transform3);
810 assert!(result.is_err());
811 if let Err(e) = result {
812 assert!(matches!(e, TransformError::CyclicTransformTree));
813 }
814 }
815
816 #[test]
817 fn test_find_path() {
818 let mut tree = TransformTree::<f32>::new();
819
820 let transform1 = make_stamped("world", "robot", 1000.into(), Transform3D::default());
821 let transform2 = make_stamped("robot", "sensor", 1000.into(), Transform3D::default());
822
823 assert!(tree.add_transform(&transform1).is_ok());
824 assert!(tree.add_transform(&transform2).is_ok());
825
826 let path = tree.find_path("world", "sensor");
827 assert!(path.is_ok());
828
829 let path_vec = path.unwrap();
830 assert_eq!(path_vec.len(), 2);
831 assert_eq!(path_vec[0].0.as_str(), "world");
832 assert_eq!(path_vec[0].1.as_str(), "robot");
833 assert_eq!(path_vec[1].0.as_str(), "robot");
834 assert_eq!(path_vec[1].1.as_str(), "sensor");
835 }
836
837 #[test]
838 fn test_lookup_transform_with_inverse() {
839 let mut tree = TransformTree::<f32>::new();
840
841 let matrix = [
842 [1.0, 0.0, 0.0, 0.0],
843 [0.0, 1.0, 0.0, 0.0],
844 [0.0, 0.0, 1.0, 0.0],
845 [2.0, 3.0, 4.0, 1.0],
846 ];
847 let tf = make_stamped(
848 "world",
849 "robot",
850 CuDuration(1000),
851 Transform3D::from_matrix(matrix),
852 );
853
854 assert!(tree.add_transform(&tf).is_ok());
855
856 let clock = RobotClock::default();
857
858 let forward = tree
859 .lookup_transform("world", "robot", CuDuration(1000), &clock)
860 .unwrap();
861 assert_eq!(get_translation(&forward).0, 2.0);
862 assert_eq!(get_translation(&forward).1, 3.0);
863 assert_eq!(get_translation(&forward).2, 4.0);
864
865 let inverse = tree
866 .lookup_transform("robot", "world", CuDuration(1000), &clock)
867 .unwrap();
868 assert_eq!(get_translation(&inverse).0, -2.0);
869 assert_eq!(get_translation(&inverse).1, -3.0);
870 assert_eq!(get_translation(&inverse).2, -4.0);
871 }
872
873 #[test]
874 fn test_multi_step_transform_composition() {
875 let mut tree = TransformTree::<f32>::new();
876 let ts = CuDuration(1000);
877
878 let world_to_base = make_stamped(
879 "world",
880 "base",
881 ts,
882 Transform3D::from_matrix([
883 [1.0, 0.0, 0.0, 0.0],
884 [0.0, 1.0, 0.0, 0.0],
885 [0.0, 0.0, 1.0, 0.0],
886 [1.0, 0.0, 0.0, 1.0],
887 ]),
888 );
889
890 let base_to_arm = make_stamped(
891 "base",
892 "arm",
893 ts,
894 Transform3D::from_matrix([
895 [0.0, 1.0, 0.0, 0.0],
896 [-1.0, 0.0, 0.0, 0.0],
897 [0.0, 0.0, 1.0, 0.0],
898 [0.0, 0.0, 0.0, 1.0],
899 ]),
900 );
901
902 let arm_to_gripper = make_stamped(
903 "arm",
904 "gripper",
905 ts,
906 Transform3D::from_matrix([
907 [1.0, 0.0, 0.0, 0.0],
908 [0.0, 1.0, 0.0, 0.0],
909 [0.0, 0.0, 1.0, 0.0],
910 [0.0, 2.0, 0.0, 1.0],
911 ]),
912 );
913
914 assert!(tree.add_transform(&world_to_base).is_ok());
915 assert!(tree.add_transform(&base_to_arm).is_ok());
916 assert!(tree.add_transform(&arm_to_gripper).is_ok());
917
918 let clock = RobotClock::default();
919 let transform = tree
920 .lookup_transform("world", "gripper", ts, &clock)
921 .unwrap();
922 let epsilon = 1e-5;
923
924 let mat = transform.to_matrix();
925 assert_approx_eq(mat[0][0], 0.0, epsilon, "mat_0_0");
926 assert_approx_eq(mat[1][0], -1.0, epsilon, "mat_1_0");
927 assert_approx_eq(mat[0][1], 1.0, epsilon, "mat_0_1");
928 assert_approx_eq(mat[1][1], 0.0, epsilon, "mat_1_1");
929
930 assert_approx_eq(get_translation(&transform).0, 0.0, epsilon, "translation_x");
931 assert_approx_eq(get_translation(&transform).1, 3.0, epsilon, "translation_y");
932 assert_approx_eq(get_translation(&transform).2, 0.0, epsilon, "translation_z");
933
934 let cached = tree
935 .lookup_transform("world", "gripper", ts, &clock)
936 .unwrap();
937 for i in 0..4 {
938 for j in 0..4 {
939 assert_approx_eq(
940 transform.to_matrix()[i][j],
941 cached.to_matrix()[i][j],
942 epsilon,
943 "matrix_element",
944 );
945 }
946 }
947
948 let inverse = tree
949 .lookup_transform("gripper", "world", ts, &clock)
950 .unwrap();
951 let inv_mat = inverse.to_matrix();
952 assert_approx_eq(inv_mat[1][0], 1.0, epsilon, "inv_mat_1_0");
953 assert_approx_eq(inv_mat[0][1], -1.0, epsilon, "inv_mat_0_1");
954 assert_approx_eq(get_translation(&inverse).0, -3.0, epsilon, "translation_x");
955 assert_approx_eq(get_translation(&inverse).1, 0.0, epsilon, "translation_y");
956
957 let product = transform * inverse;
958 for i in 0..4 {
959 for j in 0..4 {
960 let expected = if i == j { 1.0 } else { 0.0 };
961 assert_approx_eq(
962 product.to_matrix()[i][j],
963 expected,
964 epsilon,
965 "matrix_element",
966 );
967 }
968 }
969 }
970
971 #[test]
972 fn test_cache_invalidation() {
973 let mut tree = TransformTree::<f32>::with_cache_settings(5, Duration::from_millis(50));
974 let ts = CuDuration(1000);
975
976 let tf = make_stamped(
977 "a",
978 "b",
979 ts,
980 Transform3D::from_matrix([
981 [1.0, 0.0, 0.0, 0.0],
982 [0.0, 1.0, 0.0, 0.0],
983 [0.0, 0.0, 1.0, 0.0],
984 [1.0, 2.0, 3.0, 1.0],
985 ]),
986 );
987
988 assert!(tree.add_transform(&tf).is_ok());
989
990 let clock = RobotClock::default();
991 let result1 = tree.lookup_transform("a", "b", ts, &clock);
992 assert!(result1.is_ok());
993
994 let transform1 = result1.unwrap();
995 assert_eq!(get_translation(&transform1).0, 1.0);
996
997 std::thread::sleep(Duration::from_millis(100));
998
999 let result2 = tree.lookup_transform("a", "b", ts, &clock);
1000 assert!(result2.is_ok());
1001
1002 tree.clear_cache();
1003
1004 let result3 = tree.lookup_transform("a", "b", ts, &clock);
1005 assert!(result3.is_ok());
1006 }
1007
1008 #[test]
1009 fn test_multi_step_transform_with_inverse() {
1010 let mut tree = TransformTree::<f32>::new();
1011 let ts = CuDuration(1000);
1012
1013 let world_to_robot = make_stamped(
1014 "world",
1015 "robot",
1016 ts,
1017 Transform3D::from_matrix([
1018 [1.0, 0.0, 0.0, 0.0],
1019 [0.0, 1.0, 0.0, 0.0],
1020 [0.0, 0.0, 1.0, 0.0],
1021 [1.0, 2.0, 3.0, 1.0],
1022 ]),
1023 );
1024
1025 let robot_to_camera = make_stamped(
1026 "robot",
1027 "camera",
1028 ts,
1029 Transform3D::from_matrix([
1030 [0.0, 1.0, 0.0, 0.0],
1031 [-1.0, 0.0, 0.0, 0.0],
1032 [0.0, 0.0, 1.0, 0.0],
1033 [0.5, 0.0, 0.2, 1.0],
1034 ]),
1035 );
1036
1037 assert!(tree.add_transform(&world_to_robot).is_ok());
1038 assert!(tree.add_transform(&robot_to_camera).is_ok());
1039
1040 let clock = RobotClock::default();
1041 let transform = tree
1042 .lookup_transform("world", "camera", ts, &clock)
1043 .unwrap();
1044 let epsilon = 1e-5;
1045
1046 let mat = transform.to_matrix();
1047 assert_approx_eq(mat[0][0], 0.0, epsilon, "mat_0_0");
1048 assert_approx_eq(mat[1][0], -1.0, epsilon, "mat_1_0");
1049 assert_approx_eq(mat[0][1], 1.0, epsilon, "mat_0_1");
1050 assert_approx_eq(mat[1][1], 0.0, epsilon, "mat_1_1");
1051
1052 assert_approx_eq(
1053 get_translation(&transform).0,
1054 -1.5,
1055 epsilon,
1056 "translation_x",
1057 );
1058 assert_approx_eq(get_translation(&transform).1, 1.0, epsilon, "translation_y");
1059 assert_approx_eq(get_translation(&transform).2, 3.2, epsilon, "translation_z");
1060
1061 let inverse = tree.lookup_transform("camera", "world", ts, &clock);
1062 assert!(inverse.is_ok());
1063 }
1064
1065 #[test]
1066 fn test_cache_cleanup() {
1067 let tree = TransformTree::<f32>::with_cache_settings(5, Duration::from_millis(10));
1068
1069 let clock = RobotClock::default();
1071 tree.cleanup_cache(&clock);
1072 }
1073
1074 #[test]
1075 fn test_lookup_velocity() {
1076 let mut tree = TransformTree::<f32>::new();
1077
1078 let w2b_1 = make_stamped(
1079 "world",
1080 "base",
1081 CuDuration(1_000_000_000),
1082 Transform3D::from_matrix([
1083 [1.0, 0.0, 0.0, 0.0],
1084 [0.0, 1.0, 0.0, 0.0],
1085 [0.0, 0.0, 1.0, 0.0],
1086 [0.0, 0.0, 0.0, 1.0],
1087 ]),
1088 );
1089
1090 let w2b_2 = make_stamped(
1091 "world",
1092 "base",
1093 CuDuration(2_000_000_000),
1094 Transform3D::from_matrix([
1095 [1.0, 0.0, 0.0, 0.0],
1096 [0.0, 1.0, 0.0, 0.0],
1097 [0.0, 0.0, 1.0, 0.0],
1098 [1.0, 0.0, 0.0, 1.0],
1099 ]),
1100 );
1101
1102 let b2s_1 = make_stamped(
1103 "base",
1104 "sensor",
1105 CuDuration(1_000_000_000),
1106 Transform3D::from_matrix([
1107 [1.0, 0.0, 0.0, 0.0],
1108 [0.0, 1.0, 0.0, 0.0],
1109 [0.0, 0.0, 1.0, 0.0],
1110 [0.0, 0.0, 0.0, 1.0],
1111 ]),
1112 );
1113
1114 let b2s_2 = make_stamped(
1115 "base",
1116 "sensor",
1117 CuDuration(2_000_000_000),
1118 Transform3D::from_matrix([
1119 [1.0, 0.0, 0.0, 0.0],
1120 [0.0, 1.0, 0.0, 0.0],
1121 [0.0, 0.0, 1.0, 0.0],
1122 [0.0, 2.0, 0.0, 1.0],
1123 ]),
1124 );
1125
1126 tree.add_transform(&w2b_1).unwrap();
1127 tree.add_transform(&w2b_2).unwrap();
1128 tree.add_transform(&b2s_1).unwrap();
1129 tree.add_transform(&b2s_2).unwrap();
1130
1131 let clock = RobotClock::default();
1132 let velocity = tree.lookup_velocity("world", "sensor", CuDuration(1_500_000_000), &clock);
1133 assert!(velocity.is_ok());
1134
1135 let vel = velocity.unwrap();
1136 let epsilon = 0.1;
1137 assert_approx_eq(vel.linear[0], 1.0, epsilon, "linear_velocity_0");
1138 assert_approx_eq(vel.linear[1], 2.0, epsilon, "linear_velocity_1");
1139 assert_approx_eq(vel.linear[2], 0.0, epsilon, "linear_velocity_2");
1140 }
1141
1142 #[test]
1143 fn test_velocity_with_rotation() {
1144 let mut tree = TransformTree::<f32>::new();
1145
1146 let ts1 = CuDuration(1_000_000_000);
1147 let ts2 = CuDuration(2_000_000_000);
1148
1149 let w2b_1 = make_stamped(
1150 "world",
1151 "base",
1152 ts1,
1153 Transform3D::from_matrix([
1154 [1.0, 0.0, 0.0, 0.0],
1155 [0.0, 1.0, 0.0, 0.0],
1156 [0.0, 0.0, 1.0, 0.0],
1157 [0.0, 0.0, 0.0, 1.0],
1158 ]),
1159 );
1160
1161 let b2s_1 = make_stamped(
1162 "base",
1163 "sensor",
1164 ts1,
1165 Transform3D::from_matrix([
1166 [0.0, 1.0, 0.0, 0.0],
1167 [-1.0, 0.0, 0.0, 0.0],
1168 [0.0, 0.0, 1.0, 0.0],
1169 [1.0, 0.0, 0.0, 1.0],
1170 ]),
1171 );
1172
1173 let w2b_2 = make_stamped(
1174 "world",
1175 "base",
1176 ts2,
1177 Transform3D::from_matrix([
1178 [1.0, 0.0, 0.0, 0.0],
1179 [0.0, 1.0, 0.0, 0.0],
1180 [0.0, 0.0, 1.0, 0.0],
1181 [1.0, 0.0, 0.0, 1.0],
1182 ]),
1183 );
1184
1185 let b2s_2 = make_stamped(
1186 "base",
1187 "sensor",
1188 ts2,
1189 Transform3D::from_matrix([
1190 [0.0, 1.0, 0.0, 0.0],
1191 [-1.0, 0.0, 0.0, 0.0],
1192 [0.0, 0.0, 1.0, 0.0],
1193 [1.0, 0.0, 0.0, 1.0],
1194 ]),
1195 );
1196
1197 tree.add_transform(&w2b_1).unwrap();
1198 tree.add_transform(&w2b_2).unwrap();
1199 tree.add_transform(&b2s_1).unwrap();
1200 tree.add_transform(&b2s_2).unwrap();
1201
1202 let clock = RobotClock::default();
1203 let mid_ts = CuDuration(1_500_000_000);
1204
1205 let velocity = tree.lookup_velocity("world", "sensor", mid_ts, &clock);
1206 assert!(velocity.is_ok());
1207 let vel = velocity.unwrap();
1208 let epsilon = 0.2;
1209 assert_approx_eq(vel.linear[0], 1.0, epsilon, "linear_velocity_0");
1210 assert_approx_eq(vel.linear[1], 0.0, epsilon, "linear_velocity_1");
1211 assert_approx_eq(vel.linear[2], 0.0, epsilon, "linear_velocity_2");
1212
1213 let reverse = tree.lookup_velocity("sensor", "world", mid_ts, &clock);
1214 assert!(reverse.is_ok());
1215 let rev_vel = reverse.unwrap();
1216 assert_approx_eq(rev_vel.linear[0], -1.0, epsilon, "linear_velocity_0");
1217 assert_approx_eq(rev_vel.linear[1], 0.0, epsilon, "linear_velocity_1");
1218 assert_approx_eq(rev_vel.linear[2], 0.0, epsilon, "linear_velocity_2");
1219 }
1220
1221 #[test]
1222 fn test_velocity_with_angular_motion() {
1223 let mut tree = TransformTree::<f32>::new();
1224 let ts1 = CuDuration(1_000_000_000);
1225 let ts2 = CuDuration(2_000_000_000);
1226
1227 let w2b_1 = make_stamped(
1228 "world",
1229 "base",
1230 ts1,
1231 Transform3D::from_matrix([
1232 [1.0, 0.0, 0.0, 0.0],
1233 [0.0, 1.0, 0.0, 0.0],
1234 [0.0, 0.0, 1.0, 0.0],
1235 [0.0, 0.0, 0.0, 1.0],
1236 ]),
1237 );
1238
1239 let w2b_2 = make_stamped(
1240 "world",
1241 "base",
1242 ts2,
1243 Transform3D::from_matrix([
1244 [0.0, 1.0, 0.0, 0.0],
1245 [-1.0, 0.0, 0.0, 0.0],
1246 [0.0, 0.0, 1.0, 0.0],
1247 [0.0, 0.0, 0.0, 1.0],
1248 ]),
1249 );
1250
1251 let b2s_1 = make_stamped(
1252 "base",
1253 "sensor",
1254 ts1,
1255 Transform3D::from_matrix([
1256 [1.0, 0.0, 0.0, 0.0],
1257 [0.0, 1.0, 0.0, 0.0],
1258 [0.0, 0.0, 1.0, 0.0],
1259 [1.0, 0.0, 0.0, 1.0],
1260 ]),
1261 );
1262
1263 let b2s_2 = make_stamped(
1264 "base",
1265 "sensor",
1266 ts2,
1267 Transform3D::from_matrix([
1268 [1.0, 0.0, 0.0, 0.0],
1269 [0.0, 1.0, 0.0, 0.0],
1270 [0.0, 0.0, 1.0, 0.0],
1271 [1.0, 0.0, 0.0, 1.0],
1272 ]),
1273 );
1274
1275 tree.add_transform(&w2b_1).unwrap();
1276 tree.add_transform(&w2b_2).unwrap();
1277 tree.add_transform(&b2s_1).unwrap();
1278 tree.add_transform(&b2s_2).unwrap();
1279
1280 let clock = RobotClock::default();
1281 let vel = tree
1282 .lookup_velocity("world", "sensor", CuDuration(1_500_000_000), &clock)
1283 .unwrap();
1284
1285 let epsilon = 0.1;
1286 assert_approx_eq(vel.angular[0], 0.0, epsilon, "angular_velocity_0");
1287 assert_approx_eq(vel.angular[1], 0.0, epsilon, "angular_velocity_1");
1288 assert_approx_eq(vel.angular[2], -1.0, epsilon, "angular_velocity_2");
1289
1290 assert!(!vel.linear[0].is_nan());
1291 assert!(!vel.linear[1].is_nan());
1292 assert!(!vel.linear[2].is_nan());
1293
1294 assert!(!vel.angular[0].is_nan());
1295 assert!(!vel.angular[1].is_nan());
1296 assert!(!vel.angular[2].is_nan());
1297 }
1298
1299 #[test]
1300 fn test_velocity_cache() {
1301 let mut tree = TransformTree::<f32>::new();
1302 let ts1 = CuDuration(1_000_000_000);
1303 let ts2 = CuDuration(2_000_000_000);
1304
1305 let tf1 = make_stamped(
1306 "world",
1307 "robot",
1308 ts1,
1309 Transform3D::from_matrix([
1310 [1.0, 0.0, 0.0, 0.0],
1311 [0.0, 1.0, 0.0, 0.0],
1312 [0.0, 0.0, 1.0, 0.0],
1313 [0.0, 0.0, 0.0, 1.0],
1314 ]),
1315 );
1316
1317 let tf2 = make_stamped(
1318 "world",
1319 "robot",
1320 ts2,
1321 Transform3D::from_matrix([
1322 [1.0, 0.0, 0.0, 0.0],
1323 [0.0, 1.0, 0.0, 0.0],
1324 [0.0, 0.0, 1.0, 0.0],
1325 [2.0, 0.0, 0.0, 1.0],
1326 ]),
1327 );
1328
1329 tree.add_transform(&tf1).unwrap();
1330 tree.add_transform(&tf2).unwrap();
1331
1332 let clock = RobotClock::default();
1333
1334 let start_time = std::time::Instant::now();
1335 let velocity1 = tree.lookup_velocity("world", "robot", CuDuration(1_500_000_000), &clock);
1336 let first_lookup_time = start_time.elapsed();
1337
1338 assert!(velocity1.is_ok());
1339 let vel1 = velocity1.unwrap();
1340 assert_approx_eq(vel1.linear[0], 2.0, 0.01, "linear_velocity_0");
1341
1342 let start_time = std::time::Instant::now();
1343 let velocity2 = tree.lookup_velocity("world", "robot", CuDuration(1_500_000_000), &clock);
1344 let second_lookup_time = start_time.elapsed();
1345
1346 assert!(velocity2.is_ok());
1347 let vel2 = velocity2.unwrap();
1348 assert_approx_eq(vel2.linear[0], 2.0, 0.01, "linear_velocity_0");
1349
1350 tree.clear_cache();
1351
1352 let start_time = std::time::Instant::now();
1353 let velocity3 = tree.lookup_velocity("world", "robot", CuDuration(1_500_000_000), &clock);
1354 let third_lookup_time = start_time.elapsed();
1355
1356 assert!(velocity3.is_ok());
1357
1358 println!("First lookup: {first_lookup_time:?}");
1359 println!("Second lookup (cached): {second_lookup_time:?}");
1360 println!("Third lookup (after cache clear): {third_lookup_time:?}");
1361 }
1362
1363 #[test]
1364 fn test_velocity_cache_invalidation() {
1365 let mut tree = TransformTree::<f32>::new();
1366 let ts1 = CuDuration(1_000_000_000);
1367 let ts2 = CuDuration(2_000_000_000);
1368 let ts3 = CuDuration(3_000_000_000);
1369
1370 let tf1 = make_stamped(
1371 "world",
1372 "robot",
1373 ts1,
1374 Transform3D::from_matrix([
1375 [1.0, 0.0, 0.0, 0.0],
1376 [0.0, 1.0, 0.0, 0.0],
1377 [0.0, 0.0, 1.0, 0.0],
1378 [0.0, 0.0, 0.0, 1.0],
1379 ]),
1380 );
1381
1382 let tf2 = make_stamped(
1383 "world",
1384 "robot",
1385 ts2,
1386 Transform3D::from_matrix([
1387 [1.0, 0.0, 0.0, 0.0],
1388 [0.0, 1.0, 0.0, 0.0],
1389 [0.0, 0.0, 1.0, 0.0],
1390 [1.0, 0.0, 0.0, 1.0],
1391 ]),
1392 );
1393
1394 let tf3 = make_stamped(
1395 "world",
1396 "robot",
1397 ts3,
1398 Transform3D::from_matrix([
1399 [1.0, 0.0, 0.0, 0.0],
1400 [0.0, 1.0, 0.0, 0.0],
1401 [0.0, 0.0, 1.0, 0.0],
1402 [3.0, 0.0, 0.0, 1.0],
1403 ]),
1404 );
1405
1406 tree.add_transform(&tf1).unwrap();
1407 tree.add_transform(&tf2).unwrap();
1408
1409 let clock = RobotClock::default();
1410 let velocity1 = tree
1411 .lookup_velocity("world", "robot", CuDuration(1_500_000_000), &clock)
1412 .unwrap();
1413 assert_approx_eq(velocity1.linear[0], 1.0, 0.01, "linear_velocity_0");
1414
1415 tree.add_transform(&tf3).unwrap();
1416
1417 let velocity2 = tree
1418 .lookup_velocity("world", "robot", CuDuration(1_500_000_000), &clock)
1419 .unwrap();
1420 assert_approx_eq(velocity2.linear[0], 1.0, 0.01, "linear_velocity_0");
1421
1422 let velocity3 = tree
1423 .lookup_velocity("world", "robot", CuDuration(2_500_000_000), &clock)
1424 .unwrap();
1425 assert_approx_eq(velocity3.linear[0], 2.0, 0.01, "linear_velocity_0");
1426 }
1427}