laser_to_pc_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  ROS_INFO("Started laser_to_pc_nodelet");
38  ros::init(argc,argv,"laser_to_pc_nodelet");
39 
40  ros::NodeHandle n;
41 
42  // Variables to read from launch file
43  string laser_input;
44  string pointcloud_output;
45  string frame_id;
46 
47  double min_x,min_y,max_x,max_y;
48 
49  // Declare the class node
50  laser_to_pc * las_to_pointcloud = new laser_to_pc;
51 
52  // Initialize ros parameters
53  ros::NodeHandle private_node_handle_("~");
54  private_node_handle_.param("laser_input", laser_input, string("laser_input"));
55  private_node_handle_.param("pointcloud_output", pointcloud_output, string("pointcloud_output"));
56  private_node_handle_.param("frame_id", frame_id, string("frame_id"));
57  private_node_handle_.param("min_x", min_x, double(min_x));
58  private_node_handle_.param("min_y", min_y, double(min_y));
59  private_node_handle_.param("max_x", max_x, double(max_x));
60  private_node_handle_.param("max_y", max_y, double(max_y));
61  private_node_handle_.param("min_z", las_to_pointcloud->min_z, double(las_to_pointcloud->min_z));
62  private_node_handle_.param("max_z", las_to_pointcloud->max_z, double(las_to_pointcloud->max_z));
63 
64  // Subscribe a pointcloud message
65  ros::Subscriber sub_cloud = n.subscribe(laser_input.c_str(), 1000, &laser_to_pc::filter, las_to_pointcloud);
66 
67  // Publish a pointcloud message
68  ros::Publisher pub_message = n.advertise<sensor_msgs::PointCloud2>(pointcloud_output.c_str(), 10);
69 
70  las_to_pointcloud->pub_ptr=&pub_message;
71 
72  // Pass a listener pointer and set frame_id
73  tf::TransformListener listener;
74  las_to_pointcloud->listener_ptr=&listener;
75  las_to_pointcloud->frame_id=frame_id;
76 
77  // Set the convex hull properties
78  PointXYZ point; point.z=0.0;
79  point.x=min_x; point.y=max_y;
80  las_to_pointcloud->convex_hull.points.push_back(point);
81  point.x=max_x; point.y=max_y;
82  las_to_pointcloud->convex_hull.points.push_back(point);
83  point.x=max_x; point.y=min_y;
84  las_to_pointcloud->convex_hull.points.push_back(point);
85  point.x=min_x; point.y=min_y;
86  las_to_pointcloud->convex_hull.points.push_back(point);
87  las_to_pointcloud->convex_hull.header.frame_id=frame_id;
88 
89 
90  // Main loop.
91  while (n.ok())
92  {
93  ros::spinOnce();
94  }
95 
96  return 1;
97 }
tf::TransformListener * listener_ptr
transform_listener pointer
Definition: laser_to_pc.h:78
PointCloud< PointXYZ > convex_hull
convex_hull for extraction
Definition: laser_to_pc.h:81
laser_to_pc class declaration
double min_z
z limits for extraction
Definition: laser_to_pc.h:75
ros::Publisher * pub_ptr
publisher pointer
Definition: laser_to_pc.h:64
int main(int argc, char **argv)
double max_z
Definition: laser_to_pc.h:75
void filter(const sensor_msgs::LaserScanPtr &msg)
callback function
Definition: laser_to_pc.cpp:34
string frame_id
frame id
Definition: laser_to_pc.h:72


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