filtering_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 ***************************************************************************************************/
34 
35 int main(int argc, char **argv)
36 {
37  // Set up ROS.
38  ros::init(argc, argv, "listener");
39  ros::NodeHandle n;
40 
41  // Variables from launch file
42  string pointcloud_input;
43  string pointcloud_output;
44  string laser_input;
45  double min_x, max_x, min_y, max_y;
46 
47  // Create a filtering class object and make the proper setup
49 
50  // Initialize ros parameters
51  ros::NodeHandle private_node_handle_("~");
52  private_node_handle_.param("pointcloud_input", pointcloud_input, string("pointcloud_input"));
53  private_node_handle_.param("pointcloud_output", pointcloud_output, string("pointcloud_output"));
54  private_node_handle_.param("frame_id", filt->frame_id, string("frame_id"));
55 
56  private_node_handle_.param("voxel_size", filt->voxel_size, double(filt->voxel_size));
57  private_node_handle_.param("min_x", min_x, double(min_x));
58  private_node_handle_.param("max_x", max_x, double(max_x));
59  private_node_handle_.param("min_y", min_y, double(min_y));
60  private_node_handle_.param("max_y", max_y, double(max_y));
61  private_node_handle_.param("min_z", filt->min_z, double(filt->min_z));
62  private_node_handle_.param("max_z", filt->max_z, double(filt->max_z));
63 
64  // Set the convex hull properties
65  PointXYZRGB point; point.z=0.0;
66  point.x=min_x; point.y=max_y;
67  filt->convex_hull.points.push_back(point);
68  point.x=max_x; point.y=max_y;
69  filt->convex_hull.points.push_back(point);
70  point.x=max_x; point.y=min_y;
71  filt->convex_hull.points.push_back(point);
72  point.x=min_x; point.y=min_y;
73  filt->convex_hull.points.push_back(point);
74  filt->convex_hull.header.frame_id=filt->frame_id;
75 
76 
77  // Subscribe a pointcloud message
78  ros::Subscriber sub_cloud = n.subscribe(pointcloud_input.c_str(), 1000, &filtering<PointXYZRGB>::filter, filt);
79 
80  // Publish a pointcloud message
81  ros::Publisher pub_message = n.advertise<sensor_msgs::PointCloud2>(pointcloud_output.c_str(), 10);
82 
83  // Pass a pub pointer to the class object
84  filt->pub_ptr=&pub_message;
85 
86  // Pass a listener transform to class object
87  tf::TransformListener listener_center_bumper;
88  filt->transform_listener_ptr=&listener_center_bumper;
89 
90  // Main loop.
91  while (n.ok())
92  {
93  ros::spinOnce();
94  }
95 
96  return 0;
97 }
double min_z
Minimum value for Z pointcloud.
Definition: filtering.h:93
double max_z
Maximum value for Z pointcloud.
Definition: filtering.h:90
string frame_id
The frame_id to transform.
Definition: filtering.h:102
int main(int argc, char **argv)
tf::TransformListener * transform_listener_ptr
Pointer to a transform listener.
Definition: filtering.h:99
ros::Publisher * pub_ptr
Pointer to pointcloud publisher.
Definition: filtering.h:96
double voxel_size
Voxel grid size.
Definition: filtering.h:87
filtering class declaration
PointCloud< T > convex_hull
The convex hull for cloud extraction.
Definition: filtering.h:84


pointcloud_segmentation
Author(s): Tiago Talhada
autogenerated on Mon Mar 2 2015 01:32:39