feat: 一种复杂的实现
parent
9f31523913
commit
9e2e286251
|
@ -3,7 +3,6 @@ project(pcl_wrapper)
|
||||||
|
|
||||||
set(CMAKE_CXX_STANDARD 17)
|
set(CMAKE_CXX_STANDARD 17)
|
||||||
|
|
||||||
|
|
||||||
# 获取 libomp 安装路径
|
# 获取 libomp 安装路径
|
||||||
execute_process(
|
execute_process(
|
||||||
COMMAND brew --prefix libomp
|
COMMAND brew --prefix libomp
|
||||||
|
@ -15,11 +14,22 @@ execute_process(
|
||||||
find_package(PCL REQUIRED)
|
find_package(PCL REQUIRED)
|
||||||
|
|
||||||
# 添加 include 路径
|
# 添加 include 路径
|
||||||
|
include_directories(include)
|
||||||
|
include_directories(include/pcl_wrapper)
|
||||||
include_directories(${PCL_INCLUDE_DIRS} "${LIBOMP_PREFIX}/include")
|
include_directories(${PCL_INCLUDE_DIRS} "${LIBOMP_PREFIX}/include")
|
||||||
add_definitions(${PCL_DEFINITIONS})
|
add_definitions(${PCL_DEFINITIONS})
|
||||||
|
|
||||||
# 添加库
|
# 添加库
|
||||||
add_library(pclwrapper SHARED pcl_wrapper.cpp)
|
add_library(pclwrapper SHARED wrapper.cpp
|
||||||
|
include/pcl_wrapper/point_types.hpp
|
||||||
|
include/pcl_wrapper/filter.hpp
|
||||||
|
include/pcl_wrapper/kdtree.hpp
|
||||||
|
include/pcl_wrapper/io.hpp
|
||||||
|
include/pcl_wrapper/pcl_wrapper_api.hpp
|
||||||
|
src/filter.cpp
|
||||||
|
src/kdtree.cpp
|
||||||
|
src/io.cpp
|
||||||
|
)
|
||||||
|
|
||||||
# 指定 OpenMP 和 PCL 库
|
# 指定 OpenMP 和 PCL 库
|
||||||
target_compile_options(pclwrapper PRIVATE -Xpreprocessor -fopenmp)
|
target_compile_options(pclwrapper PRIVATE -Xpreprocessor -fopenmp)
|
||||||
|
|
|
@ -0,0 +1,33 @@
|
||||||
|
#ifndef PCL_WRAPPER_FILTER_HPP
|
||||||
|
#define PCL_WRAPPER_FILTER_HPP
|
||||||
|
// filter.hpp
|
||||||
|
#pragma once
|
||||||
|
#include <pcl/point_cloud.h>
|
||||||
|
#include "point_types.hpp"
|
||||||
|
|
||||||
|
namespace pcl_wrapper {
|
||||||
|
|
||||||
|
template<typename PointT>
|
||||||
|
class FilterBase {
|
||||||
|
public:
|
||||||
|
virtual ~FilterBase() = default;
|
||||||
|
virtual void setInputCloud(typename pcl::PointCloud<PointT>::Ptr cloud) = 0;
|
||||||
|
virtual typename pcl::PointCloud<PointT>::Ptr getFilteredCloud() = 0;
|
||||||
|
};
|
||||||
|
|
||||||
|
// filter.hpp 中追加声明(不要写实现体)
|
||||||
|
template<typename PointT>
|
||||||
|
class VoxelGridFilterImpl : public FilterBase<PointT> {
|
||||||
|
public:
|
||||||
|
void setLeafSize(float ls);
|
||||||
|
void setInputCloud(typename pcl::PointCloud<PointT>::Ptr cloud) override;
|
||||||
|
typename pcl::PointCloud<PointT>::Ptr getFilteredCloud() override;
|
||||||
|
|
||||||
|
private:
|
||||||
|
typename pcl::PointCloud<PointT>::Ptr inputCloud;
|
||||||
|
float leafSize = 0.1f;
|
||||||
|
};
|
||||||
|
|
||||||
|
} // namespace pcl_wrapper
|
||||||
|
|
||||||
|
#endif //PCL_WRAPPER_FILTER_HPP
|
|
@ -0,0 +1,25 @@
|
||||||
|
//
|
||||||
|
// Created by QP on 2025/4/12.
|
||||||
|
//
|
||||||
|
|
||||||
|
#ifndef PCL_WRAPPER_IO_HPP
|
||||||
|
#define PCL_WRAPPER_IO_HPP
|
||||||
|
|
||||||
|
// io.hpp
|
||||||
|
#pragma once
|
||||||
|
#include <string>
|
||||||
|
#include <pcl/io/pcd_io.h>
|
||||||
|
#include "point_types.hpp"
|
||||||
|
|
||||||
|
namespace pcl_wrapper {
|
||||||
|
|
||||||
|
template<typename PointT>
|
||||||
|
typename pcl::PointCloud<PointT>::Ptr loadPCD(const std::string& filename);
|
||||||
|
|
||||||
|
template<typename PointT>
|
||||||
|
void savePCD(const std::string& filename, const typename pcl::PointCloud<PointT>::Ptr& cloud);
|
||||||
|
|
||||||
|
}
|
||||||
|
|
||||||
|
|
||||||
|
#endif //PCL_WRAPPER_IO_HPP
|
|
@ -0,0 +1,37 @@
|
||||||
|
//
|
||||||
|
// Created by QP on 2025/4/12.
|
||||||
|
//
|
||||||
|
|
||||||
|
#ifndef PCL_WRAPPER_KDTREE_HPP
|
||||||
|
#define PCL_WRAPPER_KDTREE_HPP
|
||||||
|
|
||||||
|
// kdtree.hpp
|
||||||
|
#pragma once
|
||||||
|
#include <pcl/kdtree/kdtree_flann.h>
|
||||||
|
#include "point_types.hpp"
|
||||||
|
|
||||||
|
namespace pcl_wrapper {
|
||||||
|
|
||||||
|
template<typename PointT>
|
||||||
|
class KdTree {
|
||||||
|
public:
|
||||||
|
virtual ~KdTree() = default;
|
||||||
|
virtual void setInputCloud(typename pcl::PointCloud<PointT>::Ptr cloud) = 0;
|
||||||
|
virtual std::vector<int> radiusSearch(const PointT& pt, float radius) = 0;
|
||||||
|
};
|
||||||
|
|
||||||
|
template<typename PointT>
|
||||||
|
class KdTreeFLANNWrapperImpl : public KdTree<PointT> {
|
||||||
|
public:
|
||||||
|
void setInputCloud(typename pcl::PointCloud<PointT>::Ptr cloud);
|
||||||
|
|
||||||
|
std::vector<int> radiusSearch(const PointT& pt, float radius);
|
||||||
|
|
||||||
|
private:
|
||||||
|
pcl::KdTreeFLANN<PointT> kdtree;
|
||||||
|
typename pcl::PointCloud<PointT>::Ptr inputCloud;
|
||||||
|
};
|
||||||
|
}
|
||||||
|
|
||||||
|
|
||||||
|
#endif //PCL_WRAPPER_KDTREE_HPP
|
|
@ -0,0 +1,24 @@
|
||||||
|
//
|
||||||
|
// Created by QP on 2025/4/12.
|
||||||
|
//
|
||||||
|
|
||||||
|
#ifndef PCL_WRAPPER_PCL_WRAPPER_API_HPP
|
||||||
|
#define PCL_WRAPPER_PCL_WRAPPER_API_HPP
|
||||||
|
// pcl_wrapper/include/pcl_wrapper/pcl_wrapper_api.hpp
|
||||||
|
#pragma once
|
||||||
|
#ifdef __cplusplus
|
||||||
|
extern "C" {
|
||||||
|
#endif
|
||||||
|
|
||||||
|
// 创建滤波器实例
|
||||||
|
void* CreateVoxelGridXYZ(float leaf);
|
||||||
|
void SetInputCloudXYZ(void* filter, const float* points, int numPoints);
|
||||||
|
void ApplyVoxelGridXYZ(void* filter, float** outPoints, int* outCount);
|
||||||
|
void FreeVoxelGridXYZ(void* filter);
|
||||||
|
|
||||||
|
|
||||||
|
|
||||||
|
#ifdef __cplusplus
|
||||||
|
}
|
||||||
|
#endif
|
||||||
|
#endif //PCL_WRAPPER_PCL_WRAPPER_API_HPP
|
|
@ -0,0 +1,19 @@
|
||||||
|
//
|
||||||
|
// Created by QP on 2025/4/12.
|
||||||
|
//
|
||||||
|
|
||||||
|
#ifndef PCL_WRAPPER_POINT_TYPES_HPP
|
||||||
|
#define PCL_WRAPPER_POINT_TYPES_HPP
|
||||||
|
|
||||||
|
#pragma once
|
||||||
|
#include <pcl/point_types.h>
|
||||||
|
|
||||||
|
namespace pcl_wrapper {
|
||||||
|
|
||||||
|
using PointXYZ = pcl::PointXYZ;
|
||||||
|
using PointXYZI = pcl::PointXYZI;
|
||||||
|
|
||||||
|
}
|
||||||
|
|
||||||
|
|
||||||
|
#endif //PCL_WRAPPER_POINT_TYPES_HPP
|
|
@ -1,65 +0,0 @@
|
||||||
#include <pcl/io/pcd_io.h>
|
|
||||||
#include <pcl/filters/voxel_grid.h>
|
|
||||||
#include <pcl/point_types.h>
|
|
||||||
|
|
||||||
using PointType = pcl::PointXYZ;
|
|
||||||
|
|
||||||
class PclPointCloud {
|
|
||||||
public:
|
|
||||||
pcl::PointCloud<PointType>::Ptr cloud;
|
|
||||||
|
|
||||||
PclPointCloud() : cloud(new pcl::PointCloud<PointType>) {}
|
|
||||||
};
|
|
||||||
|
|
||||||
class PclVoxelGrid {
|
|
||||||
public:
|
|
||||||
pcl::VoxelGrid<PointType> filter;
|
|
||||||
};
|
|
||||||
|
|
||||||
extern "C" {
|
|
||||||
|
|
||||||
void* create_point_cloud() {
|
|
||||||
return new PclPointCloud();
|
|
||||||
}
|
|
||||||
|
|
||||||
void delete_point_cloud(void* ptr) {
|
|
||||||
delete static_cast<PclPointCloud*>(ptr);
|
|
||||||
}
|
|
||||||
|
|
||||||
int load_point_cloud(void* ptr, const char* path) {
|
|
||||||
auto* cloud = static_cast<PclPointCloud*>(ptr);
|
|
||||||
return pcl::io::loadPCDFile<PointType>(path, *cloud->cloud);
|
|
||||||
}
|
|
||||||
|
|
||||||
int save_point_cloud(void* ptr, const char* path) {
|
|
||||||
auto* cloud = static_cast<PclPointCloud*>(ptr);
|
|
||||||
return pcl::io::savePCDFileBinary(path, *cloud->cloud);
|
|
||||||
}
|
|
||||||
|
|
||||||
void* create_voxel_filter() {
|
|
||||||
return new PclVoxelGrid();
|
|
||||||
}
|
|
||||||
|
|
||||||
void delete_voxel_filter(void* ptr) {
|
|
||||||
delete static_cast<PclVoxelGrid*>(ptr);
|
|
||||||
}
|
|
||||||
|
|
||||||
void set_voxel_leaf_size(void* ptr, float lx, float ly, float lz) {
|
|
||||||
auto* vf = static_cast<PclVoxelGrid*>(ptr);
|
|
||||||
vf->filter.setLeafSize(lx, ly, lz);
|
|
||||||
}
|
|
||||||
|
|
||||||
void set_voxel_input_cloud(void* vf_ptr, void* cloud_ptr) {
|
|
||||||
auto* vf = static_cast<PclVoxelGrid*>(vf_ptr);
|
|
||||||
auto* cloud = static_cast<PclPointCloud*>(cloud_ptr);
|
|
||||||
vf->filter.setInputCloud(cloud->cloud);
|
|
||||||
}
|
|
||||||
|
|
||||||
void* apply_voxel_filter(void* vf_ptr) {
|
|
||||||
auto* vf = static_cast<PclVoxelGrid*>(vf_ptr);
|
|
||||||
auto* result = new PclPointCloud();
|
|
||||||
vf->filter.filter(*result->cloud);
|
|
||||||
return result;
|
|
||||||
}
|
|
||||||
|
|
||||||
}
|
|
|
@ -0,0 +1,32 @@
|
||||||
|
// pcl_wrapper/src/filter.cpp
|
||||||
|
#include "filter.hpp"
|
||||||
|
#include <pcl/filters/voxel_grid.h>
|
||||||
|
|
||||||
|
namespace pcl_wrapper {
|
||||||
|
|
||||||
|
template<typename PointT>
|
||||||
|
void VoxelGridFilterImpl<PointT>::setLeafSize(float ls) {
|
||||||
|
leafSize = ls;
|
||||||
|
}
|
||||||
|
|
||||||
|
template<typename PointT>
|
||||||
|
void VoxelGridFilterImpl<PointT>::setInputCloud(typename pcl::PointCloud<PointT>::Ptr cloud) {
|
||||||
|
inputCloud = cloud;
|
||||||
|
}
|
||||||
|
|
||||||
|
template<typename PointT>
|
||||||
|
typename pcl::PointCloud<PointT>::Ptr VoxelGridFilterImpl<PointT>::getFilteredCloud() {
|
||||||
|
pcl::VoxelGrid<PointT> voxel;
|
||||||
|
voxel.setInputCloud(inputCloud);
|
||||||
|
voxel.setLeafSize(leafSize, leafSize, leafSize);
|
||||||
|
typename pcl::PointCloud<PointT>::Ptr filtered(new pcl::PointCloud<PointT>());
|
||||||
|
voxel.filter(*filtered);
|
||||||
|
return filtered;
|
||||||
|
}
|
||||||
|
|
||||||
|
// 显式实例化
|
||||||
|
template class VoxelGridFilterImpl<pcl::PointXYZ>;
|
||||||
|
template class VoxelGridFilterImpl<pcl::PointXYZI>;
|
||||||
|
|
||||||
|
|
||||||
|
} // namespace pcl_wrapper
|
|
@ -0,0 +1,29 @@
|
||||||
|
|
||||||
|
// pcl_wrapper/src/io.cpp
|
||||||
|
#include "io.hpp"
|
||||||
|
|
||||||
|
namespace pcl_wrapper {
|
||||||
|
|
||||||
|
template<typename PointT>
|
||||||
|
typename pcl::PointCloud<PointT>::Ptr loadPCD(const std::string& filename) {
|
||||||
|
typename pcl::PointCloud<PointT>::Ptr cloud(new pcl::PointCloud<PointT>());
|
||||||
|
if (pcl::io::loadPCDFile<PointT>(filename, *cloud) == -1) {
|
||||||
|
throw std::runtime_error("Failed to load PCD file: " + filename);
|
||||||
|
}
|
||||||
|
return cloud;
|
||||||
|
}
|
||||||
|
|
||||||
|
template<typename PointT>
|
||||||
|
void savePCD(const std::string& filename, const typename pcl::PointCloud<PointT>::Ptr& cloud) {
|
||||||
|
if (pcl::io::savePCDFileBinary(filename, *cloud) == -1) {
|
||||||
|
throw std::runtime_error("Failed to save PCD file: " + filename);
|
||||||
|
}
|
||||||
|
}
|
||||||
|
|
||||||
|
// 显式实例化
|
||||||
|
template pcl::PointCloud<pcl::PointXYZ>::Ptr loadPCD<pcl::PointXYZ>(const std::string&);
|
||||||
|
template pcl::PointCloud<pcl::PointXYZI>::Ptr loadPCD<pcl::PointXYZI>(const std::string&);
|
||||||
|
template void savePCD<pcl::PointXYZ>(const std::string&, const pcl::PointCloud<pcl::PointXYZ>::Ptr&);
|
||||||
|
template void savePCD<pcl::PointXYZI>(const std::string&, const pcl::PointCloud<pcl::PointXYZI>::Ptr&);
|
||||||
|
|
||||||
|
} // namespace pcl_wrapper
|
|
@ -0,0 +1,24 @@
|
||||||
|
|
||||||
|
// pcl_wrapper/src/kdtree.cpp
|
||||||
|
#include "kdtree.hpp"
|
||||||
|
|
||||||
|
namespace pcl_wrapper {
|
||||||
|
|
||||||
|
template<typename PointT>
|
||||||
|
void KdTreeFLANNWrapperImpl<PointT>::setInputCloud(typename pcl::PointCloud<PointT>::Ptr cloud) {
|
||||||
|
inputCloud = cloud;
|
||||||
|
kdtree.setInputCloud(cloud);
|
||||||
|
}
|
||||||
|
template<typename PointT>
|
||||||
|
std::vector<int> KdTreeFLANNWrapperImpl<PointT>::radiusSearch(const PointT& pt, float radius) {
|
||||||
|
std::vector<int> indices;
|
||||||
|
std::vector<float> sqrDistances;
|
||||||
|
kdtree.radiusSearch(pt, radius, indices, sqrDistances);
|
||||||
|
return indices;
|
||||||
|
}
|
||||||
|
|
||||||
|
// 显式模板实例化
|
||||||
|
template class KdTreeFLANNWrapperImpl<pcl::PointXYZ>;
|
||||||
|
template class KdTreeFLANNWrapperImpl<pcl::PointXYZI>;
|
||||||
|
|
||||||
|
// namespace pcl_wrapper
|
|
@ -0,0 +1,64 @@
|
||||||
|
|
||||||
|
// pcl_wrapper/src/wrapper.cpp
|
||||||
|
#include "filter.hpp"
|
||||||
|
#include "point_types.hpp"
|
||||||
|
#include "pcl_wrapper_api.hpp"
|
||||||
|
#include <vector>
|
||||||
|
#include <cstring>
|
||||||
|
|
||||||
|
using namespace pcl_wrapper;
|
||||||
|
|
||||||
|
using CloudPtr = pcl::PointCloud<PointXYZ>::Ptr;
|
||||||
|
|
||||||
|
class VoxelGridXYZBridge {
|
||||||
|
public:
|
||||||
|
VoxelGridXYZBridge(float leaf) {
|
||||||
|
filter.setLeafSize(leaf);
|
||||||
|
}
|
||||||
|
|
||||||
|
void setInput(const float* points, int count) {
|
||||||
|
CloudPtr cloud(new pcl::PointCloud<PointXYZ>());
|
||||||
|
cloud->resize(count);
|
||||||
|
for (int i = 0; i < count; ++i) {
|
||||||
|
(*cloud)[i].x = points[3 * i];
|
||||||
|
(*cloud)[i].y = points[3 * i + 1];
|
||||||
|
(*cloud)[i].z = points[3 * i + 2];
|
||||||
|
}
|
||||||
|
filter.setInputCloud(cloud);
|
||||||
|
}
|
||||||
|
|
||||||
|
void getFiltered(float** outPts, int* outCount) {
|
||||||
|
auto cloud = filter.getFilteredCloud();
|
||||||
|
*outCount = cloud->size();
|
||||||
|
*outPts = new float[*outCount * 3];
|
||||||
|
for (int i = 0; i < *outCount; ++i) {
|
||||||
|
(*outPts)[3 * i + 0] = (*cloud)[i].x;
|
||||||
|
(*outPts)[3 * i + 1] = (*cloud)[i].y;
|
||||||
|
(*outPts)[3 * i + 2] = (*cloud)[i].z;
|
||||||
|
}
|
||||||
|
}
|
||||||
|
|
||||||
|
private:
|
||||||
|
VoxelGridFilterImpl<PointXYZ> filter;
|
||||||
|
};
|
||||||
|
|
||||||
|
|
||||||
|
extern "C" {
|
||||||
|
|
||||||
|
void* CreateVoxelGridXYZ(float leaf) {
|
||||||
|
return new VoxelGridXYZBridge(leaf);
|
||||||
|
}
|
||||||
|
|
||||||
|
void SetInputCloudXYZ(void* obj, const float* points, int count) {
|
||||||
|
static_cast<VoxelGridXYZBridge*>(obj)->setInput(points, count);
|
||||||
|
}
|
||||||
|
|
||||||
|
void ApplyVoxelGridXYZ(void* obj, float** outPoints, int* outCount) {
|
||||||
|
static_cast<VoxelGridXYZBridge*>(obj)->getFiltered(outPoints, outCount);
|
||||||
|
}
|
||||||
|
|
||||||
|
void FreeVoxelGridXYZ(void* obj) {
|
||||||
|
delete static_cast<VoxelGridXYZBridge*>(obj);
|
||||||
|
}
|
||||||
|
|
||||||
|
} // extern C
|
Loading…
Reference in New Issue