#include <mp2p_icp/optimal_tf_gauss_newton.h>
#include <mp2p_icp/optimal_tf_horn.h>
#include <mp2p_icp/optimal_tf_olae.h>
#include <mrpt/core/exceptions.h>
#include <mrpt/core/get_env.h>
#include <mrpt/poses/CPose3D.h>
#include <mrpt/poses/CPose3DQuat.h>
#include <mrpt/poses/Lie/SO.h>
#include <mrpt/random.h>
#include <mrpt/system/CTimeLogger.h>
#include <mrpt/system/filesystem.h>
#include <cstdlib>
#include <iostream>
#include <sstream>
Go to the source code of this file.
|  | 
| TPlanes | generate_planes (const size_t nPlanes) | 
|  | 
| TPoints | generate_points (const size_t nPts) | 
|  | 
| int | main ([[maybe_unused]] int argc, [[maybe_unused]] char **argv) | 
|  | 
| bool | test_icp_algos (const size_t numPts, const size_t numLines, const size_t numPlanes, const double xyz_noise_std=.0, const double n_err_std=.0, bool use_robust=false, const double outliers_ratio=.0) | 
|  | 
| std::tuple< mrpt::poses::CPose3D, std::vector< std::size_t > > | transform_points_planes (const TPoints &pA, TPoints &pB, mrpt::tfest::TMatchingPairList &pointsPairs, const TPlanes &plA, TPlanes &plB, std::vector< mp2p_icp::matched_plane_t > &planePairs, mp2p_icp::MatchedPointPlaneList &pt2plPairs, const double xyz_noise_std, const double n_err_std, const double outliers_ratio) | 
|  | 
◆ TPlanes
◆ TPoints
      
        
          | using TPoints =  std::vector<mrpt::math::TPoint3D> | 
      
 
 
◆ generate_planes()
      
        
          | TPlanes generate_planes | ( | const size_t | nPlanes | ) |  | 
      
 
 
◆ generate_points()
      
        
          | TPoints generate_points | ( | const size_t | nPts | ) |  | 
      
 
 
◆ main()
      
        
          | int main | ( | [[maybe_unused] ] int | argc, | 
        
          |  |  | [[maybe_unused] ] char ** | argv | 
        
          |  | ) |  |  | 
      
 
 
◆ test_icp_algos()
      
        
          | bool test_icp_algos | ( | const size_t | numPts, | 
        
          |  |  | const size_t | numLines, | 
        
          |  |  | const size_t | numPlanes, | 
        
          |  |  | const double | xyz_noise_std = .0, | 
        
          |  |  | const double | n_err_std = .0, | 
        
          |  |  | bool | use_robust = false, | 
        
          |  |  | const double | outliers_ratio = .0 | 
        
          |  | ) |  |  | 
      
 
 
◆ transform_points_planes()
      
        
          | std::tuple<mrpt::poses::CPose3D, std::vector<std::size_t> > transform_points_planes | ( | const TPoints & | pA, | 
        
          |  |  | TPoints & | pB, | 
        
          |  |  | mrpt::tfest::TMatchingPairList & | pointsPairs, | 
        
          |  |  | const TPlanes & | plA, | 
        
          |  |  | TPlanes & | plB, | 
        
          |  |  | std::vector< mp2p_icp::matched_plane_t > & | planePairs, | 
        
          |  |  | mp2p_icp::MatchedPointPlaneList & | pt2plPairs, | 
        
          |  |  | const double | xyz_noise_std, | 
        
          |  |  | const double | n_err_std, | 
        
          |  |  | const double | outliers_ratio | 
        
          |  | ) |  |  | 
      
 
 
◆ DO_PRINT_ALL
  
  | 
        
          | bool DO_PRINT_ALL = nullptr != ::getenv("DO_PRINT_ALL") |  | static | 
 
 
◆ DO_SAVE_STAT_FILES
  
  | 
        
          | bool DO_SAVE_STAT_FILES = nullptr != ::getenv("DO_SAVE_STAT_FILES") |  | static | 
 
 
◆ num_reps
  
  | 
        
          | const size_t num_reps = mrpt::get_env<int>("NUM_REPS", 25) |  | static | 
 
 
◆ SKIP_OUTLIERS
  
  | 
        
          | bool SKIP_OUTLIERS = nullptr != ::getenv("SKIP_OUTLIERS") |  | static | 
 
 
◆ TEST_LARGE_ROTATIONS
  
  | 
        
          | bool TEST_LARGE_ROTATIONS = nullptr != ::getenv("TEST_LARGE_ROTATIONS") |  | static |