Problem in implementing voxel grid filter on the point cloud using Kinect

asked 2016-07-11 23:51:33 -0500

Hashir Shafi gravatar image

I am working on ROS Indigo Igloo with platform Ubuntu 14.04. I have to implement voxel grid filter on the real time point cloud obtained by Kinect v1.1. I am following a tutorial http://aeswiki.datasys.swri.edu/rosit... from the tutorial series http://aeswiki.datasys.swri.edu/rosit... . The tutorial is written for working with a provided bag file in Exercise 4.4 but I want to implement it on the point cloud obtained by Kinect in the run time. Following is the node I am running.

#include <ros ros.h=""> #include <tf transform_datatypes.h=""> #include <tf transform_listener.h=""> #include <tf transform_broadcaster.h=""> #include <sensor_msgs pointcloud2.h=""> //hydro

// PCL specific includes #include <pcl_conversions pcl_conversions.h=""> //hydro #include "pcl_ros/transforms.h"

#include <pcl filters="" voxel_grid.h=""> //#include <pcl filters="" passthrough.h=""> //#include <pcl sample_consensus="" method_types.h=""> //#include <pcl sample_consensus="" model_types.h=""> //#include <pcl segmentation="" sac_segmentation.h=""> //#include <pcl filters="" extract_indices.h=""> //#include <pcl segmentation="" extract_clusters.h=""> //#include <pcl kdtree="" kdtree_flann.h=""> //#include <pcl filters="" statistical_outlier_removal.h="">

int main(int argc, char argv[]) { / * INITIALIZE ROS NODE */ ros::init(argc, argv, "perception_node"); ros::NodeHandle nh; ros::NodeHandle priv_nh_("~");

/* * SET UP PARAMETERS (COULD BE INPUT FROM LAUNCH FILE/TERMINAL) */ std::string cloud_topic, world_frame, camera_frame; world_frame="camera_depth_optical_frame"; camera_frame="camera_link"; cloud_topic="camera/depth_registered/points";

/* * SETUP PUBLISHERS */ ros::Publisher object_pub, cluster_pub, pose_pub; object_pub = nh.advertise<sensor_msgs::pointcloud2>("object_cluster", 1); cluster_pub = nh.advertise<sensor_msgs::pointcloud2>("primary_cluster", 1);

while (ros::ok()) { /* * LISTEN FOR POINTCLOUD */ std::string topic = nh.resolveName(cloud_topic); ROS_INFO_STREAM("Cloud service called; waiting for a PointCloud2 on topic "<< topic); sensor_msgs::PointCloud2::ConstPtr recent_cloud = ros::topic::waitForMessage<sensor_msgs::pointcloud2>(topic, nh);

/* * TRANSFORM POINTCLOUD FROM CAMERA FRAME TO WORLD FRAME */ tf::TransformListener listener; tf::StampedTransform stransform; try { listener.waitForTransform(world_frame, camera_frame, ros::Time::now(), ros::Duration(6.0)); listener.lookupTransform(world_frame, camera_frame, ros::Time(0), stransform); } catch (tf::TransformException ex) { ROS_ERROR("%s",ex.what()); } sensor_msgs::PointCloud2 transformed_cloud; pcl_ros::transformPointCloud(world_frame, *recent_cloud, transformed_cloud, listener);

/* * CONVERT POINTCLOUD ROS->PCL */ pcl::PointCloud<pcl::pointxyz> cloud; pcl::fromROSMsg (transformed_cloud, cloud);

/* ======================================== * Fill Code: VOXEL GRID * ========================================/ pcl::PointCloud<pcl::pointxyz>::Ptr cloud_ptr (new pcl::PointCloud<pcl::pointxyz> (cloud)); pcl::PointCloud<pcl::pointxyz>::Ptr cloud_voxel_filtered (new pcl::PointCloud<pcl::pointxyz> ()); pcl::VoxelGrid<pcl::pointxyz> voxel_filter; voxel_filter.setInputCloud (cloud_ptr); voxel_filter.setLeafSize (float(0.005), float(0.005), float(0.005)); voxel_filter.filter (cloud_voxel_filtered);

ROS_INFO_STREAM("Original cloud had " << cloud_ptr->size() << " points"); ROS_INFO_STREAM("Downsampled cloud with " << cloud_voxel_filtered->size() << " points");

/* ======================================== * Fill Code: PASSTHROUGH FILTER(S) * ========================================*/ //filter in x

//filter in y

//filter in z

/* ======================================== * Fill Code: CROPBOX (OPTIONAL) * ========================================*/

/* ======================================== * Fill Code: PLANE SEGEMENTATION * ========================================*/

/* ======================================== * Fill Code: PUBLISH PLANE MARKER (OPTIONAL) * ========================================*/

/* ======================================== * Fill Code: EUCLIDEAN CLUSTER EXTRACTION (OPTIONAL/RECOMMENDED) * ========================================*/

/* ======================================== * Fill Code: STATISTICAL OUTLIER REMOVAL (OPTIONAL) * ========================================*/

/* ======================================== * CONVERT POINTCLOUD PCL->ROS * PUBLISH CLOUD * Fill Code: UPDATE AS NECESSARY * ========================================/ sensor_msgs::PointCloud2::Ptr pc2_cloud (new sensor_msgs::PointCloud2); pcl::toROSMsg(cloud_voxel_filtered, *pc2_cloud); pc2_cloud->header.frame_id=world_frame; pc2_cloud->header.stamp=ros::Time::now(); object_pub.publish(pc2_cloud);

/* ======================================== * Fill Code: PUBLISH OTHER MARKERS (OPTIONAL) * ========================================*/

/* ======================================== * BROADCAST TRANSFORM (OPTIONAL) * ========================================*/

/* ======================================== * Fill Code: POLYGONAL SEGMENTATION (OPTIONAL) * ========================================*/

} return 0; }

And I am getting the following error. In the rviz window when I subscribe to ... (more)

edit retag flag offensive close merge delete