1use threecrate_core::{PointCloud, Result, Point3f, Error, Isometry3};
10use nalgebra::{Matrix3, Vector3, UnitQuaternion, Translation3};
11use std::collections::HashMap;
12
13#[derive(Debug, Clone)]
15pub struct NdtConfig {
16 pub resolution: f32,
18 pub step_size: f32,
20 pub max_iterations: usize,
22 pub epsilon: f32,
24 pub min_points_per_voxel: usize,
26}
27
28impl Default for NdtConfig {
29 fn default() -> Self {
30 Self {
31 resolution: 1.0,
32 step_size: 0.1,
33 max_iterations: 35,
34 epsilon: 1e-4,
35 min_points_per_voxel: 5,
36 }
37 }
38}
39
40#[derive(Debug, Clone)]
42pub struct NdtResult {
43 pub transformation: Isometry3<f32>,
45 pub score: f32,
47 pub iterations: usize,
49 pub converged: bool,
51}
52
53#[derive(Debug, Clone)]
55struct VoxelDistribution {
56 mean: Vector3<f32>,
57 inv_cov: Matrix3<f32>,
58}
59
60fn voxel_key(p: &Point3f, resolution: f32) -> (i32, i32, i32) {
62 (
63 (p.x / resolution).floor() as i32,
64 (p.y / resolution).floor() as i32,
65 (p.z / resolution).floor() as i32,
66 )
67}
68
69fn build_voxel_grid(
71 target: &PointCloud<Point3f>,
72 resolution: f32,
73 min_points: usize,
74) -> HashMap<(i32, i32, i32), VoxelDistribution> {
75 let mut cells: HashMap<(i32, i32, i32), Vec<Vector3<f32>>> = HashMap::new();
77 for p in &target.points {
78 let key = voxel_key(p, resolution);
79 cells.entry(key).or_default().push(Vector3::new(p.x, p.y, p.z));
80 }
81
82 let mut grid = HashMap::new();
83 for (key, pts) in cells {
84 if pts.len() < min_points {
85 continue;
86 }
87 let n = pts.len() as f32;
88
89 let mean = pts.iter().fold(Vector3::zeros(), |acc, p| acc + p) / n;
91
92 let mut cov = Matrix3::zeros();
94 for p in &pts {
95 let d = p - mean;
96 cov += d * d.transpose();
97 }
98 cov /= n;
99
100 cov += Matrix3::identity() * 1e-4;
102
103 if let Some(inv_cov) = cov.try_inverse() {
104 grid.insert(key, VoxelDistribution { mean, inv_cov });
105 }
106 }
107 grid
108}
109
110fn compute_score_and_derivatives(
115 source: &[Point3f],
116 grid: &HashMap<(i32, i32, i32), VoxelDistribution>,
117 transform: &Isometry3<f32>,
118 resolution: f32,
119) -> (f32, nalgebra::Vector6<f32>, nalgebra::Matrix6<f32>) {
120 let rot = transform.rotation.to_rotation_matrix();
121 let rot_mat = rot.matrix();
122
123 let mut score = 0.0_f32;
124 let mut gradient = nalgebra::Vector6::<f32>::zeros();
125 let mut hessian = nalgebra::Matrix6::<f32>::zeros();
126
127 for src_pt in source {
128 let p = transform * src_pt;
130 let key = voxel_key(&p, resolution);
131
132 let dist = match grid.get(&key) {
133 Some(d) => d,
134 None => continue,
135 };
136
137 let diff = Vector3::new(p.x, p.y, p.z) - dist.mean;
138 let cov_diff = dist.inv_cov * diff;
139 let exponent = -0.5 * diff.dot(&cov_diff);
140 let e = exponent.exp();
141
142 score += e;
143
144 let src_vec = Vector3::new(src_pt.x, src_pt.y, src_pt.z);
148 let dp_dtrans = Matrix3::identity();
149 let rs = rot_mat * src_vec;
152 let dp_drx = Vector3::new(0.0, -rs[2], rs[1]); let dp_dry = Vector3::new(rs[2], 0.0, -rs[0]); let dp_drz = Vector3::new(-rs[1], rs[0], 0.0); let mut jac = nalgebra::Matrix3x6::<f32>::zeros();
158 jac.fixed_columns_mut::<3>(0).copy_from(&dp_dtrans);
159 jac.column_mut(3).copy_from(&dp_drx);
160 jac.column_mut(4).copy_from(&dp_dry);
161 jac.column_mut(5).copy_from(&dp_drz);
162
163 let g_vec = jac.transpose() * cov_diff;
165 gradient += e * g_vec;
166
167 let h_contrib = jac.transpose() * dist.inv_cov * jac;
169 hessian += e * h_contrib;
170 }
171
172 (score, gradient, hessian)
173}
174
175pub fn ndt_registration(
186 source: &PointCloud<Point3f>,
187 target: &PointCloud<Point3f>,
188 initial_transform: Isometry3<f32>,
189 config: &NdtConfig,
190) -> Result<NdtResult> {
191 if source.points.is_empty() {
192 return Err(Error::Algorithm("Source point cloud is empty".into()));
193 }
194 if target.points.len() < config.min_points_per_voxel {
195 return Err(Error::Algorithm(
196 "Target point cloud has too few points for NDT voxel grid".into(),
197 ));
198 }
199
200 let grid = build_voxel_grid(target, config.resolution, config.min_points_per_voxel);
201 if grid.is_empty() {
202 return Err(Error::Algorithm(
203 "NDT voxel grid is empty — try a larger resolution or lower min_points_per_voxel".into(),
204 ));
205 }
206
207 let mut transform = initial_transform;
208 let mut converged = false;
209 let mut iterations = 0;
210 let mut score = 0.0_f32;
211
212 for iter in 0..config.max_iterations {
213 iterations = iter + 1;
214
215 let (s, grad, hess) = compute_score_and_derivatives(
216 &source.points,
217 &grid,
218 &transform,
219 config.resolution,
220 );
221 score = s;
222
223 let reg = nalgebra::Matrix6::<f32>::identity() * 1e-6;
225 let hess_reg = hess + reg;
226
227 let delta = match hess_reg.lu().solve(&(-grad)) {
229 Some(d) => d,
230 None => break,
231 };
232
233 let step_norm = delta.norm();
235 let delta = if step_norm > config.step_size {
236 delta * (config.step_size / step_norm)
237 } else {
238 delta
239 };
240
241 if delta.norm() < config.epsilon {
243 converged = true;
244 break;
245 }
246
247 let dt = Translation3::new(delta[0], delta[1], delta[2]);
249 let dr = UnitQuaternion::from_euler_angles(delta[3], delta[4], delta[5]);
250 let delta_iso = Isometry3::from_parts(dt, dr);
251 transform = delta_iso * transform;
252 }
253
254 Ok(NdtResult {
255 transformation: transform,
256 score,
257 iterations,
258 converged,
259 })
260}
261
262pub fn ndt_registration_default(
264 source: &PointCloud<Point3f>,
265 target: &PointCloud<Point3f>,
266 initial_transform: Isometry3<f32>,
267) -> Result<NdtResult> {
268 ndt_registration(source, target, initial_transform, &NdtConfig::default())
269}
270
271#[cfg(test)]
272mod tests {
273 use super::*;
274 use threecrate_core::PointCloud;
275 use nalgebra::{Translation3, UnitQuaternion};
276
277 fn make_grid_cloud(nx: usize, ny: usize, nz: usize, scale: f32) -> PointCloud<Point3f> {
278 let mut points = Vec::new();
279 for ix in 0..nx {
280 for iy in 0..ny {
281 for iz in 0..nz {
282 points.push(Point3f::new(
283 ix as f32 * scale,
284 iy as f32 * scale,
285 iz as f32 * scale,
286 ));
287 }
288 }
289 }
290 PointCloud { points }
291 }
292
293 fn apply_transform(cloud: &PointCloud<Point3f>, iso: &Isometry3<f32>) -> PointCloud<Point3f> {
294 PointCloud {
295 points: cloud.points.iter().map(|p| iso * p).collect(),
296 }
297 }
298
299 #[test]
300 fn test_ndt_identity() {
301 let target = make_grid_cloud(5, 5, 5, 1.0);
302 let config = NdtConfig {
303 resolution: 2.0,
304 min_points_per_voxel: 2,
305 ..Default::default()
306 };
307 let result = ndt_registration(&target, &target, Isometry3::identity(), &config).unwrap();
308 assert!(result.score > 0.0);
309 let t = result.transformation.translation.vector;
311 assert!(t.norm() < 1.0, "Translation should be small: {}", t.norm());
312 }
313
314 #[test]
315 fn test_ndt_small_translation() {
316 let target = make_grid_cloud(6, 6, 6, 1.0);
317 let translation = Isometry3::from_parts(
318 Translation3::new(0.3, 0.2, 0.1),
319 UnitQuaternion::identity(),
320 );
321 let source = apply_transform(&target, &translation);
322
323 let config = NdtConfig {
324 resolution: 2.0,
325 step_size: 0.5,
326 max_iterations: 50,
327 epsilon: 1e-5,
328 min_points_per_voxel: 3,
329 };
330 let result = ndt_registration(&source, &target, Isometry3::identity(), &config).unwrap();
331 assert!(result.score > 0.0);
332 assert!(result.iterations <= 50);
333 }
334
335 #[test]
336 fn test_ndt_empty_source() {
337 let empty: PointCloud<Point3f> = PointCloud { points: vec![] };
338 let target = make_grid_cloud(4, 4, 4, 1.0);
339 let config = NdtConfig::default();
340 assert!(ndt_registration(&empty, &target, Isometry3::identity(), &config).is_err());
341 }
342
343 #[test]
344 fn test_ndt_sparse_target() {
345 let source = make_grid_cloud(4, 4, 4, 1.0);
346 let sparse: PointCloud<Point3f> = PointCloud {
348 points: vec![Point3f::new(0.0, 0.0, 0.0), Point3f::new(1.0, 1.0, 1.0)],
349 };
350 let config = NdtConfig::default();
351 assert!(ndt_registration(&source, &sparse, Isometry3::identity(), &config).is_err());
352 }
353
354 #[test]
355 fn test_ndt_config_default() {
356 let cfg = NdtConfig::default();
357 assert_eq!(cfg.resolution, 1.0);
358 assert_eq!(cfg.max_iterations, 35);
359 assert!(cfg.epsilon > 0.0);
360 assert!(cfg.step_size > 0.0);
361 assert!(cfg.min_points_per_voxel >= 1);
362 }
363
364 #[test]
365 fn test_ndt_result_fields() {
366 let target = make_grid_cloud(5, 5, 5, 1.0);
367 let config = NdtConfig {
368 resolution: 2.0,
369 min_points_per_voxel: 2,
370 ..Default::default()
371 };
372 let result = ndt_registration(&target, &target, Isometry3::identity(), &config).unwrap();
373 assert!(result.iterations > 0);
375 assert!(result.score >= 0.0);
376 let qnorm = result.transformation.rotation.norm();
378 assert!((qnorm - 1.0).abs() < 1e-5);
379 }
380
381 #[test]
382 fn test_ndt_default_wrapper() {
383 let target = make_grid_cloud(5, 5, 5, 1.0);
384 let config_res_cloud = NdtConfig {
386 resolution: 2.0,
387 min_points_per_voxel: 2,
388 ..Default::default()
389 };
390 let r1 = ndt_registration(&target, &target, Isometry3::identity(), &config_res_cloud);
391 assert!(r1.is_ok());
392 }
393}