Conscience Core
CscPointCloudMatcher.h
Go to the documentation of this file.
1 #ifndef CscPointCloudMatcher_h
2 #define CscPointCloudMatcher_h
3 
4 #include <array>
5 #include <map>
6 #include <string>
7 #include <vector>
8 
9 #include <pcl/point_types.h>
10 #include <pcl/registration/icp.h>
11 
12 #include "Axiomes/Csc3dTypes.h"
13 
14 #include "Util/conscience_log.h"
15 
16 using std::cout, std::endl, std::string, std::pair, std::vector, std::to_string;
17 
18 using namespace conscience_utils::logging;
19 using namespace conscience_core::axiomes;
20 
21 namespace conscience_core::lidar {
22 
24 public:
25  struct Result {
26  bool success;
31  float score = 0;
32 
36  CscPoint3dOriented *transformation = nullptr;
37  };
38 
40 
45  const Result compare(const vector<const CscPoint3d *> &pointsReference, const vector<const CscPoint3d *> &points, bool XZTo2DOnly) const;
46  float calculateLikelihood(const vector<const CscPoint3d *> &pointsReference, const vector<const CscPoint3d *> &points, bool XZTo2DOnly);
47 
48 private:
49  unique_ptr<CscLogger> logger;
50 
51  // ICP configuration method
52  void configureICP(pcl::IterativeClosestPoint<pcl::PointXYZ, pcl::PointXYZ> &icp);
53 
54  // Conversion methods
55  pcl::PointCloud<pcl::PointXYZ>::Ptr convertToPCLPointCloud(const vector<const CscPoint3d *> &points);
56  vector<const CscPoint3d *> convertToCscPoint3dVector(const pcl::PointCloud<pcl::PointXYZ> &pclCloud);
57 
58  // Filtering method
59  void filterPointCloud(pcl::PointCloud<pcl::PointXYZ>::Ptr &cloud,
60  const Eigen::Vector4f &minPoint,
61  const Eigen::Vector4f &maxPoint);
62  pair<const Eigen::Vector4f, const Eigen::Vector4f> computeBoxAroundReference(pcl::PointXYZ &reference, double maxDistanceForFilter);
63 };
64 
65 }
66 
67 #endif
conscience_log.h
nlohmann::to_string
NLOHMANN_BASIC_JSON_TPL_DECLARATION std::string to_string(const NLOHMANN_BASIC_JSON_TPL &j)
user-defined to_string function for JSON values
Definition: json.hpp:26470
conscience_core::lidar::CscPointCloudMatcher
Definition: CscPointCloudMatcher.h:23
conscience_core::axiomes
Definition: Csc2dTypes.cpp:9
conscience_core::lidar
Definition: CscEntityReflexion.h:42
logger
static std::unique_ptr< CscLogger > logger
Definition: gltfHelpers.cpp:6
conscience_utils::logging
Definition: conscience_log.cpp:20
conscience_core::lidar::CscPointCloudMatcher::Result::success
bool success
Definition: CscPointCloudMatcher.h:26
conscience_core::lidar::CscPointCloudMatcher::Result
Definition: CscPointCloudMatcher.h:25
Csc3dTypes.h
conscience_core::axiomes::CscPoint3dOriented
Definition: Csc3dTypes.h:277