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
00027 #ifndef _points_from_volume_nodelet_CPP_
00028 #define _points_from_volume_nodelet_CPP_
00029
00036 #include <ros/ros.h>
00037 #include <points_from_volume/points_from_volume.h>
00038
00039
00040 ros::NodeHandle* p_n;
00041 ros::Publisher cloud_pub;
00042 bool defined_hull=false;
00043 double positive;
00044 double negative;
00045 bool flag;
00046
00047 points_from_volume<pcl::PointXYZ> piv;
00048
00055 void cloud_cb (const sensor_msgs::PointCloud2ConstPtr & pcmsg_in)
00056 {
00057 pcl::PointCloud<pcl::PointXYZ> pc_in;
00058 pcl::fromROSMsg(*pcmsg_in,pc_in);
00059 pcl::PointCloud<pcl::PointXYZ> pc_filtered;
00060 piv.convexhull_function(pc_in, positive, negative, flag);
00061 sensor_msgs::PointCloud2 pcmsg_out;
00062 pcl::toROSMsg(piv.get_pc_in_volume(), pcmsg_out);
00063
00064
00065 cloud_pub.publish(pcmsg_out);
00066 }
00067
00074 void cb_points_convexhull (const sensor_msgs::PointCloud2ConstPtr & pcmsg_convexhull_in)
00075 {
00076 printf("-------Flag is now True-------\n");
00077 piv.set_convex_hull(pcmsg_convexhull_in);
00078 defined_hull=true;
00079 }
00080
00081
00090 int main(int argc, char **argv)
00091 {
00092 ros::init(argc, argv, "points_from_volume_nodelet");
00093 ros::NodeHandle n("~");
00094
00095
00096 p_n=&n;
00097
00098
00099 if(!positive)
00100 {
00101 ROS_WARN_ONCE("Positive_offset not defined. Setting to default value '2.0'\n");
00102 n.param("positive_offset", positive, 2.0);
00103 }
00104 if(!negative)
00105 {
00106 ROS_WARN_ONCE("Negative_offset not defined. Setting to default value '-0.1'\n");
00107 n.param("negative_offset", negative, -0.1);
00108 }
00109 if(!flag)
00110 {
00111 ROS_WARN_ONCE("Flag_in_out not defined. Setting to default value 'false'\n");
00112 n.param("flag_in_out", flag, false);
00113 }
00114
00115
00116 ros::Subscriber sub1 = n.subscribe ("/points_convexhull", 1, cb_points_convexhull);
00117 ros::Subscriber sub2 = n.subscribe ("/point_cloud_input", 1, cloud_cb);
00118
00119 if(defined_hull==false)
00120 {
00121 ROS_WARN("No point cloud convexhull received yet...");
00122 }
00123
00124
00125 cloud_pub = n.advertise<sensor_msgs::PointCloud2>("/pcmsg_out", 1);
00126
00127 ros::Rate loop_rate(30);
00128 ros::spin();
00129 }
00130 #endif