cu_transform/
velocity.rs

1use bincode::{Decode, Encode};
2use core::fmt::Debug;
3use serde::{Deserialize, Serialize};
4use uom::si::angular_velocity::radian_per_second;
5use uom::si::f32::AngularVelocity as AngularVelocity32;
6use uom::si::f32::Velocity as Velocity32;
7use uom::si::f64::AngularVelocity as AngularVelocity64;
8use uom::si::f64::Velocity as Velocity64;
9use uom::si::velocity::meter_per_second;
10
11/// A struct representing linear and angular velocity in 3D space
12///
13/// The `VelocityTransform` encapsulates both linear and angular velocity components
14/// of a rigid body in 3D space. It complements the `Transform3D` struct which
15/// represents position and orientation.
16///
17/// Linear velocity is represented as a 3D vector [vx, vy, vz] in meters per second.
18/// Angular velocity is represented as a 3D vector [wx, wy, wz] in radians per second,
19/// where the vector represents the axis of rotation and the magnitude is the rate.
20///
21/// # Examples
22///
23/// ```
24/// use cu_transform::VelocityTransform;
25///
26/// // Create a velocity with 1 m/s forward and 0.5 rad/s rotation around Z axis
27/// let velocity = VelocityTransform::<f32> {
28///     linear: [1.0, 0.0, 0.0],
29///     angular: [0.0, 0.0, 0.5],
30/// };
31/// ```
32///
33/// Velocities can be transformed between coordinate frames using the
34/// `transform_velocity` function, and new velocities can be computed from time-stamped
35/// transforms using `StampedTransform::compute_velocity`.
36///
37/// When using the TransformTree to look up velocities with `lookup_velocity`, results
38/// are automatically cached for improved performance on repeated lookups. The cache is
39/// invalidated when new transforms are added or when entries exceed their age limit.
40#[derive(Debug, Clone, Encode, Decode, Serialize, Deserialize)]
41pub struct VelocityTransform<T: Copy + Debug + 'static> {
42    /// Linear velocity components [vx, vy, vz] in meters per second
43    pub linear: [T; 3],
44    /// Angular velocity components [wx, wy, wz] in radians per second
45    pub angular: [T; 3],
46}
47
48impl<T: Copy + Debug + Default + num_traits::Zero + 'static> VelocityTransform<T> {
49    /// Create a new velocity transform with zero velocities
50    pub fn zero() -> Self {
51        Self {
52            linear: [T::zero(); 3],
53            angular: [T::zero(); 3],
54        }
55    }
56}
57
58// Generic implementations for all numeric types
59impl<T> VelocityTransform<T>
60where
61    T: Copy
62        + Debug
63        + Default
64        + 'static
65        + std::ops::Add<Output = T>
66        + std::ops::Sub<Output = T>
67        + std::ops::Mul<Output = T>
68        + std::ops::Div<Output = T>
69        + std::ops::Neg<Output = T>,
70{
71    /// Add two velocity transforms component-wise
72    pub fn add(&self, other: &Self) -> Self {
73        Self {
74            linear: [
75                self.linear[0] + other.linear[0],
76                self.linear[1] + other.linear[1],
77                self.linear[2] + other.linear[2],
78            ],
79            angular: [
80                self.angular[0] + other.angular[0],
81                self.angular[1] + other.angular[1],
82                self.angular[2] + other.angular[2],
83            ],
84        }
85    }
86
87    /// Subtract two velocity transforms component-wise
88    pub fn sub(&self, other: &Self) -> Self {
89        Self {
90            linear: [
91                self.linear[0] - other.linear[0],
92                self.linear[1] - other.linear[1],
93                self.linear[2] - other.linear[2],
94            ],
95            angular: [
96                self.angular[0] - other.angular[0],
97                self.angular[1] - other.angular[1],
98                self.angular[2] - other.angular[2],
99            ],
100        }
101    }
102
103    /// Scale a velocity transform by a scalar
104    pub fn scale(&self, scalar: T) -> Self {
105        Self {
106            linear: [
107                self.linear[0] * scalar,
108                self.linear[1] * scalar,
109                self.linear[2] * scalar,
110            ],
111            angular: [
112                self.angular[0] * scalar,
113                self.angular[1] * scalar,
114                self.angular[2] * scalar,
115            ],
116        }
117    }
118
119    /// Negate a velocity transform
120    pub fn negate(&self) -> Self {
121        Self {
122            linear: [-self.linear[0], -self.linear[1], -self.linear[2]],
123            angular: [-self.angular[0], -self.angular[1], -self.angular[2]],
124        }
125    }
126}
127
128// Specific implementations for f32 and f64 that provide unit conversions
129impl VelocityTransform<f64> {
130    /// Get linear velocity components with units
131    pub fn linear_velocity(&self) -> [Velocity64; 3] {
132        [
133            Velocity64::new::<meter_per_second>(self.linear[0]),
134            Velocity64::new::<meter_per_second>(self.linear[1]),
135            Velocity64::new::<meter_per_second>(self.linear[2]),
136        ]
137    }
138
139    /// Get angular velocity components with units
140    pub fn angular_velocity(&self) -> [AngularVelocity64; 3] {
141        [
142            AngularVelocity64::new::<radian_per_second>(self.angular[0]),
143            AngularVelocity64::new::<radian_per_second>(self.angular[1]),
144            AngularVelocity64::new::<radian_per_second>(self.angular[2]),
145        ]
146    }
147}
148
149impl VelocityTransform<f32> {
150    /// Get linear velocity components with units
151    pub fn linear_velocity(&self) -> [Velocity32; 3] {
152        [
153            Velocity32::new::<meter_per_second>(self.linear[0]),
154            Velocity32::new::<meter_per_second>(self.linear[1]),
155            Velocity32::new::<meter_per_second>(self.linear[2]),
156        ]
157    }
158
159    /// Get angular velocity components with units
160    pub fn angular_velocity(&self) -> [AngularVelocity32; 3] {
161        [
162            AngularVelocity32::new::<radian_per_second>(self.angular[0]),
163            AngularVelocity32::new::<radian_per_second>(self.angular[1]),
164            AngularVelocity32::new::<radian_per_second>(self.angular[2]),
165        ]
166    }
167}
168
169impl<T: Copy + Debug + Default> Default for VelocityTransform<T> {
170    fn default() -> Self {
171        Self {
172            linear: [T::default(); 3],
173            angular: [T::default(); 3],
174        }
175    }
176}
177
178// Implement Add trait for VelocityTransform
179impl<T> std::ops::Add for VelocityTransform<T>
180where
181    T: Copy + Debug + Default + 'static + std::ops::Add<Output = T>,
182{
183    type Output = Self;
184
185    fn add(self, other: Self) -> Self::Output {
186        Self {
187            linear: [
188                self.linear[0] + other.linear[0],
189                self.linear[1] + other.linear[1],
190                self.linear[2] + other.linear[2],
191            ],
192            angular: [
193                self.angular[0] + other.angular[0],
194                self.angular[1] + other.angular[1],
195                self.angular[2] + other.angular[2],
196            ],
197        }
198    }
199}
200
201// Implement Sub trait for VelocityTransform
202impl<T> std::ops::Sub for VelocityTransform<T>
203where
204    T: Copy + Debug + Default + 'static + std::ops::Sub<Output = T>,
205{
206    type Output = Self;
207
208    fn sub(self, other: Self) -> Self::Output {
209        Self {
210            linear: [
211                self.linear[0] - other.linear[0],
212                self.linear[1] - other.linear[1],
213                self.linear[2] - other.linear[2],
214            ],
215            angular: [
216                self.angular[0] - other.angular[0],
217                self.angular[1] - other.angular[1],
218                self.angular[2] - other.angular[2],
219            ],
220        }
221    }
222}
223
224// Implement Neg trait for VelocityTransform
225impl<T> std::ops::Neg for VelocityTransform<T>
226where
227    T: Copy + Debug + Default + 'static + std::ops::Neg<Output = T>,
228{
229    type Output = Self;
230
231    fn neg(self) -> Self::Output {
232        Self {
233            linear: [-self.linear[0], -self.linear[1], -self.linear[2]],
234            angular: [-self.angular[0], -self.angular[1], -self.angular[2]],
235        }
236    }
237}
238
239/// Transform a velocity from one frame to another
240///
241/// Given a velocity in frame A and a transform from frame A to frame B,
242/// computes the equivalent velocity in frame B.
243///
244/// For a point moving with velocity v_a in frame A, the velocity v_b in frame B is:
245/// v_b = R * v_a + ω × (R * p_a)
246/// where:
247/// - R is the rotation matrix from A to B
248/// - ω is the angular velocity of frame A relative to frame B
249/// - p_a is the position of the point in frame A
250/// - × represents the cross product
251///
252/// For transform chain conversion, we follow similar rules as spatial transforms.
253pub fn transform_velocity<T>(
254    velocity: &VelocityTransform<T>,
255    transform: &crate::Transform3D<T>,
256    position: &[T; 3],
257) -> VelocityTransform<T>
258where
259    T: Copy
260        + Debug
261        + Default
262        + 'static
263        + std::ops::Add<Output = T>
264        + std::ops::Mul<Output = T>
265        + std::ops::Sub<Output = T>
266        + num_traits::NumCast,
267{
268    // Extract rotation matrix from transform
269    let mat = transform.to_matrix();
270    let rot = [
271        [mat[0][0], mat[0][1], mat[0][2]],
272        [mat[1][0], mat[1][1], mat[1][2]],
273        [mat[2][0], mat[2][1], mat[2][2]],
274    ];
275
276    // First, transform the angular velocity by applying rotation
277    let mut transformed_angular = [T::default(); 3];
278
279    // Angular velocity transforms as: ω_b = R * ω_a
280    for i in 0..3 {
281        for j in 0..3 {
282            transformed_angular[i] = transformed_angular[i] + rot[i][j] * velocity.angular[j];
283        }
284    }
285
286    // Next, transform the linear velocity
287    // First part: v'_linear = R * v_linear
288    let mut transformed_linear = [T::default(); 3];
289    for i in 0..3 {
290        for j in 0..3 {
291            transformed_linear[i] = transformed_linear[i] + rot[i][j] * velocity.linear[j];
292        }
293    }
294
295    // Second part: Add ω × (R * p)
296    // First calculate R * p
297    let mut rotated_position = [T::default(); 3];
298    for i in 0..3 {
299        for (j, pos) in position.iter().enumerate() {
300            rotated_position[i] = rotated_position[i] + rot[i][j] * *pos;
301        }
302    }
303
304    // Then calculate cross product ω × (R * p)
305    // (ω_x, ω_y, ω_z) × (p_x, p_y, p_z) = (ω_y*p_z - ω_z*p_y, ω_z*p_x - ω_x*p_z, ω_x*p_y - ω_y*p_x)
306    let cross_product = [
307        transformed_angular[1] * rotated_position[2] - transformed_angular[2] * rotated_position[1],
308        transformed_angular[2] * rotated_position[0] - transformed_angular[0] * rotated_position[2],
309        transformed_angular[0] * rotated_position[1] - transformed_angular[1] * rotated_position[0],
310    ];
311
312    // Add the cross product to the linear velocity
313    transformed_linear[0] = transformed_linear[0] + cross_product[0];
314    transformed_linear[1] = transformed_linear[1] + cross_product[1];
315    transformed_linear[2] = transformed_linear[2] + cross_product[2];
316
317    VelocityTransform {
318        linear: transformed_linear,
319        angular: transformed_angular,
320    }
321}
322
323#[cfg(test)]
324mod tests {
325    use super::*;
326
327    #[test]
328    fn test_velocity_transform_default() {
329        let vel: VelocityTransform<f32> = VelocityTransform::default();
330        assert_eq!(vel.linear, [0.0, 0.0, 0.0]);
331        assert_eq!(vel.angular, [0.0, 0.0, 0.0]);
332    }
333
334    #[test]
335    fn test_velocity_transform_zero() {
336        let vel = VelocityTransform::<f64>::zero();
337        assert_eq!(vel.linear, [0.0, 0.0, 0.0]);
338        assert_eq!(vel.angular, [0.0, 0.0, 0.0]);
339
340        // Test generic zero() with other types
341        let vel_f32 = VelocityTransform::<f32>::zero();
342        assert_eq!(vel_f32.linear, [0.0, 0.0, 0.0]);
343        assert_eq!(vel_f32.angular, [0.0, 0.0, 0.0]);
344    }
345
346    #[test]
347    fn test_velocity_with_units() {
348        let vel = VelocityTransform::<f32> {
349            linear: [1.0, 2.0, 3.0],
350            angular: [0.1, 0.2, 0.3],
351        };
352
353        let linear_vel = vel.linear_velocity();
354        let angular_vel = vel.angular_velocity();
355
356        // Check that units are correctly applied
357        assert_eq!(linear_vel[0].get::<meter_per_second>(), 1.0);
358        assert_eq!(linear_vel[1].get::<meter_per_second>(), 2.0);
359        assert_eq!(linear_vel[2].get::<meter_per_second>(), 3.0);
360
361        assert_eq!(angular_vel[0].get::<radian_per_second>(), 0.1);
362        assert_eq!(angular_vel[1].get::<radian_per_second>(), 0.2);
363        assert_eq!(angular_vel[2].get::<radian_per_second>(), 0.3);
364    }
365
366    #[test]
367    fn test_transform_velocity() {
368        // Create a velocity in frame A
369        let vel_a = VelocityTransform {
370            linear: [1.0f32, 0.0, 0.0], // Moving along x-axis at 1 m/s
371            angular: [0.0, 0.0, 1.0],   // Rotating around z-axis at 1 rad/s
372        };
373
374        // Create a transform from frame A to frame B
375        // 90-degree rotation around z-axis (cos(π/2)=0, sin(π/2)=1)
376        let transform_a_to_b = crate::Transform3D::from_matrix([
377            [0.0, -1.0, 0.0, 2.0], // 90-degree rotation with translation
378            [1.0, 0.0, 0.0, 3.0],
379            [0.0, 0.0, 1.0, 0.0],
380            [0.0, 0.0, 0.0, 1.0],
381        ]);
382
383        // The point's position in frame A
384        let position_a = [0.0f32, 0.0, 0.0]; // Position at origin
385
386        // Transform the velocity from frame A to frame B
387        let vel_b = transform_velocity(&vel_a, &transform_a_to_b, &position_a);
388
389        // After 90-degree rotation:
390        // - Linear velocity along x-axis (1,0,0) becomes (0,1,0)
391        // - Angular velocity around z-axis stays (0,0,1)
392        let epsilon = 1e-5;
393        assert!(
394            (vel_b.linear[0] - 0.0).abs() < epsilon,
395            "X velocity should be 0 after rotation"
396        );
397        assert!(
398            (vel_b.linear[1] - 1.0).abs() < epsilon,
399            "Y velocity should be 1 after rotation"
400        );
401        assert!(
402            (vel_b.linear[2] - 0.0).abs() < epsilon,
403            "Z velocity should remain 0"
404        );
405
406        assert!(
407            (vel_b.angular[0] - 0.0).abs() < epsilon,
408            "X angular velocity should be 0"
409        );
410        assert!(
411            (vel_b.angular[1] - 0.0).abs() < epsilon,
412            "Y angular velocity should be 0"
413        );
414        assert!(
415            (vel_b.angular[2] - 1.0).abs() < epsilon,
416            "Z angular velocity should remain 1"
417        );
418    }
419
420    #[test]
421    fn test_transform_velocity_with_offset_point() {
422        // Create a velocity in frame A
423        let vel_a = VelocityTransform {
424            linear: [0.0f32, 0.0, 0.0], // No linear velocity
425            angular: [0.0, 0.0, 1.0],   // Rotating around z-axis at 1 rad/s
426        };
427
428        // Create a transform from frame A to frame B (identity rotation)
429        let transform_a_to_b = crate::Transform3D::from_matrix([
430            [1.0, 0.0, 0.0, 0.0], // Identity rotation
431            [0.0, 1.0, 0.0, 0.0],
432            [0.0, 0.0, 1.0, 0.0],
433            [0.0, 0.0, 0.0, 1.0],
434        ]);
435
436        // The point's position in frame A - 1 meter along x-axis
437        let position_a = [1.0f32, 0.0, 0.0];
438
439        // Transform the velocity from frame A to frame B
440        let vel_b = transform_velocity(&vel_a, &transform_a_to_b, &position_a);
441
442        // The point is offset 1m in x direction, with angular velocity 1 rad/s around z
443        // This should create a linear velocity in the y direction of 1 m/s
444        // v = ω × r = (0,0,1) × (1,0,0) = (0,1,0)
445        let epsilon = 1e-5;
446        assert!(
447            (vel_b.linear[0] - 0.0).abs() < epsilon,
448            "X velocity should be 0"
449        );
450        assert!(
451            (vel_b.linear[1] - 1.0).abs() < epsilon,
452            "Y velocity should be 1 due to cross product"
453        );
454        assert!(
455            (vel_b.linear[2] - 0.0).abs() < epsilon,
456            "Z velocity should be 0"
457        );
458
459        // Angular velocity should remain unchanged (no rotation in transform)
460        assert!(
461            (vel_b.angular[0] - 0.0).abs() < epsilon,
462            "X angular velocity should be 0"
463        );
464        assert!(
465            (vel_b.angular[1] - 0.0).abs() < epsilon,
466            "Y angular velocity should be 0"
467        );
468        assert!(
469            (vel_b.angular[2] - 1.0).abs() < epsilon,
470            "Z angular velocity should remain 1"
471        );
472    }
473}