A Fractional-Order Spatiotemporal Unified Energy Framework for Non-Repetitive LiDAR Point Cloud Registration
Abstract
1. Introduction
2. Preliminaries
2.1. Overview of the Point Cloud Registration Problem
2.2. Grünwald–Letnikov Fractional Derivative and Its Discretization
2.3. Fractional Laplacian and Graph Representation
3. Unified Spatiotemporal Fractional Energy Framework
3.1. Fractional Spatial Regularization Term
3.1.1. Residual Vector Field and Target Point Cloud Graph
3.1.2. From Continuous Fractional Dirichlet Energy to Graph Discrete Form
3.1.3. Fractional Spatial Regularization Term for the Residual Field
- When s approaches 1, Equation (18) approximates a quadratic penalty on , imposing strong smoothness constraints on the residual field. This is beneficial for obtaining highly smooth solutions in scenarios with relatively low noise and good coverage.
- When s approaches 0, the power exponent decreases, making the energy less sensitive to large differences on individual edges. This emphasizes evaluating the global structure through the cumulative effect of multiple edges, resulting in stronger robustness against local anomalies and incomplete viewpoint overlaps.
3.2. Fractional-Order Temporal Dynamics Solving Strategy
3.2.1. From Integer-Order Gradient Flow to Fractional-Order Gradient Flow
3.2.2. Discrete Time Update Based on GL Form
- When is close to 0, is small, and is short, the contribution of is negligible. is primarily controlled by the current gradient term, approximating classical Gradient Descent or Gauss–Newton updates.
- When is close to 1, and and take larger values, the response of memory weights to historical increments is enhanced. The algorithm exhibits significant temporal long-memory characteristics, which helps smooth the optimization path and suppress high-frequency oscillations in scenarios with complex energy landscapes and numerous local minima.
3.2.3. Geometric Implementation of Pose Update with Fractional Time Memory
3.3. Construction and Solution of the Unified Energy Model
3.3.1. Unified Energy Model and Definition of Terms
- Data Term :This term measures the scale-normalized residual between the transformed source points and target points, serving as the dominant term reflecting geometric consistency in the unified energy.
- Entropy Regularization Term :This term imposes entropy regularization on the local transport plan, encouraging correspondences to maintain a certain degree of spread within the local neighborhood. This prevents degeneracy into extremely few edges, thereby enhancing stability under sparse sampling conditions.
- Normal Consistency Term : Let and be the unit normals of the source and target points, respectively. We calculate their alignment on each edge asand defineWhen the normals of most weighted correspondence edges are nearly aligned, takes a small value; conversely, when there are numerous mismatched edges with inconsistent normals, this term increases, thereby suppressing registration results with inconsistent geometric structures.
- Spherical Normal Distribution Alignment (SNDA) Term : We construct direction histograms and on the unit sphere for the normals of the source and target point clouds, respectively. Under pose T, is mapped to via rotation . The normalized correlation coefficient between them is defined aswhere the inner product is integrated discretely over the unit sphere. The SNDA energy is then defined asThis term measures the consistency of normal distributions at a global scale and is capable of counteracting misleading local matches, making it particularly suitable for scenarios with uneven local coverage caused by non-repetitive scanning.
3.3.2. Solving Framework Based on Fractional Temporal Dynamics
- Local Linearization and Base Step Construction: In the vicinity of pose , we perform a first-order or second-order approximation of the local residual terms (including and ) in the unified energy . By constructing normal equations, we obtain a base increment . This increment can be viewed as a one-step approximation of the integer-order gradient flow (19) in discrete time.
- Introduction of Fractional Time Memory: We input and its historical steps into the fractional increment update formula (24) to obtain the effective increment with long memory:where is the fractional order, is the memory kernel generated by GL weights, and and control the relative influence of the instantaneous gradient and historical memory, respectively. This step embodies our fractional innovation in the temporal dimension: unlike traditional momentum methods, the memory kernel is derived from the rigorous mathematical definition of fractional derivatives, causing the influence intensity and time scale of historical steps to decay according to a power law rather than simple exponential decay.
- Pose Update and Energy-Driven Line Search: We execute the update on using the effective increment :and perform a 1D line search along this direction. We evaluate on a set of scaling factors to select a step size that satisfies sufficient decrease conditions. To enhance robustness in complex energy landscapes, we employ a non-monotonic line search with a finite window. This allows the energy to undergo finite non-monotonic changes within an iteration window and terminates the iteration at the current scale early upon detecting a “plateau” (via a threshold on the max/min energy difference within the window).
3.3.3. Complementarity of Spatial and Temporal Components
3.3.4. Verification of Consistency Between Unified Energy and Pose Variation
4. Experiments and Analysis
4.1. Experimental Data Preparation
4.1.1. Viewpoint Simulation and Partial Point Cloud Generation
- Model Preprocessing: First, the model point cloud is centered (setting its centroid to the origin) and normalized (scaling it within a unit bounding box) to eliminate scale and translation ambiguities.
- Virtual Camera Scanning: We define a virtual camera pose, including its position , observation target (usually the origin), and up vector .
- Visibility and Occlusion Judgment: By simulating a pinhole camera model, we calculate the visibility of each point in . A point is considered visible if and only if it satisfies the following conditions simultaneously:
- −
- Frustum Constraint: Point lies within the preset depth range of the camera, i.e.,
- −
- Forward Constraint: Point must be located in front of the camera, i.e.,
- −
- Back-face Culling: To simulate occlusion by opaque surfaces, we utilize the normal vector at point . The point is deemed visible only if the angle between the normal and the viewing vector is less than a certain threshold (e.g., 90°).
- Partial Point Cloud Basis: All points passing the above filtering constitute the “visible model point cloud” . This forms the basis for subsequent perturbation.
4.1.2. Ground Truth Pose and Source Point Cloud Generation
4.1.3. Adaptive Gaussian Perturbation (Simulating Non-Repetitive Sampling)
- Local Density Estimation: Point position jitter (in terms of absolute distance) caused by non-repetitive sampling is typically greater in sparse regions than in dense regions. We employ the K-Nearest Neighbor (K-NN) distance to quantify the local sparsity of each point in . We calculate the Euclidean distance from to its K-th nearest neighbor. The choice of K (e.g., ) simulates the scale of the perturbation influence. A larger indicates that the region where is located is sparser.
- Adaptive Perturbation Radius: We treat as the adaptive perturbation radius for point . This implies that points in sparse regions are allowed to jitter within a larger range.
- Gaussian Perturbation Generation: We randomly select a certain proportion (e.g., 100%) of points from for perturbation. For each selected point , we generate a 3D Gaussian perturbation vector .
- −
- Adaptive Standard Deviation: The standard deviation of the perturbation is proportional to the perturbation radius of that point, i.e.,The choice of is based on the rule of the Gaussian distribution, ensuring that approximately of the random perturbation vectors naturally fall within the radius .
- −
- Perturbation Truncation: To strictly ensure that the perturbation remains within the radius, we truncate the generated :
- −
- Generating Final Source Point Cloud:
4.2. Registration Evaluation Criteria
- Rotation Error (RRE): RRE measures the angular difference between the estimated rotation and the ground truth rotation . It is defined as the rotation angle of the relative rotation matrix . This angle can be calculated via the trace of . The RRE converts this radian value (or uses it directly in calculation) into degrees:where denotes the trace of a matrix (the sum of diagonal elements), denotes the transpose (inverse) of , and arccos is the arccosine function.
- Relative Translation Error (RTE): RTE measures the Euclidean distance between the estimated translation and the ground truth translation :where denotes the norm (Euclidean distance) of a vector.
- Success Rate: In non-convex registration problems, comparing average RRE/RTE alone can be misleading, as a few extreme failure cases (where RRE approaches 180°) can severely skew the mean. Therefore, we introduce the Success Rate as a more robust macroscopic evaluation metric. A registration experiment is considered successful if and only if both its RRE and RTE are below preset thresholds and . In the experiments of this paper, we adopt a set of strict thresholds:The Success Rate is defined as the percentage of successful trials out of all test cases. This metric is a key criterion for measuring the robustness of the algorithm under challenging conditions (such as the non-repetitive sampling perturbations simulated in this experiment).
4.3. Bayesian Parameter Optimization
4.4. Comparative Experiments
4.4.1. Comparison Methods and Characteristics
- RANSAC+FPFH+ICP: A classic three-stage pipeline comprising feature extraction (FPFH), global estimation (RANSAC), and point-to-plane ICP for superior local refinement. It serves as a traditional baseline but relies heavily on feature stability.
- FGR+ICP: An advanced non-learning framework that optimizes global pose via robust cost functions (e.g., GNC) followed by ICP. It offers higher efficiency and stability than RANSAC under moderate outlier ratios [20].
- PREDATOR: An advanced Transformer-based network that simultaneously predicts overlap and inliers. We utilize its pre-trained model to evaluate cross-dataset generalization and robustness under non-repetitive sampling [23].
- GeoTransformer: Encodes multi-scale geometry using GNNs and Transformers. It serves both as a strong learning-based baseline and as the front-end generator for our method, enabling a direct evaluation of different back-end solving strategies [24].
4.4.2. Experimental Settings
4.4.3. Results and Analysis
4.5. Ablation Studies
4.5.1. Experimental Purpose and Settings for Module-Wise Ablations
- no_time_frac: Disables the temporal fractional memory, relying solely on geometric increments (based on the current gradient and energy descent) to update the pose in the main processing stage;
- no_riesz_frac: Removes the fractional spatial regularization term from the unified energy, ceasing to couple point cloud residuals across neighborhoods via the Riesz-type non-local operator;
- no_ot: Replaces the soft correspondence term in the unified energy with 1-NN weighted SVD/ICP edges, i.e., relying only on nearest-neighbor rigid registration without explicitly solving for sparse optimal transport weights;
- no_bracket: Disables the bracketing search mechanism in the three-stage solver (including the bootstrap stage and the main processing/polishing stages), using only fixed step sizes or local line searches for updates;
- no_snda_boot: Skips the global rotation search based on the Spherical Normal Distribution Alignment (SNDA) prior in the bootstrap stage, entering the subsequent optimization directly from the given initial pose.
4.5.2. Module-Wise Ablation Results and Analysis
4.5.3. Experimental Purpose and Settings for Order-Oriented Ablations
4.5.4. Order-Oriented Ablation Results and Analysis
4.6. Real-World Scenario Testing
5. Discussion
5.1. Analysis of Solver Convergence Properties
- (1)
- Heavy-tailed vs. Exponential Memory (Comparison with Nesterov). Classical momentum methods, including Nesterov, rely on an exponentially decaying history (). This implies a “short-term memory” mechanism. While efficient for smooth convex basins, this momentum dissipates rapidly when the solver encounters extended “flat” plateaus or continuous jittery regions characteristic of sparse LiDAR scans. In contrast, the Grünwald-Letnikov fractional definition introduces a memory kernel that follows a power-law decay (). This “heavy-tailed” long-term memory allows the solver to accumulate and retain directional inertia over a significantly longer horizon. It provides the sustained “kinetic energy” necessary to escape deep, wide basins of attraction where classical exponentially-decaying momentum would stagnate.
- (2)
- Infeasibility of Second-Order Methods. Second-order methods (e.g., Gauss-Newton) require the inversion of the Hessian matrix to normalize the gradient. As discussed in Section 3.2, the sampling pattern of non-repetitive LiDAR is spatially sparse and anisotropic, frequently rendering the Hessian matrix ill-conditioned or singular (degenerate geometry) due to the lack of constraints in directions perpendicular to the scan lines. Consequently, second-order updates become numerically unstable and computationally prohibitive (), whereas our fractional first-order approach maintains numerical stability with linear complexity while effectively mimicking curvature-aware benefits through the non-local Riesz operator.
5.2. Future Horizons: Optimization and Generalization
- Generalization to Sparse Modalities: The core efficacy of the fractional Riesz regularization lies in imposing structural constraints across disconnected regions. This property suggests immediate applicability to other sparse sensing modalities, such as 4D Imaging Radar or sparse visual feature matching in textureless environments, where non-local potentials can effectively “densify” geometric constraints better than integer-order Laplacians.
- Continuous-Time Estimation: The temporal component, currently employed for iterative updates, shares a theoretical isomorphism with continuous-time trajectory estimation (e.g., in CT-SLAM). The Grünwald–Letnikov memory kernel can be reinterpreted as a trajectory smoothing prior that enforces long-range temporal coherence, potentially reducing drift in large-scale mapping tasks.
- Beyond Rigid Transformation: Finally, the fractional Laplacian’s capability to maintain global topology while tolerating local irregularities offers a mathematically elegant avenue for non-rigid registration. In deformable scenarios, the global coupling introduced by the fractional order naturally enforces elastic constraints, preventing topological tearing during local warping.
6. Conclusions
Author Contributions
Funding
Data Availability Statement
Conflicts of Interest
References
- Aijazi, A.K.; Checchin, P. Non-repetitive scanning LiDAR sensor for robust 3D point cloud registration in localization and mapping applications. Sensors 2024, 24, 378. [Google Scholar] [CrossRef]
- Besl, P.J.; McKay, N.D. Method for registration of 3-D shapes. In Proceedings of the Sensor Fusion IV: Control Paradigms and Data Structures; Spie: Bellingham, WA, USA, 1992; Volume 1611, pp. 586–606. [Google Scholar]
- Segal, A.; Haehnel, D.; Thrun, S. Generalized-icp. Robot. Sci. Syst. 2009, 2, 435. [Google Scholar]
- Myronenko, A.; Song, X. Point set registration: Coherent point drift. IEEE Trans. Pattern Anal. Mach. Intell. 2010, 32, 2262–2275. [Google Scholar] [CrossRef] [PubMed]
- Yang, H.; Shi, J.; Carlone, L. Teaser: Fast and certifiable point cloud registration. IEEE Trans. Robot. 2020, 37, 314–333. [Google Scholar] [CrossRef]
- Zhang, X.; Chen, Y. Admissibility and robust stabilization of continuous linear singular fractional order systems with the fractional order α: The 0 < α < 1 case. ISA Trans. 2018, 82, 42–50. [Google Scholar] [PubMed]
- Zhang, X.; Chen, S.; Zhang, J.X. Adaptive sliding mode consensus control based on neural network for singular fractional order multi-agent systems. Appl. Math. Comput. 2022, 434, 127442. [Google Scholar] [CrossRef]
- Liu, T.; Jiang, Z.P. Event-based control of nonlinear systems with partial state and output feedback. Automatica 2015, 53, 10–22. [Google Scholar] [CrossRef]
- Liu, T.; Qin, Z.; Hong, Y.; Jiang, Z.P. Distributed optimization of nonlinear multiagent systems: A small-gain approach. IEEE Trans. Autom. Control 2021, 67, 676–691. [Google Scholar] [CrossRef]
- Zhang, X.; Liu, R.; Ren, J.; Gui, Q. Adaptive fractional image enhancement algorithm based on rough set and particle swarm optimization. Fractal Fract. 2022, 6, 100. [Google Scholar] [CrossRef]
- Zhang, X.; Dai, L. Image enhancement based on rough set and fractional order differentiator. Fractal Fract. 2022, 6, 214. [Google Scholar] [CrossRef]
- Zhang, X.; Boutat, D.; Liu, D. Applications of fractional operator in image processing and stability of control systems. Fractal Fract. 2023, 7, 359. [Google Scholar] [CrossRef]
- Zhang, J.X.; Ding, J.; Chai, T. Fault-tolerant prescribed performance control of wheeled mobile robots: A mixed-gain adaption approach. IEEE Trans. Autom. Control 2024, 69, 5500–5507. [Google Scholar]
- Zhang, J.X.; Xu, K.D.; Wang, Q.G. Prescribed performance tracking control of time-delay nonlinear systems with output constraints. IEEE/CAA J. Autom. Sin. 2024, 11, 1557–1565. [Google Scholar] [CrossRef]
- Turk, G.; Levoy, M. Zippered polygon meshes from range images. In Proceedings of the 21st Annual Conference on Computer Graphics and Interactive Techniques, Orlando, FL, USA, 24–29 July 1994; pp. 311–318. [Google Scholar]
- Drost, B.; Ulrich, M.; Bergmann, P.; Hartinger, P.; Steger, C. Introducing mvtec itodd-a dataset for 3d object recognition in industry. In Proceedings of the IEEE International Conference on Computer Vision Workshops, Venice, Italy, 22–29 October 2017; pp. 2200–2208. [Google Scholar]
- Kaskman, R.; Zakharov, S.; Shugurov, I.; Ilic, S. Homebreweddb: Rgb-d dataset for 6d pose estimation of 3d objects. In Proceedings of the IEEE/CVF International Conference on Computer Vision Workshops, Seoul, Republic of Korea, 27–28 October 2019. [Google Scholar]
- Jones, D.R.; Schonlau, M.; Welch, W.J. Efficient global optimization of expensive black-box functions. J. Glob. Optim. 1998, 13, 455–492. [Google Scholar] [CrossRef]
- Snoek, J.; Larochelle, H.; Adams, R.P. Practical bayesian optimization of machine learning algorithms. In Proceedings of the Advances in Neural Information Processing Systems 25, Lake Tahoe, Nevada, 3–6 December 2012. [Google Scholar]
- Zhou, Q.Y.; Park, J.; Koltun, V. Fast global registration. In Proceedings of the European Conference on Computer Vision; Springer: Berlin/Heidelberg, Germany, 2016; pp. 766–782. [Google Scholar]
- Fischler, M.A.; Bolles, R.C. Random sample consensus: A paradigm for model fitting with applications to image analysis and automated cartography. Commun. ACM 1981, 24, 381–395. [Google Scholar] [CrossRef]
- Rusu, R.B.; Blodow, N.; Beetz, M. Fast point feature histograms (FPFH) for 3D registration. In Proceedings of the 2009 IEEE International Conference on Robotics and Automation, Kobe, Japan, 12–17 May 2009; IEEE: Piscataway Township, NJ, USA, 2009; pp. 3212–3217. [Google Scholar]
- Huang, S.; Gojcic, Z.; Usvyatsov, M.; Wieser, A.; Schindler, K. Predator: Registration of 3d point clouds with low overlap. In Proceedings of the IEEE/CVF Conference on Computer Vision and Pattern Recognition, Nashville, TN, USA, 20–25 June 2021; pp. 4267–4276. [Google Scholar]
- Qin, Z.; Yu, H.; Wang, C.; Guo, Y.; Peng, Y.; Ilic, S.; Hu, D.; Xu, K. Geotransformer: Fast and robust point cloud registration with geometric transformer. IEEE Trans. Pattern Anal. Mach. Intell. 2023, 45, 9806–9821. [Google Scholar] [CrossRef] [PubMed]









| Dataset | K | Success Rate (RRE < 3°, RTE < 0.03 m) of the Corresponding Method % | |||||
|---|---|---|---|---|---|---|---|
| Ours | GeoTrans Former | RANSAC+ FPFH+ ICP | PREDATOR | FGR+ ICP | RANSAC+ FPFH+ TEASER++ | ||
| Stanford 3D | 8 | 100.00 | 68.33 | 86.11 | 52.78 | 76.67 | 11.11 |
| 12 | 100.00 | 66.11 | 76.67 | 49.44 | 71.67 | 13.89 | |
| 16 | 100.00 | 67.78 | 50.56 | 54.44 | 71.67 | 11.67 | |
| 20 | 100.00 | 54.44 | 51.67 | 49.44 | 66.11 | 2.22 | |
| 24 | 100.00 | 55.00 | 45.00 | 42.22 | 60.56 | 5.00 | |
| ITODD | 8 | 100.00 | 91.52 | 79.09 | 20.00 | 62.73 | 0.30 |
| 12 | 100.00 | 83.33 | 63.33 | 17.27 | 50.91 | 0.00 | |
| 16 | 100.00 | 70.00 | 53.64 | 13.94 | 45.76 | 0.00 | |
| 20 | 99.70 | 53.33 | 46.67 | 12.73 | 37.27 | 1.82 | |
| 24 | 90.61 | 31.52 | 33.94 | 14.24 | 33.94 | 0.00 | |
| HB | 8 | 100.00 | 88.15 | 92.78 | 17.22 | 83.33 | 0.00 |
| 12 | 100.00 | 53.52 | 85.00 | 15.19 | 76.85 | 0.00 | |
| 16 | 99.44 | 53.33 | 77.59 | 14.81 | 73.70 | 0.19 | |
| 20 | 96.85 | 44.63 | 55.93 | 13.70 | 68.33 | 13.70 | |
| 24 | 96.11 | 30.56 | 44.44 | 12.78 | 66.11 | 0.37 | |
| K | Maximum Rotation Error | |||||
|---|---|---|---|---|---|---|
| Ours | no_riesz_frac | no_time_frac | no_bracket | no_ot | no_snda_boot | |
| 8 | 0.17 | 0.94 | 0.69 | 0.94 | 0.81 | 0.64 |
| 12 | 0.38 | 1.51 | 1.87 | 1.53 | 6.30 | 1.53 |
| 16 | 0.37 | 1.78 | 35.90 | 0.78 | 41.96 | 2.83 |
| 20 | 0.92 | 0.96 | 38.10 | 2.15 | 129.76 | 113.25 |
| 24 | 0.96 | 1.44 | 177.73 | 178.02 | 167.78 | 178.05 |
| K | Maximum Relative Translation Error | |||||
|---|---|---|---|---|---|---|
| Ours | no_riesz_frac | no_time_frac | no_bracket | no_ot | no_snda_boot | |
| 8 | 0.002 | 0.014 | 0.011 | 0.014 | 0.014 | 0.010 |
| 12 | 0.004 | 0.021 | 0.026 | 0.023 | 0.075 | 0.023 |
| 16 | 0.005 | 0.019 | 0.790 | 0.016 | 0.672 | 0.032 |
| 20 | 0.012 | 0.019 | 0.571 | 0.036 | 0.936 | 0.925 |
| 24 | 0.012 | 0.020 | 1.405 | 1.688 | 1.568 | 1.712 |
| Fixed Spatial Order | |||
|---|---|---|---|
| Parameter Selection | Bunny | Obj_000001 | Obj_000013 |
| 0.5589 | 0.2437 | 0.2519 | |
| 0.5458 | 0.2422 | 0.2387 | |
| 0.5461 | 0.2413 | 0.2503 | |
| 0.5498 | 0.2479 | 0.2540 | |
| 0.5871 | 0.2483 | 0.2552 | |
| 0.5931 | 0.2499 | 0.2609 | |
| Fixed Temporal Order | |||
|---|---|---|---|
| Parameter Selection | Bunny | Obj_000001 | Obj_000013 |
| 0.5589 | 0.2437 | 0.2519 | |
| 0.5743 | 0.2367 | 0.2436 | |
| 0.5260 | 0.2439 | 0.2430 | |
| 0.4906 | 0.2448 | 0.2465 | |
| 0.5084 | 0.2456 | 0.2484 | |
| 0.5973 | 0.2528 | 0.2521 | |
| Points | K | FGR + ICP | GeoTransformer | Ours | ||||||||
|---|---|---|---|---|---|---|---|---|---|---|---|---|
| RRE/° | RTE/m | Time/s | RRE/° | RTE/m | Time/s | RRE/° | RTE/m | Time/s | ||||
| 6000 | 8 | 62.576 | 0.5249 | 2.1802 | 1.6087 | 0.0201 | 0.9203 | 0.2102 | 0.0019 | 8.2590 | ||
| 12 | 48.991 | 0.3011 | 2.2303 | 3.3671 | 0.0408 | 0.9144 | 0.2558 | 0.0029 | 7.5648 | |||
| 16 | 50.068 | 0.4015 | 2.3084 | 3.5291 | 0.0459 | 0.9817 | 0.2952 | 0.0032 | 9.6769 | |||
| 20 | 91.159 | 0.7589 | 2.2940 | 3.8393 | 0.0541 | 0.9973 | 0.4997 | 0.0050 | 9.4807 | |||
| 24 | 66.821 | 0.4199 | 2.2051 | 5.4106 | 0.0776 | 1.0118 | 0.6561 | 0.0086 | 10.351 | |||
| 8000 | 8 | 13.125 | 0.1166 | 2.1044 | 0.8258 | 0.0080 | 0.8663 | 0.1264 | 0.0013 | 8.2137 | ||
| 12 | 33.905 | 0.2156 | 2.0067 | 1.1721 | 0.0106 | 0.9291 | 0.0872 | 0.0005 | 9.3213 | |||
| 16 | 58.524 | 0.6787 | 2.3554 | 1.6468 | 0.0156 | 0.8666 | 0.2137 | 0.0008 | 7.6903 | |||
| 20 | 82.654 | 0.6842 | 2.2675 | 2.5765 | 0.0286 | 0.8688 | 0.2535 | 0.0012 | 8.1750 | |||
| 24 | 92.740 | 0.1166 | 2.1044 | 3.7679 | 0.0406 | 0.8650 | 0.3773 | 0.0035 | 8.8328 | |||
| 10,000 | 8 | 4.4965 | 0.0672 | 2.0245 | 0.9190 | 0.0140 | 1.0462 | 0.0368 | 0.0005 | 11.456 | ||
| 12 | 53.947 | 0.4399 | 2.3068 | 1.7617 | 0.0240 | 0.8860 | 0.1100 | 0.0015 | 8.0418 | |||
| 16 | 37.923 | 0.3259 | 2.0984 | 1.5712 | 0.0189 | 0.8604 | 0.1343 | 0.0020 | 8.7841 | |||
| 20 | 68.486 | 0.5459 | 2.2597 | 1.3239 | 0.0151 | 0.8446 | 0.1802 | 0.0008 | 9.3973 | |||
| 24 | 68.195 | 0.5274 | 2.3169 | 3.0085 | 0.0374 | 0.8918 | 2.2480 | 0.0138 | 11.374 | |||
Disclaimer/Publisher’s Note: The statements, opinions and data contained in all publications are solely those of the individual author(s) and contributor(s) and not of MDPI and/or the editor(s). MDPI and/or the editor(s) disclaim responsibility for any injury to people or property resulting from any ideas, methods, instructions or products referred to in the content. |
© 2026 by the authors. Licensee MDPI, Basel, Switzerland. This article is an open access article distributed under the terms and conditions of the Creative Commons Attribution (CC BY) license.
Share and Cite
Yang, Q.; Li, D.; Li, M.; Liu, L. A Fractional-Order Spatiotemporal Unified Energy Framework for Non-Repetitive LiDAR Point Cloud Registration. Fractal Fract. 2026, 10, 42. https://doi.org/10.3390/fractalfract10010042
Yang Q, Li D, Li M, Liu L. A Fractional-Order Spatiotemporal Unified Energy Framework for Non-Repetitive LiDAR Point Cloud Registration. Fractal and Fractional. 2026; 10(1):42. https://doi.org/10.3390/fractalfract10010042
Chicago/Turabian StyleYang, Qi, Dongwei Li, Minghao Li, and Lu Liu. 2026. "A Fractional-Order Spatiotemporal Unified Energy Framework for Non-Repetitive LiDAR Point Cloud Registration" Fractal and Fractional 10, no. 1: 42. https://doi.org/10.3390/fractalfract10010042
APA StyleYang, Q., Li, D., Li, M., & Liu, L. (2026). A Fractional-Order Spatiotemporal Unified Energy Framework for Non-Repetitive LiDAR Point Cloud Registration. Fractal and Fractional, 10(1), 42. https://doi.org/10.3390/fractalfract10010042

