cloud_on_plane.h
Go to the documentation of this file.
1 // -*- mode: c++ -*-
2 /*********************************************************************
3  * Software License Agreement (BSD License)
4  *
5  * Copyright (c) 2015, 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 
37 
38 #ifndef JSK_PCL_ROS_UTILS_CLOUD_ON_PLANE_H_
39 #define JSK_PCL_ROS_UTILS_CLOUD_ON_PLANE_H_
40 
41 #include <jsk_topic_tools/diagnostic_nodelet.h>
42 #include <jsk_recognition_msgs/PolygonArray.h>
49 #include <jsk_pcl_ros_utils/CloudOnPlaneConfig.h>
50 #include <dynamic_reconfigure/server.h>
51 #include <jsk_recognition_msgs/BoolStamped.h>
53 
54 namespace jsk_pcl_ros_utils
55 {
56  class CloudOnPlane: public jsk_topic_tools::DiagnosticNodelet
57  {
58  public:
60  typedef CloudOnPlaneConfig Config;
62  sensor_msgs::PointCloud2,
63  jsk_recognition_msgs::PolygonArray > SyncPolicy;
65  sensor_msgs::PointCloud2,
66  jsk_recognition_msgs::PolygonArray> ApproximateSyncPolicy;
67 
68  CloudOnPlane(): DiagnosticNodelet("CloudOnPlane") {}
69  virtual ~CloudOnPlane();
70  protected:
71  virtual void onInit();
72  virtual void subscribe();
73  virtual void unsubscribe();
74  virtual void predicate(const sensor_msgs::PointCloud2::ConstPtr& cloud_msg,
75  const jsk_recognition_msgs::PolygonArray::ConstPtr& polygon_msg);
76  virtual void configCallback(Config& config, uint32_t level);
77  virtual void publishPredicate(const std_msgs::Header& header, const bool v);
78 
80  boost::mutex mutex_;
86  bool approximate_sync_;
87  double distance_thr_;
88  int buf_size_;
90  private:
91 
92  };
93 }
94 
95 #endif
jsk_pcl_ros_utils
Definition: add_point_indices.h:51
jsk_pcl_ros_utils::CloudOnPlane::buf_size_
int buf_size_
Definition: cloud_on_plane.h:152
ros::Publisher
boost::shared_ptr
jsk_pcl_ros_utils::CloudOnPlane::distance_thr_
double distance_thr_
Definition: cloud_on_plane.h:151
jsk_pcl_ros_utils::CloudOnPlane::SyncPolicy
message_filters::sync_policies::ExactTime< sensor_msgs::PointCloud2, jsk_recognition_msgs::PolygonArray > SyncPolicy
Definition: cloud_on_plane.h:127
jsk_pcl_ros_utils::CloudOnPlane::CloudOnPlane
CloudOnPlane()
Definition: cloud_on_plane.h:132
jsk_pcl_ros_utils::CloudOnPlane::Config
CloudOnPlaneConfig Config
Definition: cloud_on_plane.h:124
jsk_pcl_ros_utils::CloudOnPlane::predicate
virtual void predicate(const sensor_msgs::PointCloud2::ConstPtr &cloud_msg, const jsk_recognition_msgs::PolygonArray::ConstPtr &polygon_msg)
Definition: cloud_on_plane_nodelet.cpp:100
jsk_pcl_ros_utils::CloudOnPlane::subscribe
virtual void subscribe()
Definition: cloud_on_plane_nodelet.cpp:71
jsk_pcl_ros_utils::CloudOnPlane::~CloudOnPlane
virtual ~CloudOnPlane()
Definition: cloud_on_plane_nodelet.cpp:59
time_synchronizer.h
jsk_pcl_ros_utils::CloudOnPlane::publishPredicate
virtual void publishPredicate(const std_msgs::Header &header, const bool v)
Definition: cloud_on_plane_nodelet.cpp:134
jsk_pcl_ros_utils::CloudOnPlane::unsubscribe
virtual void unsubscribe()
Definition: cloud_on_plane_nodelet.cpp:86
jsk_pcl_ros_utils::CloudOnPlane::onInit
virtual void onInit()
Definition: cloud_on_plane_nodelet.cpp:43
message_filters::Subscriber< sensor_msgs::PointCloud2 >
jsk_pcl_ros_utils::CloudOnPlane::Ptr
boost::shared_ptr< CloudOnPlane > Ptr
Definition: cloud_on_plane.h:123
jsk_pcl_ros_utils::CloudOnPlane::async_
boost::shared_ptr< message_filters::Synchronizer< ApproximateSyncPolicy > > async_
Definition: cloud_on_plane.h:149
jsk_pcl_ros_utils::CloudOnPlane::mutex_
boost::mutex mutex_
Definition: cloud_on_plane.h:144
jsk_pcl_ros_utils::CloudOnPlane::sub_polygon_
message_filters::Subscriber< jsk_recognition_msgs::PolygonArray > sub_polygon_
Definition: cloud_on_plane.h:147
jsk_pcl_ros_utils::CloudOnPlane::approximate_sync_
bool approximate_sync_
Definition: cloud_on_plane.h:150
jsk_pcl_ros_utils::CloudOnPlane::sync_
boost::shared_ptr< message_filters::Synchronizer< SyncPolicy > > sync_
Definition: cloud_on_plane.h:148
message_filters::sync_policies::ApproximateTime
subscriber.h
jsk_pcl_ros_utils::CloudOnPlane::srv_
boost::shared_ptr< dynamic_reconfigure::Server< Config > > srv_
Definition: cloud_on_plane.h:145
exact_time.h
jsk_pcl_ros_utils::CloudOnPlane::buffer_
jsk_recognition_utils::SeriesedBoolean::Ptr buffer_
Definition: cloud_on_plane.h:153
jsk_pcl_ros_utils::CloudOnPlane::sub_cloud_
message_filters::Subscriber< sensor_msgs::PointCloud2 > sub_cloud_
Definition: cloud_on_plane.h:146
jsk_pcl_ros_utils::CloudOnPlane::configCallback
virtual void configCallback(Config &config, uint32_t level)
Definition: cloud_on_plane_nodelet.cpp:92
pcl_util.h
synchronizer.h
approximate_time.h
jsk_pcl_ros_utils::CloudOnPlane::ApproximateSyncPolicy
message_filters::sync_policies::ApproximateTime< sensor_msgs::PointCloud2, jsk_recognition_msgs::PolygonArray > ApproximateSyncPolicy
Definition: cloud_on_plane.h:130
message_filters::sync_policies::ExactTime
convex_polygon.h
jsk_pcl_ros_utils::CloudOnPlane::pub_
ros::Publisher pub_
Definition: cloud_on_plane.h:143


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