feat: 支持两种数据格式的体素滤波
parent
9e2e286251
commit
6e858135ce
|
@ -3,6 +3,8 @@ project(pcl_wrapper)
|
|||
|
||||
set(CMAKE_CXX_STANDARD 17)
|
||||
|
||||
set(CMAKE_LIBRARY_OUTPUT_DIRECTORY ${CMAKE_BINARY_DIR}/lib)
|
||||
|
||||
# 获取 libomp 安装路径
|
||||
execute_process(
|
||||
COMMAND brew --prefix libomp
|
||||
|
@ -21,14 +23,10 @@ add_definitions(${PCL_DEFINITIONS})
|
|||
|
||||
# 添加库
|
||||
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
|
||||
include/pcl_wrapper/cloud_handle.hpp
|
||||
include/pcl_wrapper/voxel_filter.hpp
|
||||
include/pcl_wrapper/io.hpp
|
||||
)
|
||||
|
||||
# 指定 OpenMP 和 PCL 库
|
||||
|
|
|
@ -0,0 +1,25 @@
|
|||
//
|
||||
// Created by QP on 2025/4/12.
|
||||
//
|
||||
|
||||
#ifndef PCL_WRAPPER_CLOUD_HANDLE_HPP
|
||||
#define PCL_WRAPPER_CLOUD_HANDLE_HPP
|
||||
#pragma once
|
||||
#include <pcl/point_cloud.h>
|
||||
#include <pcl/point_types.h>
|
||||
|
||||
namespace pcl_wrapper {
|
||||
|
||||
template<typename PointT>
|
||||
struct PclPointCloud {
|
||||
using CloudPtr = typename pcl::PointCloud<PointT>::Ptr;
|
||||
CloudPtr cloud;
|
||||
|
||||
PclPointCloud() : cloud(new pcl::PointCloud<PointT>()) {}
|
||||
};
|
||||
|
||||
using PointCloudXYZ = PclPointCloud<pcl::PointXYZ>;
|
||||
using PointCloudXYZI = PclPointCloud<pcl::PointXYZI>;
|
||||
|
||||
} // namespace pcl_wrapper
|
||||
#endif //PCL_WRAPPER_CLOUD_HANDLE_HPP
|
|
@ -1,33 +0,0 @@
|
|||
#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
|
|
@ -4,22 +4,27 @@
|
|||
|
||||
#ifndef PCL_WRAPPER_IO_HPP
|
||||
#define PCL_WRAPPER_IO_HPP
|
||||
|
||||
// io.hpp
|
||||
#pragma once
|
||||
#include <string>
|
||||
#include "cloud_handle.hpp"
|
||||
#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);
|
||||
bool loadPCD_XYZ(const std::string& filename, PointCloudXYZ& out) {
|
||||
return pcl::io::loadPCDFile<pcl::PointXYZ>(filename, *out.cloud) == 0;
|
||||
}
|
||||
|
||||
template<typename PointT>
|
||||
void savePCD(const std::string& filename, const typename pcl::PointCloud<PointT>::Ptr& cloud);
|
||||
bool loadPCD_XYZI(const std::string& filename, PointCloudXYZI& out) {
|
||||
return pcl::io::loadPCDFile<pcl::PointXYZI>(filename, *out.cloud) == 0;
|
||||
}
|
||||
|
||||
bool savePCD_XYZ(const std::string& filename, const PointCloudXYZ& cloud) {
|
||||
return pcl::io::savePCDFileBinary(filename, *cloud.cloud) == 0;
|
||||
}
|
||||
|
||||
bool savePCD_XYZI(const std::string& filename, const PointCloudXYZI& cloud) {
|
||||
return pcl::io::savePCDFileBinary(filename, *cloud.cloud) == 0;
|
||||
}
|
||||
}
|
||||
|
||||
|
||||
#endif //PCL_WRAPPER_IO_HPP
|
||||
|
|
|
@ -1,37 +0,0 @@
|
|||
//
|
||||
// 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
|
|
@ -4,21 +4,38 @@
|
|||
|
||||
#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);
|
||||
// ========== Cloud ==========
|
||||
|
||||
void* create_pointcloud_xyz();
|
||||
void* create_pointcloud_xyzi();
|
||||
void reserve_pointcloud_xyz(void* cloud, int count);
|
||||
void set_point_xyz(void* cloud, int index, float x, float y, float z);
|
||||
void set_point_xyzi(void* cloud, int index, float x, float y, float z, float intensity);
|
||||
void delete_pointcloud(void* cloud);
|
||||
|
||||
// ========== Voxel Filter ==========
|
||||
|
||||
void* create_voxel_filter_xyz();
|
||||
void* create_voxel_filter_xyzi();
|
||||
void set_voxel_leaf_size(void* filter, float lx, float ly, float lz);
|
||||
void set_voxel_input_cloud(void* filter, void* cloud);
|
||||
void* apply_voxel_filter_xyz(void* filter);
|
||||
void* apply_voxel_filter_xyzi(void* filter);
|
||||
void delete_voxel_filter(void* filter);
|
||||
|
||||
// ========= IO ==========
|
||||
bool load_pcd_xyz(const char* filename, void* out);
|
||||
bool load_pcd_xyzi(const char* filename, void* out);
|
||||
bool save_pcd_xyz(const char* filename, void* cloud);
|
||||
bool save_pcd_xyzi(const char* filename, void* cloud);
|
||||
|
||||
#ifdef __cplusplus
|
||||
}
|
||||
#endif
|
||||
|
||||
#endif //PCL_WRAPPER_PCL_WRAPPER_API_HPP
|
||||
|
|
|
@ -1,19 +0,0 @@
|
|||
//
|
||||
// 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
|
|
@ -0,0 +1,36 @@
|
|||
//
|
||||
// Created by QP on 2025/4/12.
|
||||
//
|
||||
|
||||
#ifndef PCL_WRAPPER_VOXEL_FILTER_HPP
|
||||
#define PCL_WRAPPER_VOXEL_FILTER_HPP
|
||||
#pragma once
|
||||
#include <pcl/filters/voxel_grid.h>
|
||||
|
||||
namespace pcl_wrapper {
|
||||
|
||||
template<typename PointT>
|
||||
struct VoxelGridWrapper {
|
||||
pcl::VoxelGrid<PointT> filter;
|
||||
|
||||
void setInputCloud(typename pcl::PointCloud<PointT>::Ptr cloud) {
|
||||
filter.setInputCloud(cloud);
|
||||
}
|
||||
|
||||
void setLeafSize(float lx, float ly, float lz) {
|
||||
filter.setLeafSize(lx, ly, lz);
|
||||
}
|
||||
|
||||
typename pcl::PointCloud<PointT>::Ptr filterCloud() {
|
||||
typename pcl::PointCloud<PointT>::Ptr result(new pcl::PointCloud<PointT>());
|
||||
filter.filter(*result);
|
||||
return result;
|
||||
}
|
||||
};
|
||||
|
||||
using VoxelGridXYZ = VoxelGridWrapper<pcl::PointXYZ>;
|
||||
using VoxelGridXYZI = VoxelGridWrapper<pcl::PointXYZI>;
|
||||
|
||||
} // namespace pcl_wrapper
|
||||
|
||||
#endif //PCL_WRAPPER_VOXEL_FILTER_HPP
|
|
@ -1,32 +0,0 @@
|
|||
// 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
|
29
src/io.cpp
29
src/io.cpp
|
@ -1,29 +0,0 @@
|
|||
|
||||
// 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
|
|
@ -1,24 +0,0 @@
|
|||
|
||||
// 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
|
140
wrapper.cpp
140
wrapper.cpp
|
@ -1,64 +1,104 @@
|
|||
|
||||
// pcl_wrapper/src/wrapper.cpp
|
||||
#include "filter.hpp"
|
||||
#include "point_types.hpp"
|
||||
#include "cloud_handle.hpp"
|
||||
#include "voxel_filter.hpp"
|
||||
#include "io.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* create_pointcloud_xyz() {
|
||||
return new PointCloudXYZ();
|
||||
}
|
||||
|
||||
void SetInputCloudXYZ(void* obj, const float* points, int count) {
|
||||
static_cast<VoxelGridXYZBridge*>(obj)->setInput(points, count);
|
||||
void* create_pointcloud_xyzi() {
|
||||
return new PointCloudXYZI();
|
||||
}
|
||||
|
||||
void ApplyVoxelGridXYZ(void* obj, float** outPoints, int* outCount) {
|
||||
static_cast<VoxelGridXYZBridge*>(obj)->getFiltered(outPoints, outCount);
|
||||
void reserve_pointcloud_xyz(void* cloud, int count) {
|
||||
auto* pc = static_cast<PointCloudXYZ*>(cloud);
|
||||
pc->cloud->resize(count);
|
||||
}
|
||||
|
||||
void FreeVoxelGridXYZ(void* obj) {
|
||||
delete static_cast<VoxelGridXYZBridge*>(obj);
|
||||
void set_point_xyz(void* cloud, int index, float x, float y, float z) {
|
||||
auto* pc = static_cast<PointCloudXYZ*>(cloud);
|
||||
(*pc->cloud)[index].x = x;
|
||||
(*pc->cloud)[index].y = y;
|
||||
(*pc->cloud)[index].z = z;
|
||||
}
|
||||
|
||||
} // extern C
|
||||
void set_point_xyzi(void* cloud, int index, float x, float y, float z, float intensity) {
|
||||
auto* pc = static_cast<PointCloudXYZI*>(cloud);
|
||||
(*pc->cloud)[index].x = x;
|
||||
(*pc->cloud)[index].y = y;
|
||||
(*pc->cloud)[index].z = z;
|
||||
(*pc->cloud)[index].intensity = intensity;
|
||||
}
|
||||
|
||||
void delete_pointcloud(void* cloud) {
|
||||
delete static_cast<PointCloudXYZ*>(cloud); // 可根据类型再区分
|
||||
}
|
||||
|
||||
// === 滤波器相关 ===
|
||||
|
||||
void* create_voxel_filter_xyz() {
|
||||
return new VoxelGridXYZ();
|
||||
}
|
||||
|
||||
void* create_voxel_filter_xyzi() {
|
||||
return new VoxelGridXYZI();
|
||||
}
|
||||
|
||||
void set_voxel_leaf_size(void* filter, float lx, float ly, float lz) {
|
||||
auto* vf_xyz = static_cast<VoxelGridXYZ*>(filter);
|
||||
vf_xyz->setLeafSize(lx, ly, lz); // 默认按XYZ处理
|
||||
}
|
||||
|
||||
void set_voxel_input_cloud(void* filter, void* cloud) {
|
||||
auto* vf = static_cast<VoxelGridXYZ*>(filter);
|
||||
auto* pc = static_cast<PointCloudXYZ*>(cloud);
|
||||
vf->setInputCloud(pc->cloud);
|
||||
}
|
||||
|
||||
void* apply_voxel_filter_xyz(void* filter) {
|
||||
auto* vf = static_cast<VoxelGridXYZ*>(filter);
|
||||
auto* out = new PointCloudXYZ();
|
||||
out->cloud = vf->filterCloud();
|
||||
return out;
|
||||
}
|
||||
|
||||
void* apply_voxel_filter_xyzi(void* filter) {
|
||||
auto* vf = static_cast<VoxelGridXYZI*>(filter);
|
||||
auto* out = new PointCloudXYZI();
|
||||
out->cloud = vf->filterCloud();
|
||||
return out;
|
||||
}
|
||||
|
||||
void delete_voxel_filter(void* ptr) {
|
||||
delete static_cast<VoxelGridXYZ*>(ptr); // 可再细分
|
||||
}
|
||||
|
||||
// === IO相关 ===
|
||||
|
||||
bool load_pcd_xyz(const char* filename, void* out) {
|
||||
auto* pc = static_cast<PointCloudXYZ*>(out);
|
||||
return loadPCD_XYZ(filename, *pc);
|
||||
}
|
||||
|
||||
bool load_pcd_xyzi(const char* filename, void* out) {
|
||||
auto* pc = static_cast<PointCloudXYZI*>(out);
|
||||
return loadPCD_XYZI(filename, *pc);
|
||||
}
|
||||
|
||||
bool save_pcd_xyz(const char* filename, void* cloud) {
|
||||
auto* pc = static_cast<PointCloudXYZ*>(cloud);
|
||||
return savePCD_XYZ(filename, *pc);
|
||||
}
|
||||
|
||||
bool save_pcd_xyzi(const char* filename, void* cloud) {
|
||||
auto* pc = static_cast<PointCloudXYZI*>(cloud);
|
||||
return savePCD_XYZI(filename, *pc);
|
||||
}
|
||||
|
||||
}
|
||||
|
|
Loading…
Reference in New Issue