laserscan_to_pointcloud_nodelet.h
Go to the documentation of this file.
1 /*
2  * Software License Agreement (BSD License)
3  *
4  * Copyright (c) 2019, Eurotec, Netherlands
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: Rein Appeldoorn
39  */
40 
41 #ifndef POINTCLOUD_TO_LASERSCAN_LASERSCAN_TO_POINTCLOUD_NODELET_H
42 #define POINTCLOUD_TO_LASERSCAN_LASERSCAN_TO_POINTCLOUD_NODELET_H
43 
44 #include <boost/thread/mutex.hpp>
47 #include <nodelet/nodelet.h>
48 #include <ros/ros.h>
49 #include <sensor_msgs/LaserScan.h>
50 #include <string>
51 #include <tf2_ros/buffer.h>
52 #include <tf2_ros/message_filter.h>
54 
56 {
58 
62 {
63 public:
65 
66 private:
67  virtual void onInit();
68 
69  void scanCallback(const sensor_msgs::LaserScanConstPtr& scan_msg);
70  void failureCallback(const sensor_msgs::LaserScanConstPtr& scan_msg,
72 
73  void connectCb();
74  void disconnectCb();
75 
79  boost::mutex connect_mutex_;
80 
85 
87 
88  // ROS Parameters
89  unsigned int input_queue_size_;
90  std::string target_frame_;
92 };
93 
94 } // namespace pointcloud_to_laserscan
95 
96 #endif // POINTCLOUD_TO_LASERSCAN_LASERSCAN_TO_POINTCLOUD_NODELET_H
pointcloud_to_laserscan::LaserScanToPointCloudNodelet::message_filter_
boost::shared_ptr< MessageFilter > message_filter_
Definition: laserscan_to_pointcloud_nodelet.h:84
pointcloud_to_laserscan::LaserScanToPointCloudNodelet
The PointCloudToLaserScanNodelet class to process incoming laserscans into pointclouds.
Definition: laserscan_to_pointcloud_nodelet.h:61
pointcloud_to_laserscan::LaserScanToPointCloudNodelet::tf2_
boost::shared_ptr< tf2_ros::Buffer > tf2_
Definition: laserscan_to_pointcloud_nodelet.h:81
ros::Publisher
tf2_ros::MessageFilter
boost::shared_ptr< tf2_ros::Buffer >
pointcloud_to_laserscan::LaserScanToPointCloudNodelet::projector_
laser_geometry::LaserProjection projector_
Definition: laserscan_to_pointcloud_nodelet.h:86
laser_geometry::LaserProjection
ros.h
tf2_ros::filter_failure_reasons::FilterFailureReason
FilterFailureReason
buffer.h
pointcloud_to_laserscan
Definition: laserscan_to_pointcloud_nodelet.h:55
pointcloud_to_laserscan::LaserScanToPointCloudNodelet::target_frame_
std::string target_frame_
Definition: laserscan_to_pointcloud_nodelet.h:90
message_filters::Subscriber< sensor_msgs::LaserScan >
pointcloud_to_laserscan::LaserScanToPointCloudNodelet::nh_
ros::NodeHandle nh_
Definition: laserscan_to_pointcloud_nodelet.h:76
laser_geometry.h
message_filter.h
subscriber.h
pointcloud_to_laserscan::LaserScanToPointCloudNodelet::scanCallback
void scanCallback(const sensor_msgs::LaserScanConstPtr &scan_msg)
Definition: laserscan_to_pointcloud_nodelet.cpp:132
pointcloud_to_laserscan::LaserScanToPointCloudNodelet::sub_
message_filters::Subscriber< sensor_msgs::LaserScan > sub_
Definition: laserscan_to_pointcloud_nodelet.h:83
transform_listener.h
nodelet::Nodelet
pointcloud_to_laserscan::LaserScanToPointCloudNodelet::connect_mutex_
boost::mutex connect_mutex_
Definition: laserscan_to_pointcloud_nodelet.h:79
pointcloud_to_laserscan::LaserScanToPointCloudNodelet::private_nh_
ros::NodeHandle private_nh_
Definition: laserscan_to_pointcloud_nodelet.h:77
pointcloud_to_laserscan::LaserScanToPointCloudNodelet::tf2_listener_
boost::shared_ptr< tf2_ros::TransformListener > tf2_listener_
Definition: laserscan_to_pointcloud_nodelet.h:82
pointcloud_to_laserscan::LaserScanToPointCloudNodelet::input_queue_size_
unsigned int input_queue_size_
Definition: laserscan_to_pointcloud_nodelet.h:89
nodelet.h
pointcloud_to_laserscan::LaserScanToPointCloudNodelet::pub_
ros::Publisher pub_
Definition: laserscan_to_pointcloud_nodelet.h:78
pointcloud_to_laserscan::LaserScanToPointCloudNodelet::disconnectCb
void disconnectCb()
Definition: laserscan_to_pointcloud_nodelet.cpp:113
pointcloud_to_laserscan::LaserScanToPointCloudNodelet::onInit
virtual void onInit()
Definition: laserscan_to_pointcloud_nodelet.cpp:54
pointcloud_to_laserscan::LaserScanToPointCloudNodelet::connectCb
void connectCb()
Definition: laserscan_to_pointcloud_nodelet.cpp:103
pointcloud_to_laserscan::LaserScanToPointCloudNodelet::failureCallback
void failureCallback(const sensor_msgs::LaserScanConstPtr &scan_msg, tf2_ros::filter_failure_reasons::FilterFailureReason reason)
Definition: laserscan_to_pointcloud_nodelet.cpp:123
pointcloud_to_laserscan::MessageFilter
tf2_ros::MessageFilter< sensor_msgs::LaserScan > MessageFilter
Definition: laserscan_to_pointcloud_nodelet.h:57
pointcloud_to_laserscan::LaserScanToPointCloudNodelet::LaserScanToPointCloudNodelet
LaserScanToPointCloudNodelet()
Definition: laserscan_to_pointcloud_nodelet.cpp:50
ros::NodeHandle
pointcloud_to_laserscan::LaserScanToPointCloudNodelet::transform_tolerance_
double transform_tolerance_
Definition: laserscan_to_pointcloud_nodelet.h:91


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