apex_solver/factors/between_factor.rs
1use super::Factor;
2use apex_manifolds::LieGroup;
3use nalgebra::{DMatrix, DVector};
4
5/// Generic between factor for Lie group pose constraints.
6///
7/// Represents a relative pose measurement between two poses of any Lie group manifold type.
8/// This is a generic implementation that works with SE(2), SE(3), SO(2), SO(3), and Rⁿ
9/// using static dispatch for zero runtime overhead.
10///
11/// # Type Parameter
12///
13/// * `T` - The Lie group manifold type (e.g., SE2, SE3, SO2, SO3, Rn)
14///
15/// # Mathematical Formulation
16///
17/// Given two poses `T_i` and `T_j` in a Lie group, and a measurement `T_ij`, the residual is:
18///
19/// ```text
20/// r = log(T_ij⁻¹ ⊕ T_i⁻¹ ⊕ T_j)
21/// ```
22///
23/// where:
24/// - `⊕` is the Lie group composition operation
25/// - `log` is the logarithm map (converts from manifold to tangent space)
26/// - The residual dimensionality depends on the manifold's degrees of freedom (DOF)
27///
28/// # Residual Dimensions by Manifold Type
29///
30/// - **SE(3)**: 6D residual `[v_x, v_y, v_z, ω_x, ω_y, ω_z]` - translation + rotation
31/// - **SE(2)**: 3D residual `[dx, dy, dθ]` - 2D translation + rotation
32/// - **SO(3)**: 3D residual `[ω_x, ω_y, ω_z]` - 3D rotation only
33/// - **SO(2)**: 1D residual `[dθ]` - 2D rotation only
34/// - **Rⁿ**: nD residual - Euclidean space
35///
36/// # Jacobian Computation
37///
38/// The Jacobian is computed analytically using the chain rule and Lie group derivatives:
39///
40/// ```text
41/// J = ∂r/∂[T_i, T_j]
42/// ```
43///
44/// The Jacobian dimensions are `DOF × (2 × DOF)` where DOF is the manifold's degrees of freedom:
45/// - **SE(3)**: 6×12 matrix
46/// - **SE(2)**: 3×6 matrix
47/// - **SO(3)**: 3×6 matrix
48/// - **SO(2)**: 1×2 matrix
49///
50/// # Use Cases
51///
52/// - **3D SLAM**: Visual odometry, loop closure constraints (SE3)
53/// - **2D SLAM**: Robot navigation, mapping (SE2)
54/// - **Pose graph optimization**: Relative pose constraints (SE2, SE3)
55/// - **Orientation tracking**: IMU fusion, attitude estimation (SO2, SO3)
56/// - **General manifold optimization**: Custom manifolds (Rⁿ)
57///
58/// # Examples
59///
60/// ## SE(3) - 3D Pose Graph
61///
62/// ```
63/// use apex_solver::factors::{Factor, BetweenFactor};
64/// use apex_solver::manifold::se3::SE3;
65/// use nalgebra::{Vector3, Quaternion, DVector};
66///
67/// // Measurement: relative 3D transformation between two poses
68/// let relative_pose = SE3::from_translation_quaternion(
69/// Vector3::new(1.0, 0.0, 0.0), // 1m forward
70/// Quaternion::new(1.0, 0.0, 0.0, 0.0) // No rotation
71/// );
72/// let between = BetweenFactor::new(relative_pose);
73///
74/// // Current pose estimates (in [tx, ty, tz, qw, qx, qy, qz] format)
75/// let pose_i = DVector::from_vec(vec![0.0, 0.0, 0.0, 1.0, 0.0, 0.0, 0.0]);
76/// let pose_j = DVector::from_vec(vec![0.95, 0.05, 0.0, 1.0, 0.0, 0.0, 0.0]);
77///
78/// // Compute residual (dimension 6) and Jacobian (6×12)
79/// let (residual, jacobian) = between.linearize(&[pose_i, pose_j], true);
80/// ```
81///
82/// ## SE(2) - 2D Pose Graph
83///
84/// ```
85/// use apex_solver::factors::{Factor, BetweenFactor};
86/// use apex_solver::manifold::se2::SE2;
87/// use nalgebra::DVector;
88///
89/// // Measurement: robot moved 1m forward and rotated 0.1 rad
90/// let relative_pose = SE2::from_xy_angle(1.0, 0.0, 0.1);
91/// let between = BetweenFactor::new(relative_pose);
92///
93/// // Current pose estimates (in [x, y, theta] format)
94/// let pose_i = DVector::from_vec(vec![0.0, 0.0, 0.0]);
95/// let pose_j = DVector::from_vec(vec![0.95, 0.05, 0.12]);
96///
97/// // Compute residual (dimension 3) and Jacobian (3×6)
98/// let (residual, jacobian) = between.linearize(&[pose_i, pose_j], true);
99/// ```
100///
101/// # Performance
102///
103/// This generic implementation uses static dispatch (monomorphization), meaning:
104/// - **Zero runtime overhead** compared to type-specific implementations
105/// - Compiler optimizes each instantiation (`BetweenFactor<SE3>`, `BetweenFactor<SE2>`, etc.)
106/// - All type checking happens at compile time
107/// - No dynamic dispatch or virtual function calls
108#[derive(Clone, PartialEq)]
109pub struct BetweenFactor<T>
110where
111 T: LieGroup + Clone + Send + Sync,
112 T::TangentVector: Into<DVector<f64>>,
113{
114 /// The measured relative pose transformation between the two connected poses
115 pub relative_pose: T,
116}
117
118impl<T> BetweenFactor<T>
119where
120 T: LieGroup + Clone + Send + Sync,
121 T::TangentVector: Into<DVector<f64>>,
122{
123 /// Create a new between factor from a relative pose measurement.
124 ///
125 /// This is a generic constructor that works with any Lie group manifold type.
126 /// The type parameter `T` is typically inferred from the `relative_pose` argument.
127 ///
128 /// # Arguments
129 ///
130 /// * `relative_pose` - The measured relative transformation between two poses
131 ///
132 /// # Returns
133 ///
134 /// A new `BetweenFactor<T>` instance
135 ///
136 /// # Examples
137 ///
138 /// ## SE(3) Between Factor
139 ///
140 /// ```
141 /// use apex_solver::factors::BetweenFactor;
142 /// use apex_solver::manifold::se3::SE3;
143 ///
144 /// // Create relative pose: move 2m in x, rotate 90° around z-axis
145 /// let relative = SE3::from_translation_euler(
146 /// 2.0, 0.0, 0.0, // translation (x, y, z)
147 /// 0.0, 0.0, std::f64::consts::FRAC_PI_2 // rotation (roll, pitch, yaw)
148 /// );
149 ///
150 /// // Type is inferred as BetweenFactor<SE3>
151 /// let factor = BetweenFactor::new(relative);
152 /// ```
153 ///
154 /// ## SE(2) Between Factor
155 ///
156 /// ```
157 /// use apex_solver::factors::BetweenFactor;
158 /// use apex_solver::manifold::se2::SE2;
159 ///
160 /// // Create relative 2D pose
161 /// let relative = SE2::from_xy_angle(1.0, 0.5, 0.1);
162 ///
163 /// // Type is inferred as BetweenFactor<SE2>
164 /// let factor = BetweenFactor::new(relative);
165 /// ```
166 pub fn new(relative_pose: T) -> Self {
167 Self { relative_pose }
168 }
169}
170
171impl<T> Factor for BetweenFactor<T>
172where
173 T: LieGroup + Clone + Send + Sync + From<DVector<f64>>,
174 T::TangentVector: Into<DVector<f64>>,
175{
176 /// Compute residual and Jacobian for a generic between factor.
177 ///
178 /// This method works with any Lie group manifold type, automatically adapting to
179 /// the manifold's degrees of freedom. The residual and Jacobian dimensions are
180 /// determined at runtime based on the manifold type.
181 ///
182 /// # Arguments
183 ///
184 /// * `params` - Two poses as `DVector<f64>` in the manifold's representation format:
185 /// - **SE(3)**: `[tx, ty, tz, qw, qx, qy, qz]` (7 parameters, 6 DOF)
186 /// - **SE(2)**: `[x, y, theta]` (3 parameters, 3 DOF)
187 /// - **SO(3)**: `[qw, qx, qy, qz]` (4 parameters, 3 DOF)
188 /// - **SO(2)**: `[angle]` (1 parameter, 1 DOF)
189 /// * `compute_jacobian` - Whether to compute the analytical Jacobian matrix
190 ///
191 /// # Returns
192 ///
193 /// A tuple `(residual, jacobian)` where:
194 /// - **Residual**: `DVector<f64>` with dimension = manifold DOF
195 /// - SE(3): 6×1 vector `[v_x, v_y, v_z, ω_x, ω_y, ω_z]`
196 /// - SE(2): 3×1 vector `[dx, dy, dθ]`
197 /// - SO(3): 3×1 vector `[ω_x, ω_y, ω_z]`
198 /// - SO(2): 1×1 vector `[dθ]`
199 /// - **Jacobian**: `Option<DMatrix<f64>>` with dimension = (DOF, 2×DOF)
200 /// - SE(3): 6×12 matrix `[∂r/∂pose_i | ∂r/∂pose_j]`
201 /// - SE(2): 3×6 matrix `[∂r/∂pose_i | ∂r/∂pose_j]`
202 /// - SO(3): 3×6 matrix `[∂r/∂pose_i | ∂r/∂pose_j]`
203 /// - SO(2): 1×2 matrix `[∂r/∂pose_i | ∂r/∂pose_j]`
204 ///
205 /// # Algorithm
206 ///
207 /// Uses analytical Jacobians computed via chain rule through three steps:
208 /// 1. **Between**: `T_j.between(T_i) = T_j⁻¹ ⊕ T_i` with Jacobians ∂/∂T_j and ∂/∂T_i
209 /// 2. **Composition**: `(T_j⁻¹ ⊕ T_i) ⊕ T_ij` with Jacobian ∂/∂(T_j⁻¹ ⊕ T_i)
210 /// 3. **Logarithm**: `log(...)` with Jacobian ∂log/∂(...)
211 ///
212 /// The final Jacobian is computed using the chain rule:
213 /// ```text
214 /// J = ∂log/∂diff · ∂diff/∂between · ∂between/∂poses
215 /// ```
216 ///
217 /// This approach reduces the number of matrix operations compared to computing
218 /// inverse and compose separately, resulting in both clearer code and better performance.
219 ///
220 /// # Performance
221 ///
222 /// - **Static dispatch**: All operations are monomorphized at compile time
223 /// - **Zero overhead**: Same performance as type-specific implementations
224 /// - **Parallel-safe**: Marked `Send + Sync` for use in parallel optimization
225 ///
226 /// # Examples
227 ///
228 /// ## SE(3) Linearization
229 ///
230 /// ```
231 /// use apex_solver::factors::{Factor, BetweenFactor};
232 /// use apex_solver::manifold::se3::SE3;
233 /// use nalgebra::DVector;
234 ///
235 /// let relative = SE3::identity();
236 /// let factor = BetweenFactor::new(relative);
237 ///
238 /// let pose_i = DVector::from_vec(vec![0.0, 0.0, 0.0, 1.0, 0.0, 0.0, 0.0]);
239 /// let pose_j = DVector::from_vec(vec![1.0, 0.0, 0.0, 1.0, 0.0, 0.0, 0.0]);
240 ///
241 /// let (residual, jacobian) = factor.linearize(&[pose_i, pose_j], true);
242 /// assert_eq!(residual.len(), 6); // 6 DOF
243 /// assert!(jacobian.is_some());
244 /// let jac = jacobian.unwrap();
245 /// assert_eq!(jac.nrows(), 6); // Residual dimension
246 /// assert_eq!(jac.ncols(), 12); // 2 × DOF
247 /// ```
248 ///
249 /// ## SE(2) Linearization
250 ///
251 /// ```
252 /// use apex_solver::factors::{Factor, BetweenFactor};
253 /// use apex_solver::manifold::se2::SE2;
254 /// use nalgebra::DVector;
255 ///
256 /// let relative = SE2::from_xy_angle(1.0, 0.0, 0.0);
257 /// let factor = BetweenFactor::new(relative);
258 ///
259 /// let pose_i = DVector::from_vec(vec![0.0, 0.0, 0.0]);
260 /// let pose_j = DVector::from_vec(vec![1.0, 0.0, 0.0]);
261 ///
262 /// let (residual, jacobian) = factor.linearize(&[pose_i, pose_j], true);
263 /// assert_eq!(residual.len(), 3); // 3 DOF
264 /// let jac = jacobian.unwrap();
265 /// assert_eq!(jac.nrows(), 3); // Residual dimension
266 /// assert_eq!(jac.ncols(), 6); // 2 × DOF
267 /// ```
268 fn linearize(
269 &self,
270 params: &[DVector<f64>],
271 compute_jacobian: bool,
272 ) -> (DVector<f64>, Option<DMatrix<f64>>) {
273 let se3_origin_k0 = T::from(params[0].clone());
274 let se3_origin_k1 = T::from(params[1].clone());
275 let se3_k0_k1_measured = &self.relative_pose;
276
277 // Step 1: se3_origin_k1.between(se3_origin_k0) = k1⁻¹ * k0
278 let mut j_k1_k0_wrt_k1 = T::zero_jacobian();
279 let mut j_k1_k0_wrt_k0 = T::zero_jacobian();
280 let se3_k1_k0 = se3_origin_k1.between(
281 &se3_origin_k0,
282 Some(&mut j_k1_k0_wrt_k1),
283 Some(&mut j_k1_k0_wrt_k0),
284 );
285
286 // Step 2: se3_k1_k0 * se3_k0_k1_measured
287 let mut j_diff_wrt_k1_k0 = T::zero_jacobian();
288 let se3_diff = se3_k1_k0.compose(se3_k0_k1_measured, Some(&mut j_diff_wrt_k1_k0), None);
289
290 // Step 3: se3_diff.log()
291 let mut j_log_wrt_diff = T::zero_jacobian();
292 let residual = se3_diff.log(Some(&mut j_log_wrt_diff));
293
294 let jacobian = if compute_jacobian {
295 // Calculate dimensions dynamically based on manifold DOF
296 let dof = se3_origin_k0.tangent_dim();
297
298 // Chain rule: d(residual)/d(k0) and d(residual)/d(k1)
299 let j_diff_wrt_k0 = j_diff_wrt_k1_k0.clone() * j_k1_k0_wrt_k0;
300 let j_diff_wrt_k1 = j_diff_wrt_k1_k0 * j_k1_k0_wrt_k1;
301
302 let jacobian_wrt_k0 = j_log_wrt_diff.clone() * j_diff_wrt_k0;
303 let jacobian_wrt_k1 = j_log_wrt_diff * j_diff_wrt_k1;
304
305 // Assemble full Jacobian: [∂r/∂pose_i | ∂r/∂pose_j]
306 let mut jacobian = DMatrix::<f64>::zeros(dof, 2 * dof);
307
308 // Copy element-wise from JacobianMatrix to DMatrix
309 // This works for all Matrix types (fixed-size and dynamic)
310 for i in 0..dof {
311 for j in 0..dof {
312 jacobian[(i, j)] = jacobian_wrt_k0[(i, j)];
313 jacobian[(i, j + dof)] = jacobian_wrt_k1[(i, j)];
314 }
315 }
316
317 Some(jacobian)
318 } else {
319 None
320 };
321 (residual.into(), jacobian)
322 }
323
324 fn get_dimension(&self) -> usize {
325 self.relative_pose.tangent_dim()
326 }
327}
328
329#[cfg(test)]
330mod tests {
331 use super::*;
332 use apex_manifolds::se2::{SE2, SE2Tangent};
333 use apex_manifolds::se3::SE3;
334 use apex_manifolds::so2::SO2;
335 use apex_manifolds::so3::SO3;
336 use nalgebra::{DVector, Quaternion, Vector3};
337
338 const TOLERANCE: f64 = 1e-9;
339 const FD_EPSILON: f64 = 1e-6;
340 type TestResult = Result<(), Box<dyn std::error::Error>>;
341
342 #[test]
343 fn test_between_factor_se2_identity() {
344 // Test that identity measurement yields zero residual
345 let relative = SE2::identity();
346 let factor = BetweenFactor::new(relative);
347
348 let pose_i = DVector::from_vec(vec![0.0, 0.0, 0.0]);
349 let pose_j = DVector::from_vec(vec![0.0, 0.0, 0.0]);
350
351 let (residual, _) = factor.linearize(&[pose_i, pose_j], false);
352
353 assert_eq!(residual.len(), 3);
354 assert!(
355 residual.norm() < TOLERANCE,
356 "Residual norm: {}",
357 residual.norm()
358 );
359 }
360
361 #[test]
362 fn test_between_factor_se3_identity() {
363 // Test that identity measurement yields zero residual
364 let relative = SE3::identity();
365 let factor = BetweenFactor::new(relative);
366
367 let pose_i = DVector::from_vec(vec![0.0, 0.0, 0.0, 1.0, 0.0, 0.0, 0.0]);
368 let pose_j = DVector::from_vec(vec![0.0, 0.0, 0.0, 1.0, 0.0, 0.0, 0.0]);
369
370 let (residual, _) = factor.linearize(&[pose_i, pose_j], false);
371
372 assert_eq!(residual.len(), 6);
373 assert!(
374 residual.norm() < TOLERANCE,
375 "Residual norm: {}",
376 residual.norm()
377 );
378 }
379
380 #[test]
381 fn test_between_factor_se2_jacobian_numerical() -> TestResult {
382 // Verify Jacobian using finite differences with manifold perturbations
383 let relative = SE2::from_xy_angle(1.0, 0.0, 0.1);
384 let factor = BetweenFactor::new(relative);
385
386 let pose_i = DVector::from_vec(vec![0.0, 0.0, 0.0]);
387 let pose_j = DVector::from_vec(vec![0.95, 0.05, 0.12]);
388
389 let (residual, jacobian_opt) = factor.linearize(&[pose_i.clone(), pose_j.clone()], true);
390 let jacobian = jacobian_opt.ok_or("Jacobian should be Some when compute_jacobians=true")?;
391
392 assert_eq!(jacobian.nrows(), 3);
393 assert_eq!(jacobian.ncols(), 6);
394
395 // Finite difference validation using manifold plus operation
396 let mut jacobian_fd = DMatrix::<f64>::zeros(3, 6);
397 let se2_i = SE2::from(pose_i.clone());
398 let se2_j = SE2::from(pose_j.clone());
399
400 // Perturb pose_i in tangent space
401 for i in 0..3 {
402 let delta = match i {
403 0 => SE2Tangent::new(FD_EPSILON, 0.0, 0.0),
404 1 => SE2Tangent::new(0.0, FD_EPSILON, 0.0),
405 2 => SE2Tangent::new(0.0, 0.0, FD_EPSILON),
406 _ => unreachable!(),
407 };
408 let se2_i_perturbed = se2_i.plus(&delta, None, None);
409 let pose_i_perturbed = DVector::<f64>::from(se2_i_perturbed);
410 let (residual_perturbed, _) =
411 factor.linearize(&[pose_i_perturbed, pose_j.clone()], false);
412
413 for j in 0..3 {
414 jacobian_fd[(j, i)] = (residual_perturbed[j] - residual[j]) / FD_EPSILON;
415 }
416 }
417
418 // Perturb pose_j in tangent space
419 for i in 0..3 {
420 let delta = match i {
421 0 => SE2Tangent::new(FD_EPSILON, 0.0, 0.0),
422 1 => SE2Tangent::new(0.0, FD_EPSILON, 0.0),
423 2 => SE2Tangent::new(0.0, 0.0, FD_EPSILON),
424 _ => unreachable!(),
425 };
426 let se2_j_perturbed = se2_j.plus(&delta, None, None);
427 let pose_j_perturbed = DVector::<f64>::from(se2_j_perturbed);
428 let (residual_perturbed, _) =
429 factor.linearize(&[pose_i.clone(), pose_j_perturbed], false);
430
431 for j in 0..3 {
432 jacobian_fd[(j, i + 3)] = (residual_perturbed[j] - residual[j]) / FD_EPSILON;
433 }
434 }
435
436 let diff_norm = (jacobian - jacobian_fd).norm();
437 assert!(diff_norm < 1e-5, "Jacobian difference norm: {}", diff_norm);
438 Ok(())
439 }
440
441 #[test]
442 fn test_between_factor_se3_jacobian_numerical() -> TestResult {
443 // Verify Jacobian using finite differences for SE3
444 let relative = SE3::from_translation_quaternion(
445 Vector3::new(1.0, 0.0, 0.0),
446 Quaternion::new(1.0, 0.0, 0.0, 0.0),
447 );
448 let factor = BetweenFactor::new(relative);
449
450 let pose_i = DVector::from_vec(vec![0.0, 0.0, 0.0, 1.0, 0.0, 0.0, 0.0]);
451 let pose_j = DVector::from_vec(vec![0.95, 0.05, 0.0, 1.0, 0.0, 0.0, 0.0]);
452
453 let (residual, jacobian_opt) = factor.linearize(&[pose_i.clone(), pose_j.clone()], true);
454 let jacobian = jacobian_opt.ok_or("Jacobian should be Some when compute_jacobians=true")?;
455
456 assert_eq!(jacobian.nrows(), 6);
457 assert_eq!(jacobian.ncols(), 12);
458
459 // Finite difference validation (only check translation part for simplicity)
460 let mut jacobian_fd = DMatrix::<f64>::zeros(6, 12);
461
462 // Perturb pose_i translation
463 for i in 0..3 {
464 let mut pose_i_perturbed = pose_i.clone();
465 pose_i_perturbed[i] += FD_EPSILON;
466 let (residual_perturbed, _) =
467 factor.linearize(&[pose_i_perturbed, pose_j.clone()], false);
468
469 for j in 0..6 {
470 jacobian_fd[(j, i)] = (residual_perturbed[j] - residual[j]) / FD_EPSILON;
471 }
472 }
473
474 // Perturb pose_j translation
475 for i in 0..3 {
476 let mut pose_j_perturbed = pose_j.clone();
477 pose_j_perturbed[i] += FD_EPSILON;
478 let (residual_perturbed, _) =
479 factor.linearize(&[pose_i.clone(), pose_j_perturbed], false);
480
481 for j in 0..6 {
482 jacobian_fd[(j, i + 6)] = (residual_perturbed[j] - residual[j]) / FD_EPSILON;
483 }
484 }
485
486 // Check translation part only (more robust for FD)
487 let diff_norm_trans = (jacobian.columns(0, 3) - jacobian_fd.columns(0, 3)).norm();
488 assert!(
489 diff_norm_trans < 1e-5,
490 "Jacobian difference norm (translation): {}",
491 diff_norm_trans
492 );
493 Ok(())
494 }
495
496 #[test]
497 fn test_between_factor_dimension_se2() -> TestResult {
498 let relative = SE2::from_xy_angle(1.0, 0.5, 0.1);
499 let factor = BetweenFactor::new(relative);
500
501 let pose_i = DVector::from_vec(vec![0.0, 0.0, 0.0]);
502 let pose_j = DVector::from_vec(vec![1.0, 0.0, 0.0]);
503
504 let (residual, jacobian) = factor.linearize(&[pose_i, pose_j], true);
505
506 assert_eq!(residual.len(), 3);
507 assert_eq!(factor.get_dimension(), 3);
508
509 let jac = jacobian.ok_or("Jacobian should be Some when compute_jacobians=true")?;
510 assert_eq!(jac.nrows(), 3);
511 assert_eq!(jac.ncols(), 6);
512 Ok(())
513 }
514
515 #[test]
516 fn test_between_factor_dimension_se3() -> TestResult {
517 let relative = SE3::identity();
518 let factor = BetweenFactor::new(relative);
519
520 let pose_i = DVector::from_vec(vec![0.0, 0.0, 0.0, 1.0, 0.0, 0.0, 0.0]);
521 let pose_j = DVector::from_vec(vec![1.0, 0.0, 0.0, 1.0, 0.0, 0.0, 0.0]);
522
523 let (residual, jacobian) = factor.linearize(&[pose_i, pose_j], true);
524
525 assert_eq!(residual.len(), 6);
526 assert_eq!(factor.get_dimension(), 6);
527
528 let jac = jacobian.ok_or("Jacobian should be Some when compute_jacobians=true")?;
529 assert_eq!(jac.nrows(), 6);
530 assert_eq!(jac.ncols(), 12);
531 Ok(())
532 }
533
534 #[test]
535 fn test_between_factor_so2_so3() -> TestResult {
536 // Test SO2 (rotation-only in 2D)
537 let so2_relative = SO2::from_angle(0.1);
538 let so2_factor = BetweenFactor::new(so2_relative);
539
540 let so2_i = DVector::from_vec(vec![0.0]);
541 let so2_j = DVector::from_vec(vec![0.12]);
542
543 let (residual_so2, jacobian_so2) = so2_factor.linearize(&[so2_i, so2_j], true);
544 assert_eq!(residual_so2.len(), 1);
545 assert_eq!(so2_factor.get_dimension(), 1);
546
547 let jac_so2 = jacobian_so2.ok_or("Jacobian should be Some when compute_jacobians=true")?;
548 assert_eq!(jac_so2.nrows(), 1);
549 assert_eq!(jac_so2.ncols(), 2);
550
551 // Test SO3 (rotation-only in 3D)
552 let so3_relative = SO3::identity();
553 let so3_factor = BetweenFactor::new(so3_relative);
554
555 let so3_i = DVector::from_vec(vec![1.0, 0.0, 0.0, 0.0]);
556 let so3_j = DVector::from_vec(vec![1.0, 0.0, 0.0, 0.0]);
557
558 let (residual_so3, jacobian_so3) = so3_factor.linearize(&[so3_i, so3_j], true);
559 assert_eq!(residual_so3.len(), 3);
560 assert_eq!(so3_factor.get_dimension(), 3);
561
562 let jac_so3 = jacobian_so3.ok_or("Jacobian should be Some when compute_jacobians=true")?;
563 assert_eq!(jac_so3.nrows(), 3);
564 assert_eq!(jac_so3.ncols(), 6);
565 Ok(())
566 }
567
568 #[test]
569 fn test_between_factor_finiteness() -> TestResult {
570 // Test numerical stability with various inputs
571 let relative = SE2::from_xy_angle(100.0, -200.0, std::f64::consts::PI);
572 let factor = BetweenFactor::new(relative);
573
574 let pose_i = DVector::from_vec(vec![50.0, -100.0, 1.5]);
575 let pose_j = DVector::from_vec(vec![150.0, -300.0, -1.5]);
576
577 let (residual, jacobian) = factor.linearize(&[pose_i, pose_j], true);
578
579 assert!(residual.iter().all(|&x| x.is_finite()));
580 let jac = jacobian.ok_or("Jacobian should be Some when compute_jacobians=true")?;
581 assert!(jac.iter().all(|&x| x.is_finite()));
582 Ok(())
583 }
584
585 #[test]
586 fn test_between_factor_clone() {
587 let relative = SE3::identity();
588 let factor = BetweenFactor::new(relative);
589 let factor_clone = factor.clone();
590
591 let pose_i = DVector::from_vec(vec![0.0, 0.0, 0.0, 1.0, 0.0, 0.0, 0.0]);
592 let pose_j = DVector::from_vec(vec![1.0, 0.0, 0.0, 1.0, 0.0, 0.0, 0.0]);
593
594 let (residual1, _) = factor.linearize(&[pose_i.clone(), pose_j.clone()], false);
595 let (residual2, _) = factor_clone.linearize(&[pose_i, pose_j], false);
596
597 assert!((residual1 - residual2).norm() < TOLERANCE);
598 }
599}