normal_concatenater.h
Go to the documentation of this file.
1 // -*- mode: c++ -*-
2 /*********************************************************************
3  * Software License Agreement (BSD License)
4  *
5  * Copyright (c) 2013, Ryohei Ueda and 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_NORMAL_CONCATENATER_H_
37 #define JSK_PCL_ROS_UTILS_NORMAL_CONCATENATER_H_
38 
39 #include <ros/ros.h>
40 #include <ros/names.h>
41 #include <sensor_msgs/PointCloud2.h>
42 
46 
47 #include <pcl_ros/pcl_nodelet.h>
48 #include <pcl/point_types.h>
49 #include <pcl/common/centroid.h>
50 #include <pcl/filters/extract_indices.h>
51 #include <jsk_topic_tools/connection_based_nodelet.h>
52 
53 namespace jsk_pcl_ros_utils
54 {
55  class NormalConcatenater: public jsk_topic_tools::ConnectionBasedNodelet
56  {
57  public:
60  virtual ~NormalConcatenater();
61  protected:
68  virtual void concatenate(const sensor_msgs::PointCloud2::ConstPtr& xyz, const sensor_msgs::PointCloud2::ConstPtr& normal);
69  virtual void subscribe();
70  virtual void unsubscribe();
71  bool use_async_;
72  private:
73  virtual void onInit();
74 
75  };
76 }
77 
78 #endif
jsk_pcl_ros_utils
Definition: add_point_indices.h:51
jsk_pcl_ros_utils::NormalConcatenater::use_async_
bool use_async_
Definition: normal_concatenater.h:135
ros::Publisher
jsk_pcl_ros_utils::NormalConcatenater::pub_
ros::Publisher pub_
Definition: normal_concatenater.h:126
boost::shared_ptr
ros.h
jsk_pcl_ros_utils::NormalConcatenater::subscribe
virtual void subscribe()
Definition: normal_concatenater_nodelet.cpp:135
jsk_pcl_ros_utils::NormalConcatenater::unsubscribe
virtual void unsubscribe()
Definition: normal_concatenater_nodelet.cpp:151
jsk_pcl_ros_utils::NormalConcatenater::sub_normal_
message_filters::Subscriber< sensor_msgs::PointCloud2 > sub_normal_
Definition: normal_concatenater.h:131
time_synchronizer.h
jsk_pcl_ros_utils::NormalConcatenater::~NormalConcatenater
virtual ~NormalConcatenater()
Definition: normal_concatenater_nodelet.cpp:123
message_filters::Subscriber< sensor_msgs::PointCloud2 >
pcl_nodelet.h
message_filters::sync_policies::ApproximateTime
jsk_pcl_ros_utils::NormalConcatenater::ASyncPolicy
message_filters::sync_policies::ApproximateTime< sensor_msgs::PointCloud2, sensor_msgs::PointCloud2 > ASyncPolicy
Definition: normal_concatenater.h:123
jsk_pcl_ros_utils::NormalConcatenater::SyncPolicy
message_filters::sync_policies::ExactTime< sensor_msgs::PointCloud2, sensor_msgs::PointCloud2 > SyncPolicy
Definition: normal_concatenater.h:122
jsk_pcl_ros_utils::NormalConcatenater::sync_
boost::shared_ptr< message_filters::Synchronizer< SyncPolicy > > sync_
Definition: normal_concatenater.h:128
jsk_pcl_ros_utils::NormalConcatenater::maximum_queue_size_
int maximum_queue_size_
Definition: normal_concatenater.h:127
jsk_pcl_ros_utils::NormalConcatenater::async_
boost::shared_ptr< message_filters::Synchronizer< ASyncPolicy > > async_
Definition: normal_concatenater.h:129
jsk_pcl_ros_utils::NormalConcatenater::concatenate
virtual void concatenate(const sensor_msgs::PointCloud2::ConstPtr &xyz, const sensor_msgs::PointCloud2::ConstPtr &normal)
Definition: normal_concatenater_nodelet.cpp:73
names.h
synchronizer.h
approximate_time.h
jsk_pcl_ros_utils::NormalConcatenater::onInit
virtual void onInit()
Definition: normal_concatenater_nodelet.cpp:111
message_filters::sync_policies::ExactTime
jsk_pcl_ros_utils::NormalConcatenater::sub_xyz_
message_filters::Subscriber< sensor_msgs::PointCloud2 > sub_xyz_
Definition: normal_concatenater.h:130


jsk_pcl_ros_utils
Author(s): Yohei Kakiuchi
autogenerated on Fri May 16 2025 03:11:43