plane_rejector.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_PLANE_REJECTOR_H_
37 #define JSK_PCL_ROS_UTILS_PLANE_REJECTOR_H_
38 
39 
40 // ros
41 #include <ros/ros.h>
42 #include <ros/names.h>
43 #include <sensor_msgs/PointCloud2.h>
49 
50 #include <dynamic_reconfigure/server.h>
51 // pcl
52 #include <pcl_ros/pcl_nodelet.h>
53 
54 #include <jsk_recognition_msgs/PolygonArray.h>
55 #include <jsk_recognition_msgs/ModelCoefficientsArray.h>
56 #include <jsk_recognition_msgs/ClusterPointIndices.h>
57 #include "jsk_pcl_ros_utils/PlaneRejectorConfig.h"
58 
60 #include <jsk_topic_tools/time_accumulator.h>
61 #include <jsk_topic_tools/vital_checker.h>
62 
65 #include <jsk_topic_tools/rosparam_utils.h>
67 #include <jsk_topic_tools/connection_based_nodelet.h>
68 
69 
70 namespace jsk_pcl_ros_utils
71 {
72  class PlaneRejector: public jsk_topic_tools::ConnectionBasedNodelet
73  {
74  public:
75  typedef message_filters::sync_policies::ExactTime< jsk_recognition_msgs::PolygonArray,
76  jsk_recognition_msgs::ModelCoefficientsArray > SyncPolicy;
77  typedef message_filters::sync_policies::ExactTime< jsk_recognition_msgs::PolygonArray,
78  jsk_recognition_msgs::ModelCoefficientsArray,
79  jsk_recognition_msgs::ClusterPointIndices
81  typedef jsk_pcl_ros_utils::PlaneRejectorConfig Config;
82  virtual ~PlaneRejector();
83  protected:
84  virtual void onInit();
85  virtual void reject(const jsk_recognition_msgs::PolygonArray::ConstPtr& polygons,
86  const jsk_recognition_msgs::ModelCoefficientsArray::ConstPtr& coefficients);
87  virtual void reject(const jsk_recognition_msgs::PolygonArray::ConstPtr& polygons,
88  const jsk_recognition_msgs::ModelCoefficientsArray::ConstPtr& coefficients,
89  const jsk_recognition_msgs::ClusterPointIndices::ConstPtr& inliers);
90  virtual void configCallback (Config &config, uint32_t level);
91 
92 
93  virtual void updateDiagnostics(const ros::TimerEvent& event);
94  virtual void updateDiagnosticsPlaneRejector(
96  virtual void subscribe();
97  virtual void unsubscribe();
98 
104 
105  bool use_tf2_;
106  bool use_inliers_;
107  bool allow_flip_;
108  std::string processing_frame_id_;
109  // axis
110  Eigen::Vector3d reference_axis_;
111  double angle_thr_;
113  boost::mutex mutex_;
118  jsk_topic_tools::VitalChecker::Ptr vital_checker_;
120 
124  double angle_;
125  private:
126 
127  };
128 }
129 
130 #endif
jsk_pcl_ros_utils
Definition: add_point_indices.h:51
jsk_pcl_ros_utils::PlaneRejector::configCallback
virtual void configCallback(Config &config, uint32_t level)
Definition: plane_rejector_nodelet.cpp:212
jsk_pcl_ros_utils::PlaneRejector::diagnostics_timer_
ros::Timer diagnostics_timer_
Definition: plane_rejector.h:180
jsk_pcl_ros_utils::PlaneRejector::sync_
boost::shared_ptr< message_filters::Synchronizer< SyncPolicy > > sync_
Definition: plane_rejector.h:166
ros::Publisher
boost::shared_ptr
jsk_pcl_ros_utils::PlaneRejector::sub_coefficients_
message_filters::Subscriber< jsk_recognition_msgs::ModelCoefficientsArray > sub_coefficients_
Definition: plane_rejector.h:164
jsk_pcl_ros_utils::PlaneRejector::unsubscribe
virtual void unsubscribe()
Definition: plane_rejector_nodelet.cpp:168
jsk_pcl_ros_utils::PlaneRejector::input_plane_counter_
jsk_recognition_utils::Counter input_plane_counter_
Definition: plane_rejector.h:187
ros.h
jsk_pcl_ros_utils::PlaneRejector::diagnostic_updater_
boost::shared_ptr< diagnostic_updater::Updater > diagnostic_updater_
Definition: plane_rejector.h:181
jsk_pcl_ros_utils::PlaneRejector::angle_thr_
double angle_thr_
Definition: plane_rejector.h:175
jsk_pcl_ros_utils::PlaneRejector::use_inliers_
bool use_inliers_
Definition: plane_rejector.h:170
jsk_pcl_ros_utils::PlaneRejector::updateDiagnostics
virtual void updateDiagnostics(const ros::TimerEvent &event)
Definition: plane_rejector_nodelet.cpp:206
jsk_pcl_ros_utils::PlaneRejector::tf_success_
jsk_recognition_utils::SeriesedBoolean::Ptr tf_success_
Definition: plane_rejector.h:183
time_synchronizer.h
jsk_pcl_ros_utils::PlaneRejector::listener_
tf::TransformListener * listener_
Definition: plane_rejector.h:176
jsk_pcl_ros_utils::PlaneRejector::vital_checker_
jsk_topic_tools::VitalChecker::Ptr vital_checker_
Definition: plane_rejector.h:182
jsk_pcl_ros_utils::PlaneRejector::angle_
double angle_
Definition: plane_rejector.h:188
publisher.h
transform_broadcaster.h
diagnostic_updater.h
jsk_pcl_ros_utils::PlaneRejector::~PlaneRejector
virtual ~PlaneRejector()
Definition: plane_rejector_nodelet.cpp:137
message_filters::Subscriber< jsk_recognition_msgs::PolygonArray >
jsk_pcl_ros_utils::PlaneRejector::srv_
boost::shared_ptr< dynamic_reconfigure::Server< Config > > srv_
Definition: plane_rejector.h:178
pcl_nodelet.h
jsk_pcl_ros_utils::PlaneRejector::allow_flip_
bool allow_flip_
Definition: plane_rejector.h:171
jsk_pcl_ros_utils::PlaneRejector::coefficients_pub_
ros::Publisher coefficients_pub_
Definition: plane_rejector.h:179
jsk_pcl_ros_utils::PlaneRejector::onInit
virtual void onInit()
Definition: plane_rejector_nodelet.cpp:76
jsk_pcl_ros_utils::PlaneRejector::SyncInlierPolicy
message_filters::sync_policies::ExactTime< jsk_recognition_msgs::PolygonArray, jsk_recognition_msgs::ModelCoefficientsArray, jsk_recognition_msgs::ClusterPointIndices > SyncInlierPolicy
Definition: plane_rejector.h:144
subscriber.h
jsk_pcl_ros_utils::PlaneRejector::subscribe
virtual void subscribe()
Definition: plane_rejector_nodelet.cpp:149
jsk_pcl_ros_utils::PlaneRejector::Config
jsk_pcl_ros_utils::PlaneRejectorConfig Config
Definition: plane_rejector.h:145
jsk_pcl_ros_utils::PlaneRejector::sync_inlier_
boost::shared_ptr< message_filters::Synchronizer< SyncInlierPolicy > > sync_inlier_
Definition: plane_rejector.h:167
ros::TimerEvent
jsk_pcl_ros_utils::PlaneRejector::passed_plane_counter_
jsk_recognition_utils::Counter passed_plane_counter_
Definition: plane_rejector.h:186
pcl_conversion_util.h
jsk_pcl_ros_utils::PlaneRejector::SyncPolicy
message_filters::sync_policies::ExactTime< jsk_recognition_msgs::PolygonArray, jsk_recognition_msgs::ModelCoefficientsArray > SyncPolicy
Definition: plane_rejector.h:140
jsk_pcl_ros_utils::PlaneRejector::use_tf2_
bool use_tf2_
Definition: plane_rejector.h:169
jsk_recognition_utils::Counter
jsk_pcl_ros_utils::PlaneRejector::inliers_pub_
ros::Publisher inliers_pub_
Definition: plane_rejector.h:179
jsk_pcl_ros_utils::PlaneRejector::mutex_
boost::mutex mutex_
Definition: plane_rejector.h:177
names.h
pcl_util.h
jsk_pcl_ros_utils::PlaneRejector::updateDiagnosticsPlaneRejector
virtual void updateDiagnosticsPlaneRejector(diagnostic_updater::DiagnosticStatusWrapper &stat)
Definition: plane_rejector_nodelet.cpp:174
tf::TransformListener
synchronizer.h
diagnostic_updater::DiagnosticStatusWrapper
jsk_pcl_ros_utils::PlaneRejector::sub_polygons_
message_filters::Subscriber< jsk_recognition_msgs::PolygonArray > sub_polygons_
Definition: plane_rejector.h:163
jsk_pcl_ros_utils::PlaneRejector::polygons_pub_
ros::Publisher polygons_pub_
Definition: plane_rejector.h:179
jsk_pcl_ros_utils::PlaneRejector::rejected_plane_counter_
jsk_recognition_utils::Counter rejected_plane_counter_
Definition: plane_rejector.h:185
tf_listener_singleton.h
message_filters::sync_policies::ExactTime
jsk_pcl_ros_utils::PlaneRejector::reference_axis_
Eigen::Vector3d reference_axis_
Definition: plane_rejector.h:174
ros::Timer
jsk_pcl_ros_utils::PlaneRejector::processing_frame_id_
std::string processing_frame_id_
Definition: plane_rejector.h:172
jsk_pcl_ros_utils::PlaneRejector::reject
virtual void reject(const jsk_recognition_msgs::PolygonArray::ConstPtr &polygons, const jsk_recognition_msgs::ModelCoefficientsArray::ConstPtr &coefficients)
Definition: plane_rejector_nodelet.cpp:219
jsk_pcl_ros_utils::PlaneRejector::sub_inliers_
message_filters::Subscriber< jsk_recognition_msgs::ClusterPointIndices > sub_inliers_
Definition: plane_rejector.h:165


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