Fix typos and enable links (#109)

* chore: enable youtube link

* chore: correct typos in comments
This commit is contained in:
atm 2025-05-07 09:31:31 +09:00 committed by GitHub
parent 2c5e9e6092
commit db2f8e6646
No known key found for this signature in database
GPG Key ID: B5690EEEBB952194
3 changed files with 4 additions and 4 deletions

View File

@ -129,5 +129,5 @@ small_vgicp : APE=5.956 +- 2.725 RPE(100)=1.315 +- 0.762 RPE(400)=6.8
[Code](https://github.com/koide3/small_gicp/blob/pybench/src/benchmark/odometry_benchmark.py)
Processing speed comparison between small_gicp and Open3D ([youtube]((https://youtu.be/LNESzGXPr4c?feature=shared))).
Processing speed comparison between small_gicp and Open3D ([youtube](https://youtu.be/LNESzGXPr4c?feature=shared)).
[![small_comp](https://github.com/koide3/small_gicp/assets/31344317/7959edd6-f0e4-4318-b4c1-a3f8755c407f)](https://youtu.be/LNESzGXPr4c?feature=shared)

View File

@ -431,7 +431,7 @@ python3 src/example/basic_registration.py
## [Benchmark](BENCHMARK.md)
Processing speed comparison between small_gicp and Open3D ([youtube]((https://youtu.be/LNESzGXPr4c?feature=shared))).
Processing speed comparison between small_gicp and Open3D ([youtube](https://youtu.be/LNESzGXPr4c?feature=shared)).
[![small_comp](https://github.com/koide3/small_gicp/assets/31344317/7959edd6-f0e4-4318-b4c1-a3f8755c407f)](https://youtu.be/LNESzGXPr4c?feature=shared)
### Downsampling

View File

@ -108,7 +108,7 @@ struct LevenbergMarquardtOptimizer {
// Solve with damping
const Eigen::Matrix<double, 6, 1> delta = (H + lambda * Eigen::Matrix<double, 6, 6>::Identity()).ldlt().solve(-b);
// Validte new solution
// Validate new solution
const Eigen::Isometry3d new_T = result.T_target_source * se3_exp(delta);
double new_e = reduction.error(target, source, new_T, factors);
general_factor.update_error(target, source, new_T, &e);
@ -150,7 +150,7 @@ struct LevenbergMarquardtOptimizer {
bool verbose; ///< If true, print debug messages
int max_iterations; ///< Max number of optimization iterations
int max_inner_iterations; ///< Max number of inner iterations (lambda-trial)
int max_inner_iterations; ///< Max number of inner iterations (lambda-trial)
double init_lambda; ///< Initial lambda (damping factor)
double lambda_factor; ///< Lambda increase factor
};