organized_pass_through.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 
37 #ifndef JSK_PCL_ROS_ORGANIZED_PASS_THROUGH_H_
38 #define JSK_PCL_ROS_ORGANIZED_PASS_THROUGH_H_
39 
40 #include <pcl_ros/pcl_nodelet.h>
41 #include <jsk_topic_tools/diagnostic_nodelet.h>
42 #include <jsk_topic_tools/counter.h>
43 #include <dynamic_reconfigure/server.h>
44 #include "jsk_pcl_ros/OrganizedPassThroughConfig.h"
45 
46 namespace jsk_pcl_ros
47 {
48  class OrganizedPassThrough: public jsk_topic_tools::DiagnosticNodelet
49  {
50  public:
51  typedef jsk_pcl_ros::OrganizedPassThroughConfig Config;
52  typedef pcl::PointXYZRGB PointT;
54  protected:
56  // methods
58  virtual void onInit();
59 
60  virtual void subscribe();
61 
62  virtual void unsubscribe();
63 
64  virtual void configCallback (Config &config, uint32_t level);
65 
66  virtual void filter(const sensor_msgs::PointCloud2::ConstPtr& msg);
67 
68  virtual pcl::PointIndices::Ptr filterIndices(const pcl::PointCloud<PointT>::Ptr& pc);
69 
70  virtual void updateDiagnostic(
72 
73  // pcl removed the method by 1.13, no harm in defining it ourselves to use below
74 #if __cplusplus >= 201103L
75 #define pcl_isfinite(x) std::isfinite(x)
76 #endif
77 
78  bool isPointNaN(const PointT& p) {
79  return (!pcl_isfinite(p.x) || !pcl_isfinite(p.y) || !pcl_isfinite(p.z));
80  }
81 
83  // ROS variables
89 
91  // Diagnostics variables
93  jsk_topic_tools::Counter filtered_points_counter_;
94 
95  enum FilterField
96  {
98  };
99 
101  // Parameters
104  int min_index_;
105  int max_index_;
107  bool keep_organized_;
108  bool remove_nan_;
109  private:
110 
111  };
112 }
113 
114 #endif
jsk_pcl_ros::OrganizedPassThrough::filter_limit_negative_
bool filter_limit_negative_
Definition: organized_pass_through.h:170
jsk_pcl_ros::OrganizedPassThrough::PointT
pcl::PointXYZRGB PointT
Definition: organized_pass_through.h:116
jsk_pcl_ros::OrganizedPassThrough::onInit
virtual void onInit()
Definition: organized_pass_through_nodelet.cpp:81
ros::Publisher
jsk_pcl_ros::OrganizedPassThrough::remove_nan_
bool remove_nan_
Definition: organized_pass_through.h:172
boost::shared_ptr
jsk_pcl_ros::OrganizedPassThrough::filter
virtual void filter(const sensor_msgs::PointCloud2::ConstPtr &msg)
Definition: organized_pass_through_nodelet.cpp:154
p
p
jsk_pcl_ros::OrganizedPassThrough::configCallback
virtual void configCallback(Config &config, uint32_t level)
Definition: organized_pass_through_nodelet.cpp:113
jsk_pcl_ros::OrganizedPassThrough::FIELD_X
@ FIELD_X
Definition: organized_pass_through.h:161
jsk_pcl_ros::OrganizedPassThrough::max_index_
int max_index_
Definition: organized_pass_through.h:169
jsk_pcl_ros::OrganizedPassThrough::FilterField
FilterField
Definition: organized_pass_through.h:159
jsk_pcl_ros::OrganizedPassThrough::OrganizedPassThrough
OrganizedPassThrough()
Definition: organized_pass_through_nodelet.cpp:75
jsk_pcl_ros::OrganizedPassThrough::filterIndices
virtual pcl::PointIndices::Ptr filterIndices(const pcl::PointCloud< PointT >::Ptr &pc)
Definition: organized_pass_through_nodelet.cpp:129
jsk_pcl_ros::OrganizedPassThrough::mutex_
boost::mutex mutex_
Definition: organized_pass_through.h:152
pcl_nodelet.h
jsk_pcl_ros
Definition: add_color_from_image.h:51
jsk_pcl_ros::OrganizedPassThrough::subscribe
virtual void subscribe()
Definition: organized_pass_through_nodelet.cpp:100
jsk_pcl_ros::OrganizedPassThrough::filtered_points_counter_
jsk_topic_tools::Counter filtered_points_counter_
Definition: organized_pass_through.h:157
PointT
pcl::PointXYZRGB PointT
jsk_pcl_ros::OrganizedPassThrough::keep_organized_
bool keep_organized_
Definition: organized_pass_through.h:171
jsk_pcl_ros::OrganizedPassThrough::unsubscribe
virtual void unsubscribe()
Definition: organized_pass_through_nodelet.cpp:108
jsk_pcl_ros::OrganizedPassThrough::FIELD_Y
@ FIELD_Y
Definition: organized_pass_through.h:161
jsk_pcl_ros::OrganizedPassThrough::sub_
ros::Subscriber sub_
Definition: organized_pass_through.h:149
jsk_pcl_ros::OrganizedPassThrough::isPointNaN
bool isPointNaN(const PointT &p)
Definition: organized_pass_through.h:142
jsk_pcl_ros::OrganizedPassThrough::filter_field_
FilterField filter_field_
Definition: organized_pass_through.h:167
jsk_pcl_ros::OrganizedPassThrough::min_index_
int min_index_
Definition: organized_pass_through.h:168
jsk_pcl_ros::OrganizedPassThrough::pub_
ros::Publisher pub_
Definition: organized_pass_through.h:150
diagnostic_updater::DiagnosticStatusWrapper
jsk_pcl_ros::OrganizedPassThrough::updateDiagnostic
virtual void updateDiagnostic(diagnostic_updater::DiagnosticStatusWrapper &stat)
Definition: organized_pass_through_nodelet.cpp:176
jsk_pcl_ros::OrganizedPassThrough::srv_
boost::shared_ptr< dynamic_reconfigure::Server< Config > > srv_
Definition: organized_pass_through.h:151
mutex
boost::mutex mutex
global mutex.
Definition: depth_camera_error_visualization.cpp:86
jsk_pcl_ros::OrganizedPassThrough::Config
jsk_pcl_ros::OrganizedPassThroughConfig Config
Definition: organized_pass_through.h:115
pose_with_covariance_sample.msg
msg
Definition: pose_with_covariance_sample.py:22
ros::Subscriber


jsk_pcl_ros
Author(s): Yohei Kakiuchi
autogenerated on Tue Jan 7 2025 04:05:45