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