plane_reasoner.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/o2r 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_UTILS_PLANE_REASONER_H_
38 #define JSK_PCL_ROS_UTILS_PLANE_REASONER_H_
39 
41 #include "jsk_recognition_msgs/ClusterPointIndices.h"
42 #include "jsk_recognition_msgs/PolygonArray.h"
43 #include "jsk_recognition_msgs/ModelCoefficientsArray.h"
44 
49 
50 #include <dynamic_reconfigure/server.h>
51 #include "jsk_pcl_ros_utils/PlaneReasonerConfig.h"
52 
54 
55 namespace jsk_pcl_ros_utils
56 {
57  typedef boost::tuple<pcl::PointIndices::Ptr,
58  pcl::ModelCoefficients::Ptr,
60  geometry_msgs::PolygonStamped>
62 
64  {
65  public:
67  // typedefs
70  sensor_msgs::PointCloud2,
71  jsk_recognition_msgs::ClusterPointIndices,
72  jsk_recognition_msgs::ModelCoefficientsArray,
73  jsk_recognition_msgs::PolygonArray> SyncPolicy;
74  typedef jsk_pcl_ros_utils::PlaneReasonerConfig Config;
75  typedef pcl::PointXYZRGB PointT;
76 
77 
78  PlaneReasoner(): DiagnosticNodelet("PlaneReasoner") { }
79 
80  protected:
82  // Methods
84  virtual void onInit();
85 
86  virtual void subscribe();
87 
88  virtual void unsubscribe();
89 
90  virtual void reason(
91  const sensor_msgs::PointCloud2::ConstPtr& cloud_msg,
92  const jsk_recognition_msgs::ClusterPointIndices::ConstPtr& inliers_msg,
93  const jsk_recognition_msgs::ModelCoefficientsArray::ConstPtr& coefficients_msg,
94  const jsk_recognition_msgs::PolygonArray::ConstPtr& polygons_msg);
95 
96  virtual void configCallback (Config &config, uint32_t level);
97 
98  virtual std::vector<PlaneInfoContainer>
99  packInfo(std::vector<pcl::PointIndices::Ptr>& inliers,
100  std::vector<pcl::ModelCoefficients::Ptr>& coefficients,
101  std::vector<jsk_recognition_utils::Plane::Ptr>& planes,
102  std::vector<geometry_msgs::PolygonStamped>& polygons);
103 
104  virtual std::vector<PlaneInfoContainer>
106  std::vector<PlaneInfoContainer>& infos);
107 
108  virtual std::vector<PlaneInfoContainer>
110  std::vector<PlaneInfoContainer>& infos);
111 
112  virtual std::vector<PlaneInfoContainer>
114  double reference_angle,
115  double thrshold,
116  std::vector<PlaneInfoContainer>& infos);
117 
118  virtual void publishPlaneInfo(
119  std::vector<PlaneInfoContainer>& containers,
120  const std_msgs::Header& header,
121  pcl::PointCloud<PointT>::Ptr cloud,
122  ros::Publisher& pub_inlier,
123  ros::Publisher& pub_coefficients,
124  ros::Publisher& pub_polygons);
125 
127  // ROS variables
142 
143  boost::mutex mutex_;
144 
146  // parameters
148  std::string global_frame_id_;
151  private:
152 
153  };
154 }
155 
156 #endif
message_filters::Subscriber< jsk_recognition_msgs::ModelCoefficientsArray > sub_coefficients_
config
virtual std::vector< PlaneInfoContainer > packInfo(std::vector< pcl::PointIndices::Ptr > &inliers, std::vector< pcl::ModelCoefficients::Ptr > &coefficients, std::vector< jsk_recognition_utils::Plane::Ptr > &planes, std::vector< geometry_msgs::PolygonStamped > &polygons)
coefficients
message_filters::sync_policies::ExactTime< sensor_msgs::PointCloud2, jsk_recognition_msgs::ClusterPointIndices, jsk_recognition_msgs::ModelCoefficientsArray, jsk_recognition_msgs::PolygonArray > SyncPolicy
boost::shared_ptr< message_filters::Synchronizer< SyncPolicy > > sync_
virtual void configCallback(Config &config, uint32_t level)
DiagnosticNodelet(const std::string &name)
boost::shared_ptr< Plane > Ptr
boost::tuple< pcl::PointIndices::Ptr, pcl::ModelCoefficients::Ptr, jsk_recognition_utils::Plane::Ptr, geometry_msgs::PolygonStamped > PlaneInfoContainer
tf::TransformListener * tf_listener_
jsk_pcl_ros_utils::PlaneReasonerConfig Config
virtual void reason(const sensor_msgs::PointCloud2::ConstPtr &cloud_msg, const jsk_recognition_msgs::ClusterPointIndices::ConstPtr &inliers_msg, const jsk_recognition_msgs::ModelCoefficientsArray::ConstPtr &coefficients_msg, const jsk_recognition_msgs::PolygonArray::ConstPtr &polygons_msg)
message_filters::Subscriber< jsk_recognition_msgs::PolygonArray > sub_polygons_
message_filters::Subscriber< jsk_recognition_msgs::ClusterPointIndices > sub_inliers_
virtual std::vector< PlaneInfoContainer > filterHorizontalPlanes(std::vector< PlaneInfoContainer > &infos)
ros::Publisher pub_horizontal_coefficients_
virtual std::vector< PlaneInfoContainer > filterPlanesAroundAngle(double reference_angle, double thrshold, std::vector< PlaneInfoContainer > &infos)
boost::shared_ptr< dynamic_reconfigure::Server< Config > > srv_
virtual void publishPlaneInfo(std::vector< PlaneInfoContainer > &containers, const std_msgs::Header &header, pcl::PointCloud< PointT >::Ptr cloud, ros::Publisher &pub_inlier, ros::Publisher &pub_coefficients, ros::Publisher &pub_polygons)
virtual std::vector< PlaneInfoContainer > filterVerticalPlanes(std::vector< PlaneInfoContainer > &infos)
polygons
header
message_filters::Subscriber< sensor_msgs::PointCloud2 > sub_input_


jsk_pcl_ros_utils
Author(s): Yohei Kakiuchi
autogenerated on Mon May 3 2021 03:03:15