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
pointcloud_to_laserscan::PointCloudToLaserScanNodelet::message_filter_
boost::shared_ptr< MessageFilter > message_filter_
Definition: pointcloud_to_laserscan_nodelet.h:84
pointcloud_to_laserscan::PointCloudToLaserScanNodelet::PointCloudToLaserScanNodelet
PointCloudToLaserScanNodelet()
Definition: pointcloud_to_laserscan_nodelet.cpp:51
pointcloud_to_laserscan::PointCloudToLaserScanNodelet::nh_
ros::NodeHandle nh_
Definition: pointcloud_to_laserscan_nodelet.h:77
pointcloud_to_laserscan::PointCloudToLaserScanNodelet::inf_epsilon_
double inf_epsilon_
Definition: pointcloud_to_laserscan_nodelet.h:92
ros::Publisher
tf2_ros::MessageFilter
boost::shared_ptr< tf2_ros::Buffer >
pointcloud_to_laserscan::PointCloudToLaserScanNodelet::tf2_listener_
boost::shared_ptr< tf2_ros::TransformListener > tf2_listener_
Definition: pointcloud_to_laserscan_nodelet.h:82
ros.h
pointcloud_to_laserscan::PointCloudToLaserScanNodelet::min_height_
double min_height_
Definition: pointcloud_to_laserscan_nodelet.h:90
pointcloud_to_laserscan::PointCloudToLaserScanNodelet::scan_time_
double scan_time_
Definition: pointcloud_to_laserscan_nodelet.h:90
tf2_ros::filter_failure_reasons::FilterFailureReason
FilterFailureReason
pointcloud_to_laserscan::PointCloudToLaserScanNodelet::max_height_
double max_height_
Definition: pointcloud_to_laserscan_nodelet.h:90
buffer.h
pointcloud_to_laserscan
Definition: laserscan_to_pointcloud_nodelet.h:55
pointcloud_to_laserscan::PointCloudToLaserScanNodelet::input_queue_size_
unsigned int input_queue_size_
Definition: pointcloud_to_laserscan_nodelet.h:87
message_filters::Subscriber< sensor_msgs::PointCloud2 >
pointcloud_to_laserscan::PointCloudToLaserScanNodelet::angle_max_
double angle_max_
Definition: pointcloud_to_laserscan_nodelet.h:90
pointcloud_to_laserscan::PointCloudToLaserScanNodelet::range_min_
double range_min_
Definition: pointcloud_to_laserscan_nodelet.h:90
pointcloud_to_laserscan::PointCloudToLaserScanNodelet::private_nh_
ros::NodeHandle private_nh_
Definition: pointcloud_to_laserscan_nodelet.h:77
message_filter.h
subscriber.h
pointcloud_to_laserscan::PointCloudToLaserScanNodelet::pub_
ros::Publisher pub_
Definition: pointcloud_to_laserscan_nodelet.h:78
pointcloud_to_laserscan::PointCloudToLaserScanNodelet::angle_increment_
double angle_increment_
Definition: pointcloud_to_laserscan_nodelet.h:90
pointcloud_to_laserscan::PointCloudToLaserScanNodelet::tf2_
boost::shared_ptr< tf2_ros::Buffer > tf2_
Definition: pointcloud_to_laserscan_nodelet.h:81
pointcloud_to_laserscan::PointCloudToLaserScanNodelet::connect_mutex_
boost::mutex connect_mutex_
Definition: pointcloud_to_laserscan_nodelet.h:79
pointcloud_to_laserscan::PointCloudToLaserScanNodelet::onInit
virtual void onInit()
Definition: pointcloud_to_laserscan_nodelet.cpp:55
pointcloud_to_laserscan::PointCloudToLaserScanNodelet::connectCb
void connectCb()
Definition: pointcloud_to_laserscan_nodelet.cpp:115
pointcloud_to_laserscan::PointCloudToLaserScanNodelet::cloudCb
void cloudCb(const sensor_msgs::PointCloud2ConstPtr &cloud_msg)
Definition: pointcloud_to_laserscan_nodelet.cpp:144
pointcloud_to_laserscan::PointCloudToLaserScanNodelet
Definition: pointcloud_to_laserscan_nodelet.h:61
transform_listener.h
nodelet::Nodelet
pointcloud_to_laserscan::PointCloudToLaserScanNodelet::failureCb
void failureCb(const sensor_msgs::PointCloud2ConstPtr &cloud_msg, tf2_ros::filter_failure_reasons::FilterFailureReason reason)
Definition: pointcloud_to_laserscan_nodelet.cpp:135
nodelet.h
pointcloud_to_laserscan::PointCloudToLaserScanNodelet::disconnectCb
void disconnectCb()
Definition: pointcloud_to_laserscan_nodelet.cpp:125
pointcloud_to_laserscan::PointCloudToLaserScanNodelet::sub_
message_filters::Subscriber< sensor_msgs::PointCloud2 > sub_
Definition: pointcloud_to_laserscan_nodelet.h:83
pointcloud_to_laserscan::PointCloudToLaserScanNodelet::target_frame_
std::string target_frame_
Definition: pointcloud_to_laserscan_nodelet.h:88
pointcloud_to_laserscan::PointCloudToLaserScanNodelet::range_max_
double range_max_
Definition: pointcloud_to_laserscan_nodelet.h:90
pointcloud_to_laserscan::PointCloudToLaserScanNodelet::use_inf_
bool use_inf_
Definition: pointcloud_to_laserscan_nodelet.h:91
pointcloud_to_laserscan::PointCloudToLaserScanNodelet::angle_min_
double angle_min_
Definition: pointcloud_to_laserscan_nodelet.h:90
pointcloud_to_laserscan::MessageFilter
tf2_ros::MessageFilter< sensor_msgs::LaserScan > MessageFilter
Definition: laserscan_to_pointcloud_nodelet.h:57
pointcloud_to_laserscan::PointCloudToLaserScanNodelet::tolerance_
double tolerance_
Definition: pointcloud_to_laserscan_nodelet.h:89
ros::NodeHandle


pointcloud_to_laserscan
Author(s): Paul Bovbel , Tully Foote
autogenerated on Wed Mar 2 2022 00:44:25