points_from_volume_nodelet.cpp
Go to the documentation of this file.
1 /**************************************************************************************************
2  Software License Agreement (BSD License)
3 
4  Copyright (c) 2011-2013, LAR toolkit developers - University of Aveiro - http://lars.mec.ua.pt
5  All rights reserved.
6 
7  Redistribution and use in source and binary forms, with or without modification, are permitted
8  provided that the following conditions are met:
9 
10  *Redistributions of source code must retain the above copyright notice, this list of
11  conditions and the following disclaimer.
12  *Redistributions in binary form must reproduce the above copyright notice, this list of
13  conditions and the following disclaimer in the documentation and/or other materials provided
14  with the distribution.
15  *Neither the name of the University of Aveiro nor the names of its contributors may be used to
16  endorse or promote products derived from this software without specific prior written permission.
17 
18  THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS" AND ANY EXPRESS OR
19  IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND
20  FITNESS FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT HOLDER OR
21  CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL
22  DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS OF USE,
23  DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER
24  IN CONTRACT, STRICT LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY OUT
25  OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE.
26 ***************************************************************************************************/
27 #ifndef _points_from_volume_nodelet_CPP_
28 #define _points_from_volume_nodelet_CPP_
29 
36 #include <ros/ros.h>
38 
39 // Global Vars
40 ros::NodeHandle* p_n;
41 ros::Publisher cloud_pub;
42 bool defined_hull=false;
43 double positive;
44 double negative;
45 bool flag;
46 // Class member
48 
55 void cloud_cb (const sensor_msgs::PointCloud2ConstPtr & pcmsg_in)
56 {
57  pcl::PointCloud<pcl::PointXYZ> pc_in;
58  pcl::PCLPointCloud2 pcl_pc;
59  pcl_conversions::toPCL(*pcmsg_in, pcl_pc);
60  pcl::fromPCLPointCloud2(pcl_pc, pc_in);
61 
62  pcl::PointCloud<pcl::PointXYZ> pc_filtered;
64  sensor_msgs::PointCloud2 pcmsg_out;
65  pcl::toROSMsg(piv.get_pc_in_volume(), pcmsg_out);
66  // Uncomment the next line to print the point cloud size
67  // std::cout<<"Num points "<<pc_filtered.points.size()<<std::endl;
68  cloud_pub.publish(pcmsg_out);
69 }
70 
77 void cb_points_convexhull (const sensor_msgs::PointCloud2ConstPtr & pcmsg_convexhull_in)
78 {
79  printf("-------Flag is now True-------\n");
80  piv.set_convex_hull(pcmsg_convexhull_in);
81  defined_hull=true;
82 }
83 
84 
93 int main(int argc, char **argv)
94 {
95  ros::init(argc, argv, "points_from_volume_nodelet");
96  ros::NodeHandle n("~");
97 // tf::TransformListener listener(n,ros::Duration(10));
98 // p_listener=&listener;
99  p_n=&n;
100 
101  // Set default values on parameters
102  if(!positive)
103  {
104  ROS_WARN_ONCE("Positive_offset not defined. Setting to default value '2.0'\n");
105  n.param("positive_offset", positive, 2.0);
106  }
107  if(!negative)
108  {
109  ROS_WARN_ONCE("Negative_offset not defined. Setting to default value '-0.1'\n");
110  n.param("negative_offset", negative, -0.1);
111  }
112  if(!flag)
113  {
114  ROS_WARN_ONCE("Flag_in_out not defined. Setting to default value 'false'\n");
115  n.param("flag_in_out", flag, false);
116  }
117 
118  // Point clouds subscription
119  ros::Subscriber sub1 = n.subscribe ("/points_convexhull", 1, cb_points_convexhull);
120  ros::Subscriber sub2 = n.subscribe ("/point_cloud_input", 1, cloud_cb);
121 
122  if(defined_hull==false)
123  {
124  ROS_WARN("No point cloud convexhull received yet...");
125  }
126 
127  // Pubishes the point cloud
128  cloud_pub = n.advertise<sensor_msgs::PointCloud2>("/pcmsg_out", 1);
129 
130  ros::Rate loop_rate(30);
131  ros::spin();
132 }
133 #endif
void cb_points_convexhull(const sensor_msgs::PointCloud2ConstPtr &pcmsg_convexhull_in)
ConvexHull callback.
t_func_output convexhull_function(pcl::PointCloud< T > &pc_in, double positive_offset, double negative_offset, bool flag_in_out)
Extract points from the pcl that are inside the convexhull.
points_from_volume< pcl::PointXYZ > piv
void cloud_cb(const sensor_msgs::PointCloud2ConstPtr &pcmsg_in)
Point Cloud callback.
int main(int argc, char **argv)
Main code of the nodelet.
t_func_output set_convex_hull(pcl::PointCloud< T > &pc_in)
Set the convexhull.
pcl::PointCloud< T > get_pc_in_volume()
Points in the desired volume.
ros::NodeHandle * p_n
ros::Publisher cloud_pub
points_from_volume class declaration and auxiliary types


points_from_volume
Author(s): Joel Pereira
autogenerated on Mon Mar 2 2015 01:32:40