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#[derive(Debug, Clone, Encode, Decode, Serialize, Deserialize)]
41pub struct VelocityTransform<T: Copy + Debug + 'static> {
42 pub linear: [T; 3],
44 pub angular: [T; 3],
46}
47
48impl<T: Copy + Debug + Default + num_traits::Zero + 'static> VelocityTransform<T> {
49 pub fn zero() -> Self {
51 Self {
52 linear: [T::zero(); 3],
53 angular: [T::zero(); 3],
54 }
55 }
56}
57
58impl<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 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 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 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 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
128impl VelocityTransform<f64> {
130 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 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 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 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
178impl<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
201impl<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
224impl<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
239pub 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 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 let mut transformed_angular = [T::default(); 3];
278
279 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 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 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 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 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 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 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 let vel_a = VelocityTransform {
370 linear: [1.0f32, 0.0, 0.0], angular: [0.0, 0.0, 1.0], };
373
374 let transform_a_to_b = crate::Transform3D::from_matrix([
377 [0.0, -1.0, 0.0, 2.0], [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 let position_a = [0.0f32, 0.0, 0.0]; let vel_b = transform_velocity(&vel_a, &transform_a_to_b, &position_a);
388
389 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 let vel_a = VelocityTransform {
424 linear: [0.0f32, 0.0, 0.0], angular: [0.0, 0.0, 1.0], };
427
428 let transform_a_to_b = crate::Transform3D::from_matrix([
430 [1.0, 0.0, 0.0, 0.0], [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 let position_a = [1.0f32, 0.0, 0.0];
438
439 let vel_b = transform_velocity(&vel_a, &transform_a_to_b, &position_a);
441
442 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 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}