include
jsk_pcl_ros_utils
delay_pointcloud.h
Go to the documentation of this file.
1
// -*- mode: C++ -*-
2
/*********************************************************************
3
* Software License Agreement (BSD License)
4
*
5
* Copyright (c) 2014, JSK Lab
6
* All rights reserved.
7
*
8
* Redistribution and use in source and binary forms, with or without
9
* modification, are permitted provided that the following conditions
10
* are met:
11
*
12
* * Redistributions of source code must retain the above copyright
13
* notice, this list of conditions and the following disclaimer.
14
* * Redistributions in binary form must reproduce the above
15
* copyright notice, this list of conditions and the following
16
* disclaimer in the documentation and/or other materials provided
17
* with the distribution.
18
* * Neither the name of the JSK Lab nor the names of its
19
* contributors may be used to endorse or promote products derived
20
* from this software without specific prior written permission.
21
*
22
* THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
23
* "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
24
* LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
25
* FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
26
* COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
27
* INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
28
* BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES;
29
* LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER
30
* CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
31
* LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
32
* ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
33
* POSSIBILITY OF SUCH DAMAGE.
34
*********************************************************************/
35
36
#ifndef JSK_PCL_ROS_UTILS_DELAY_POINTCLOUD_H_
37
#define JSK_PCL_ROS_UTILS_DELAY_POINTCLOUD_H_
38
39
#include <
pcl_ros/pcl_nodelet.h
>
40
#include <sensor_msgs/PointCloud.h>
41
#include "jsk_topic_tools/connection_based_nodelet.h"
42
43
#include "jsk_pcl_ros_utils/DelayPointCloudConfig.h"
44
#include <dynamic_reconfigure/server.h>
45
46
#include <
message_filters/subscriber.h
>
47
#include <
message_filters/time_sequencer.h
>
48
49
namespace
jsk_pcl_ros_utils
50
{
51
52
class
DelayPointCloud:
public
jsk_topic_tools::ConnectionBasedNodelet
53
{
54
55
public
:
56
57
typedef
jsk_pcl_ros_utils::DelayPointCloudConfig
Config
;
58
59
protected
:
60
virtual
void
onInit
();
61
virtual
void
delay
(
const
sensor_msgs::PointCloud2::ConstPtr& msg);
62
virtual
void
subscribe
();
63
virtual
void
unsubscribe
();
64
65
boost::mutex
mutex_
;
66
double
delay_time_
;
67
int
queue_size_
;
68
ros::Publisher
pub_
;
69
message_filters::Subscriber<sensor_msgs::PointCloud2>
sub_
;
70
boost::shared_ptr<message_filters::TimeSequencer<sensor_msgs::PointCloud2>
>
time_sequencer_
;
71
73
// dynamic reconfigure
75
boost::shared_ptr <dynamic_reconfigure::Server<Config>
>
srv_
;
76
void
configCallback
(
Config
&config, uint32_t level);
77
78
private
:
79
80
};
81
82
}
83
84
85
#endif
86
jsk_pcl_ros_utils
Definition:
add_point_indices.h:51
jsk_pcl_ros_utils::DelayPointCloud::Config
jsk_pcl_ros_utils::DelayPointCloudConfig Config
Definition:
delay_pointcloud.h:121
ros::Publisher
boost::shared_ptr
jsk_pcl_ros_utils::DelayPointCloud::pub_
ros::Publisher pub_
Definition:
delay_pointcloud.h:132
jsk_pcl_ros_utils::DelayPointCloud::srv_
boost::shared_ptr< dynamic_reconfigure::Server< Config > > srv_
Definition:
delay_pointcloud.h:139
jsk_pcl_ros_utils::DelayPointCloud::sub_
message_filters::Subscriber< sensor_msgs::PointCloud2 > sub_
Definition:
delay_pointcloud.h:133
jsk_pcl_ros_utils::DelayPointCloud::time_sequencer_
boost::shared_ptr< message_filters::TimeSequencer< sensor_msgs::PointCloud2 > > time_sequencer_
Definition:
delay_pointcloud.h:134
message_filters::Subscriber< sensor_msgs::PointCloud2 >
pcl_nodelet.h
jsk_pcl_ros_utils::DelayPointCloud::unsubscribe
virtual void unsubscribe()
Definition:
delay_pointcloud_nodelet.cpp:110
jsk_pcl_ros_utils::DelayPointCloud::mutex_
boost::mutex mutex_
Definition:
delay_pointcloud.h:129
jsk_pcl_ros_utils::DelayPointCloud::onInit
virtual void onInit()
Definition:
delay_pointcloud_nodelet.cpp:73
subscriber.h
jsk_pcl_ros_utils::DelayPointCloud::delay
virtual void delay(const sensor_msgs::PointCloud2::ConstPtr &msg)
Definition:
delay_pointcloud_nodelet.cpp:96
jsk_pcl_ros_utils::DelayPointCloud::delay_time_
double delay_time_
Definition:
delay_pointcloud.h:130
jsk_pcl_ros_utils::DelayPointCloud::subscribe
virtual void subscribe()
Definition:
delay_pointcloud_nodelet.cpp:103
jsk_pcl_ros_utils::DelayPointCloud::configCallback
void configCallback(Config &config, uint32_t level)
Definition:
delay_pointcloud_nodelet.cpp:88
jsk_pcl_ros_utils::DelayPointCloud::queue_size_
int queue_size_
Definition:
delay_pointcloud.h:131
time_sequencer.h
jsk_pcl_ros_utils
Author(s): Yohei Kakiuchi
autogenerated on Fri May 16 2025 03:11:43