pointcloud_to_laserscan_nodelet.h
Go to the documentation of this file.
1 /*
2  * Software License Agreement (BSD License)
3  *
4  * Copyright (c) 2010-2012, Willow Garage, Inc.
5  * All rights reserved.
6  *
7  * Redistribution and use in source and binary forms, with or without
8  * modification, are permitted provided that the following conditions
9  * are met:
10  *
11  * * Redistributions of source code must retain the above copyright
12  * notice, this list of conditions and the following disclaimer.
13  * * Redistributions in binary form must reproduce the above
14  * copyright notice, this list of conditions and the following
15  * disclaimer in the documentation and/or other materials provided
16  * with the distribution.
17  * * Neither the name of Willow Garage, Inc. nor the names of its
18  * contributors may be used to endorse or promote products derived
19  * from this software without specific prior written permission.
20  *
21  * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
22  * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
23  * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
24  * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
25  * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
26  * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
27  * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES;
28  * LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER
29  * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
30  * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
31  * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
32  * POSSIBILITY OF SUCH DAMAGE.
33  *
34  *
35  */
36 
37 /*
38  * Author: Paul Bovbel
39  */
40 
41 #ifndef POINTCLOUD_TO_LASERSCAN_POINTCLOUD_TO_LASERSCAN_NODELET_H
42 #define POINTCLOUD_TO_LASERSCAN_POINTCLOUD_TO_LASERSCAN_NODELET_H
43 
44 #include <boost/thread/mutex.hpp>
46 #include <nodelet/nodelet.h>
47 #include <ros/ros.h>
48 #include <sensor_msgs/PointCloud2.h>
49 #include <string>
50 #include <tf2_ros/buffer.h>
51 #include <tf2_ros/message_filter.h>
53 
55 {
62 {
63 public:
65 
66 private:
67  virtual void onInit();
68 
69  void cloudCb(const sensor_msgs::PointCloud2ConstPtr& cloud_msg);
70  void failureCb(const sensor_msgs::PointCloud2ConstPtr& cloud_msg,
72 
73  void connectCb();
74 
75  void disconnectCb();
76 
79  boost::mutex connect_mutex_;
80 
85 
86  // ROS Parameters
87  unsigned int input_queue_size_;
88  std::string target_frame_;
89  double tolerance_;
91  bool use_inf_;
92  double inf_epsilon_;
93 };
94 
95 } // namespace pointcloud_to_laserscan
96 
97 #endif // POINTCLOUD_TO_LASERSCAN_POINTCLOUD_TO_LASERSCAN_NODELET_H
void failureCb(const sensor_msgs::PointCloud2ConstPtr &cloud_msg, tf2_ros::filter_failure_reasons::FilterFailureReason reason)
message_filters::Subscriber< sensor_msgs::PointCloud2 > sub_
void cloudCb(const sensor_msgs::PointCloud2ConstPtr &cloud_msg)
boost::shared_ptr< tf2_ros::TransformListener > tf2_listener_
tf2_ros::MessageFilter< sensor_msgs::LaserScan > MessageFilter


pointcloud_to_laserscan
Author(s): Paul Bovbel , Tully Foote
autogenerated on Mon Feb 28 2022 23:13:15