00001
00002
00003
00004
00005
00006
00007
00008
00009
00010
00011
00012
00013
00014
00015
00016
00017
00018
00019
00020
00021
00022
00023
00024
00025
00026
00034 #include <stdio.h>
00035 #include <ros/ros.h>
00036 #include <visualization_msgs/Marker.h>
00037 #include <sensor_msgs/LaserScan.h>
00038 #include <sensor_msgs/PointCloud2.h>
00039 #include <tf/transform_listener.h>
00040 #include <pcl_ros/transforms.h>
00041 #include <pcl/ros/conversions.h>
00042 #include <pcl/point_cloud.h>
00043 #include <pcl/point_types.h>
00044 #include <pcl/segmentation/extract_polygonal_prism_data.h>
00045 #include <pcl/filters/extract_indices.h>
00046 #include <pcl/filters/project_inliers.h>
00047 #include <pcl/filters/voxel_grid.h>
00048 #include <points_from_volume/points_from_volume.h>
00049 #define PFLN printf("FILE %s LINE %d\n",__FILE__, __LINE__);
00050
00051
00052 using namespace std;
00053
00054
00055 ros::Publisher cloud_pub;
00056 ros::NodeHandle* p_n;
00057
00064 void conversion (const sensor_msgs::PointCloud2ConstPtr & pcmsg_in)
00065 {
00066 pcl::PointCloud<pcl::PointXYZ> pc_cut;
00067 pcl::PointCloud<pcl::PointXYZ> processed_pc;
00068 sensor_msgs::PointCloud2 pcmsg_out;
00069
00070 pcl::fromROSMsg(*pcmsg_in,pc_cut);
00071 pc_cut.header.frame_id=pcmsg_in->header.frame_id;
00072
00073 for (int i=0;i<(int)pc_cut.points.size();i++)
00074 {
00075 if (pc_cut.points[i].z>0.75 && pc_cut.points[i].z<1.5)
00076 {
00077 processed_pc.push_back(pc_cut.points[i]);
00078 }
00079 }
00080 processed_pc.header.frame_id=pc_cut.header.frame_id;
00081 pcl::toROSMsg(processed_pc,pcmsg_out);
00082
00083 pcmsg_out.header.stamp=pcmsg_in->header.stamp;
00084 cloud_pub.publish(pcmsg_out);
00085 }
00086
00087
00088
00095 int main(int argc, char **argv)
00096 {
00097 ros::init(argc, argv, "kinect_freq_mod");
00098 ros::NodeHandle n;
00099 ros::Rate loop_rate(10);
00100 p_n=&n;
00101
00102
00103 ros::Subscriber sub = n.subscribe ("/point_cloud_from_kinect", 1, conversion);
00104
00105
00106 cloud_pub = n.advertise<sensor_msgs::PointCloud2>("/point_cloud_input", 1);
00107
00108 while(ros::ok())
00109 {
00110 ros::spinOnce();
00111 loop_rate.sleep();
00112 }
00113 return 0;
00114 }