Go to the documentation of this file.00001 #include <pcl/apps/cloud_composer/tools/voxel_grid_downsample.h>
00002 #include <pcl/apps/cloud_composer/items/cloud_item.h>
00003
00004 #include <pcl/filters/voxel_grid.h>
00005 #include <pcl/point_types.h>
00006
00007
00008
00009 Q_EXPORT_PLUGIN2(cloud_composer_voxel_grid_downsample_tool, pcl::cloud_composer::VoxelGridDownsampleToolFactory)
00010
00011
00012 pcl::cloud_composer::VoxelGridDownsampleTool::VoxelGridDownsampleTool (PropertiesModel* parameter_model, QObject* parent)
00013 : ModifyItemTool (parameter_model, parent)
00014 {
00015
00016
00017 }
00018
00019 pcl::cloud_composer::VoxelGridDownsampleTool::~VoxelGridDownsampleTool ()
00020 {
00021
00022 }
00023
00024 QList <pcl::cloud_composer::CloudComposerItem*>
00025 pcl::cloud_composer::VoxelGridDownsampleTool::performAction (ConstItemList input_data, PointTypeFlags::PointType type)
00026 {
00027 QList <CloudComposerItem*> output;
00028 const CloudComposerItem* input_item;
00029
00030 if ( input_data.size () == 0)
00031 {
00032 qCritical () << "Empty input in VoxelGridDownsampleTool!";
00033 return output;
00034 }
00035 else if ( input_data.size () > 1)
00036 {
00037 qWarning () << "Input vector has more than one item in VoxelGridDownsampleTool";
00038 }
00039 input_item = input_data.value (0);
00040
00041 if (input_item->type () == CloudComposerItem::CLOUD_ITEM)
00042 {
00043 double leaf_x = parameter_model_->getProperty("Leaf Size x").toDouble ();
00044 double leaf_y = parameter_model_->getProperty("Leaf Size y").toDouble ();
00045 double leaf_z = parameter_model_->getProperty("Leaf Size z").toDouble ();
00046
00047 pcl::PCLPointCloud2::ConstPtr input_cloud = input_item->data (ItemDataRole::CLOUD_BLOB).value <pcl::PCLPointCloud2::ConstPtr> ();
00048
00050
00051 pcl::VoxelGrid<pcl::PCLPointCloud2> vox_grid;
00052 vox_grid.setInputCloud (input_cloud);
00053 vox_grid.setLeafSize (float (leaf_x), float (leaf_y), float (leaf_z));
00054
00055
00056
00057 pcl::PCLPointCloud2::Ptr cloud_filtered (new pcl::PCLPointCloud2);
00058
00059 vox_grid.filter (*cloud_filtered);
00060
00062
00063 Eigen::Vector4f source_origin = input_item->data (ItemDataRole::ORIGIN).value<Eigen::Vector4f> ();
00064 Eigen::Quaternionf source_orientation = input_item->data (ItemDataRole::ORIENTATION).value<Eigen::Quaternionf> ();
00065
00066 CloudItem* cloud_item = new CloudItem (input_item->text () + tr (" vox ds")
00067 , cloud_filtered
00068 , source_origin
00069 , source_orientation);
00070
00071
00072 output.append (cloud_item);
00073 }
00074 else
00075 {
00076 qDebug () << "Input item in VoxelGridDownsampleTool is not a cloud!!!";
00077 }
00078
00079
00080 return output;
00081 }
00082
00084 pcl::cloud_composer::PropertiesModel*
00085 pcl::cloud_composer::VoxelGridDownsampleToolFactory::createToolParameterModel (QObject* parent)
00086 {
00087 PropertiesModel* parameter_model = new PropertiesModel(parent);
00088
00089 parameter_model->addProperty ("Leaf Size x", 0.01, Qt::ItemIsEditable | Qt::ItemIsEnabled);
00090 parameter_model->addProperty ("Leaf Size y", 0.01, Qt::ItemIsEditable | Qt::ItemIsEnabled);
00091 parameter_model->addProperty ("Leaf Size z", 0.01, Qt::ItemIsEditable | Qt::ItemIsEnabled);
00092
00093
00094 return parameter_model;
00095 }