10 #include <pcl/io/pcd_io.h> 11 #include <pcl/point_types.h> 12 #include <pcl/filters/approximate_voxel_grid.h> 14 #include "hrpsys/idl/pointcloud.hh" 18 static const char*
spec[] =
20 "implementation_id",
"ApproximateVoxelGridFilter",
21 "type_name",
"ApproximateVoxelGridFilter",
22 "description",
"Voxel Grid Filter",
23 "version", HRPSYS_PACKAGE_VERSION,
25 "category",
"example",
26 "activity_type",
"DataFlowComponent",
29 "lang_type",
"compile",
31 "conf.default.size",
"0.01",
32 "conf.default.debugLevel",
"0",
41 m_originalIn(
"original", m_original),
42 m_filteredOut(
"filtered", m_filtered),
87 m_filtered.fields[0].data_type = PointCloudTypes::FLOAT32;
91 m_filtered.fields[1].data_type = PointCloudTypes::FLOAT32;
95 m_filtered.fields[2].data_type = PointCloudTypes::FLOAT32;
129 std::cout <<
m_profile.instance_name<<
": onActivated(" << ec_id <<
")" << std::endl;
135 std::cout <<
m_profile.instance_name<<
": onDeactivated(" << ec_id <<
")" << std::endl;
142 std::cout <<
m_profile.instance_name<<
": onExecute(" << ec_id <<
")" << std::endl;
154 pcl::PointCloud<pcl::PointXYZ>::Ptr cloud (
new pcl::PointCloud<pcl::PointXYZ>);
155 pcl::PointCloud<pcl::PointXYZ>::Ptr cloud_filtered (
new pcl::PointCloud<pcl::PointXYZ>);
159 float *src = (
float *)
m_original.data.get_buffer();
160 for (
unsigned int i=0;
i<cloud->points.size();
i++){
161 cloud->points[
i].x = src[0];
162 cloud->points[
i].y = src[1];
163 cloud->points[
i].z = src[2];
168 pcl::ApproximateVoxelGrid<pcl::PointXYZ> sor;
169 sor.setInputCloud (cloud);
171 sor.filter(*cloud_filtered);
173 std::cout << cloud->points.size() <<
" points are reduced to " 174 << cloud_filtered->points.size() <<
" points" << std::endl;
179 m_filtered.width = cloud_filtered->points.size();
183 float *dst = (
float *)
m_filtered.data.get_buffer();
184 for (
unsigned int i=0;
i<cloud_filtered->points.size();
i++){
185 dst[0] = cloud_filtered->points[
i].x;
186 dst[1] = cloud_filtered->points[
i].y;
187 dst[2] = cloud_filtered->points[
i].z;
240 RTC::Create<ApproximateVoxelGridFilter>,
241 RTC::Delete<ApproximateVoxelGridFilter>);
ComponentProfile m_profile
Moving Least Squares Filter.
png_infop png_charpp int png_charpp profile
virtual ~ApproximateVoxelGridFilter()
Destructor.
ApproximateVoxelGridFilter(RTC::Manager *manager)
Constructor.
PointCloudTypes::PointCloud m_original
OutPort< PointCloudTypes::PointCloud > m_filteredOut
coil::Properties & getProperties()
bool addOutPort(const char *name, OutPortBase &outport)
ExecutionContextHandle_t UniqueId
bool bindParameter(const char *param_name, VarType &var, const char *def_val, bool(*trans)(VarType &, const char *)=coil::stringTo)
virtual RTC::ReturnCode_t onExecute(RTC::UniqueId ec_id)
PointCloudTypes::PointCloud m_filtered
virtual RTC::ReturnCode_t onDeactivated(RTC::UniqueId ec_id)
virtual RTC::ReturnCode_t onInitialize()
virtual bool write(DataType &value)
static const char * spec[]
InPort< PointCloudTypes::PointCloud > m_originalIn
bool addInPort(const char *name, InPortBase &inport)
bool registerFactory(coil::Properties &profile, RtcNewFunc new_func, RtcDeleteFunc delete_func)
virtual RTC::ReturnCode_t onActivated(RTC::UniqueId ec_id)
void ApproximateVoxelGridFilterInit(RTC::Manager *manager)