environment_plane_modeling.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 #ifndef JSK_PCL_ROS_ENVIRONMENT_PLANE_MODELING_H_
37 #define JSK_PCL_ROS_ENVIRONMENT_PLANE_MODELING_H_
38 
39 #include <pcl_ros/pcl_nodelet.h>
40 
41 #include <pcl/kdtree/kdtree_flann.h>
45 #include <dynamic_reconfigure/server.h>
46 
47 #include <jsk_recognition_msgs/PolygonArray.h>
48 #include <jsk_recognition_msgs/ModelCoefficientsArray.h>
49 #include <jsk_recognition_msgs/ClusterPointIndices.h>
50 #include <sensor_msgs/PointCloud2.h>
51 #include <jsk_recognition_msgs/EnvironmentLock.h>
52 #include <jsk_recognition_msgs/PolygonOnEnvironment.h>
53 
55 #include <jsk_pcl_ros/EnvironmentPlaneModelingConfig.h>
56 
59 
60 #include <std_srvs/Empty.h>
61 
62 #include <jsk_topic_tools/time_accumulator.h>
63 
65 #include <jsk_recognition_msgs/SimpleOccupancyGridArray.h>
66 #include <jsk_recognition_msgs/BoundingBoxArray.h>
67 #include <jsk_topic_tools/diagnostic_nodelet.h>
70 
71 namespace jsk_pcl_ros
72 {
73 
74  // Helper classes
75 
80  class EnvironmentPlaneModeling: public jsk_topic_tools::DiagnosticNodelet
81  {
82  public:
83  typedef EnvironmentPlaneModelingConfig Config;
84 
86  sensor_msgs::PointCloud2,
87  sensor_msgs::PointCloud2,
88  jsk_recognition_msgs::PolygonArray,
89  jsk_recognition_msgs::ModelCoefficientsArray,
90  jsk_recognition_msgs::ClusterPointIndices > SyncPolicy;
91  EnvironmentPlaneModeling(): DiagnosticNodelet("EnvironmentPlaneModeling") {}
92  virtual ~EnvironmentPlaneModeling();
93  protected:
94  virtual void onInit();
95 
101  virtual void subscribe() {}
102 
108  virtual void unsubscribe() {}
109 
114  virtual void inputCallback(
115  const sensor_msgs::PointCloud2::ConstPtr& cloud_msg,
116  const sensor_msgs::PointCloud2::ConstPtr& full_cloud_msg,
117  const jsk_recognition_msgs::PolygonArray::ConstPtr& polygon_msg,
118  const jsk_recognition_msgs::ModelCoefficientsArray::ConstPtr& coefficients_msg,
119  const jsk_recognition_msgs::ClusterPointIndices::ConstPtr& indices_msg);
120 
121  virtual void printInputData(
122  const sensor_msgs::PointCloud2::ConstPtr& cloud_msg,
123  const sensor_msgs::PointCloud2::ConstPtr& full_cloud_msg,
124  const jsk_recognition_msgs::PolygonArray::ConstPtr& polygon_msg,
125  const jsk_recognition_msgs::ModelCoefficientsArray::ConstPtr& coefficients_msg,
126  const jsk_recognition_msgs::ClusterPointIndices::ConstPtr& indices_msg);
127 
128 
129  virtual bool isValidFrameIds(
130  const sensor_msgs::PointCloud2::ConstPtr& cloud_msg,
131  const sensor_msgs::PointCloud2::ConstPtr& full_cloud_msg,
132  const jsk_recognition_msgs::PolygonArray::ConstPtr& polygon_msg,
133  const jsk_recognition_msgs::ModelCoefficientsArray::ConstPtr& coefficients_msg,
134  const jsk_recognition_msgs::ClusterPointIndices::ConstPtr& indices_msg);
135 
136  virtual std::vector<jsk_recognition_utils::ConvexPolygon::Ptr> convertToConvexPolygons(
137  const pcl::PointCloud<pcl::PointNormal>::Ptr& cloud,
138  const jsk_recognition_msgs::ClusterPointIndices::ConstPtr& indices_msg,
139  const jsk_recognition_msgs::ModelCoefficientsArray::ConstPtr& coefficients_msg);
140 
141  virtual void publishConvexPolygonsBoundaries(
143  const std_msgs::Header& header,
144  std::vector<jsk_recognition_utils::ConvexPolygon::Ptr>& convexes);
145 
150  virtual void configCallback(Config &config, uint32_t level);
151 
156  virtual void publishConvexPolygons(
158  const std_msgs::Header& header,
159  std::vector<jsk_recognition_utils::ConvexPolygon::Ptr>& convexes);
160 
165  virtual void publishGridMaps(
167  const std_msgs::Header& header,
168  std::vector<GridPlane::Ptr>& grids);
169 
174  virtual std::vector<jsk_recognition_utils::ConvexPolygon::Ptr> magnifyConvexes(
175  std::vector<jsk_recognition_utils::ConvexPolygon::Ptr>& convexes);
176 
181  virtual std::vector<GridPlane::Ptr> buildGridPlanes(
182  pcl::PointCloud<pcl::PointNormal>::Ptr& cloud,
183  std::vector<jsk_recognition_utils::ConvexPolygon::Ptr> convexes,
184  std::set<int>& non_plane_indices);
185 
186  virtual std::vector<GridPlane::Ptr> morphologicalFiltering(
187  std::vector<GridPlane::Ptr>& raw_grid_maps);
188 
189  virtual void boundingBoxCallback(
190  const jsk_recognition_msgs::BoundingBox::ConstPtr& box_array);
191 
192  virtual std::vector<GridPlane::Ptr> completeFootprintRegion(
193  const std_msgs::Header& header,
194  std::vector<GridPlane::Ptr>& grid_maps);
195 
196  virtual std::vector<GridPlane::Ptr> erodeFiltering(
197  std::vector<GridPlane::Ptr>& grid_maps);
198 
199  virtual int lookupGroundPlaneForFootprint(
200  const std::string& footprint_frame_id, const std_msgs::Header& header,
201  const std::vector<GridPlane::Ptr>& grid_maps);
202 
203  virtual int lookupGroundPlaneForFootprint(
204  const Eigen::Affine3f& pose, const std::vector<GridPlane::Ptr>& grid_maps);
205 
207  const jsk_recognition_msgs::BoundingBox::ConstPtr& box,
208  const std_msgs::Header& header,
209  GridPlane::Ptr grid_map);
210 
211  virtual void moveBaseSimpleGoalCallback(
212  const geometry_msgs::PoseStamped::ConstPtr& msg);
213 
234  jsk_recognition_msgs::BoundingBox::ConstPtr latest_leg_bounding_box_;
235  std::vector<std::string> footprint_frames_;
236  std::vector<GridPlane::Ptr> latest_grid_maps_;
237  std_msgs::Header latest_global_header_;
239  // Parameters
241  double magnify_distance_;
242  double distance_threshold_;
243  double normal_threshold_;
244  double resolution_;
247  int erode_filter_size_;
250  private:
251  };
252 }
253 
254 #endif
jsk_pcl_ros::EnvironmentPlaneModeling::erodeFiltering
virtual std::vector< GridPlane::Ptr > erodeFiltering(std::vector< GridPlane::Ptr > &grid_maps)
Definition: environment_plane_modeling_nodelet.cpp:353
jsk_pcl_ros::EnvironmentPlaneModeling::footprint_plane_angular_threshold_
double footprint_plane_angular_threshold_
Definition: environment_plane_modeling.h:313
jsk_pcl_ros::EnvironmentPlaneModeling::sub_full_cloud_
message_filters::Subscriber< sensor_msgs::PointCloud2 > sub_full_cloud_
Definition: environment_plane_modeling.h:281
jsk_pcl_ros::EnvironmentPlaneModeling::sub_indices_
message_filters::Subscriber< jsk_recognition_msgs::ClusterPointIndices > sub_indices_
Definition: environment_plane_modeling.h:282
jsk_pcl_ros::EnvironmentPlaneModeling::isValidFrameIds
virtual bool isValidFrameIds(const sensor_msgs::PointCloud2::ConstPtr &cloud_msg, const sensor_msgs::PointCloud2::ConstPtr &full_cloud_msg, const jsk_recognition_msgs::PolygonArray::ConstPtr &polygon_msg, const jsk_recognition_msgs::ModelCoefficientsArray::ConstPtr &coefficients_msg, const jsk_recognition_msgs::ClusterPointIndices::ConstPtr &indices_msg)
Definition: environment_plane_modeling_nodelet.cpp:157
ros::Publisher
jsk_pcl_ros::EnvironmentPlaneModeling::pub_grid_map_
ros::Publisher pub_grid_map_
Definition: environment_plane_modeling.h:293
jsk_pcl_ros::EnvironmentPlaneModeling::tf_listener_
tf::TransformListener * tf_listener_
Definition: environment_plane_modeling.h:297
boost::shared_ptr
jsk_pcl_ros::EnvironmentPlaneModeling::SyncPolicy
message_filters::sync_policies::ExactTime< sensor_msgs::PointCloud2, sensor_msgs::PointCloud2, jsk_recognition_msgs::PolygonArray, jsk_recognition_msgs::ModelCoefficientsArray, jsk_recognition_msgs::ClusterPointIndices > SyncPolicy
Definition: environment_plane_modeling.h:154
sample_simulate_tabletop_cloud.header
header
Definition: sample_simulate_tabletop_cloud.py:162
jsk_pcl_ros::EnvironmentPlaneModeling::pub_debug_magnified_polygons_
ros::Publisher pub_debug_magnified_polygons_
Definition: environment_plane_modeling.h:287
jsk_pcl_ros::EnvironmentPlaneModeling::buildGridPlanes
virtual std::vector< GridPlane::Ptr > buildGridPlanes(pcl::PointCloud< pcl::PointNormal >::Ptr &cloud, std::vector< jsk_recognition_utils::ConvexPolygon::Ptr > convexes, std::set< int > &non_plane_indices)
make GridPlane from jsk_recognition_utils::ConvexPolygon and PointCloud
Definition: environment_plane_modeling_nodelet.cpp:527
jsk_pcl_ros::EnvironmentPlaneModeling::pub_debug_convex_point_cloud_
ros::Publisher pub_debug_convex_point_cloud_
Definition: environment_plane_modeling.h:288
jsk_pcl_ros::EnvironmentPlaneModeling::morphologicalFiltering
virtual std::vector< GridPlane::Ptr > morphologicalFiltering(std::vector< GridPlane::Ptr > &raw_grid_maps)
Definition: environment_plane_modeling_nodelet.cpp:478
jsk_pcl_ros::EnvironmentPlaneModeling::magnifyConvexes
virtual std::vector< jsk_recognition_utils::ConvexPolygon::Ptr > magnifyConvexes(std::vector< jsk_recognition_utils::ConvexPolygon::Ptr > &convexes)
Magnify jsk_recognition_utils::ConvexPolygons according to maginify_distance_ parameter.
Definition: environment_plane_modeling_nodelet.cpp:564
jsk_pcl_ros::EnvironmentPlaneModeling::sync_
boost::shared_ptr< message_filters::Synchronizer< SyncPolicy > > sync_
Definition: environment_plane_modeling.h:279
geo_util.h
jsk_pcl_ros::EnvironmentPlaneModeling::latest_global_header_
std_msgs::Header latest_global_header_
Definition: environment_plane_modeling.h:301
jsk_pcl_ros::EnvironmentPlaneModeling::sub_move_base_simple_goal_
ros::Subscriber sub_move_base_simple_goal_
Definition: environment_plane_modeling.h:286
attention_pose_set.pub
pub
Definition: attention_pose_set.py:8
jsk_pcl_ros::EnvironmentPlaneModeling::magnify_distance_
double magnify_distance_
Definition: environment_plane_modeling.h:305
time_synchronizer.h
tf_listener_singleton.h
jsk_pcl_ros::EnvironmentPlaneModeling::latest_leg_bounding_box_
jsk_recognition_msgs::BoundingBox::ConstPtr latest_leg_bounding_box_
Definition: environment_plane_modeling.h:298
jsk_pcl_ros::EnvironmentPlaneModeling::normal_threshold_
double normal_threshold_
Definition: environment_plane_modeling.h:307
jsk_pcl_ros::EnvironmentPlaneModeling::~EnvironmentPlaneModeling
virtual ~EnvironmentPlaneModeling()
Definition: environment_plane_modeling_nodelet.cpp:118
jsk_pcl_ros::EnvironmentPlaneModeling::EnvironmentPlaneModeling
EnvironmentPlaneModeling()
Definition: environment_plane_modeling.h:155
jsk_pcl_ros::EnvironmentPlaneModeling::pub_debug_noeroded_grid_map_
ros::Publisher pub_debug_noeroded_grid_map_
Definition: environment_plane_modeling.h:290
publisher.h
jsk_pcl_ros::EnvironmentPlaneModeling::latest_grid_maps_
std::vector< GridPlane::Ptr > latest_grid_maps_
Definition: environment_plane_modeling.h:300
diagnostic_updater.h
message_filters::Subscriber< sensor_msgs::PointCloud2 >
jsk_pcl_ros::EnvironmentPlaneModeling::resolution_
double resolution_
Definition: environment_plane_modeling.h:308
pcl_nodelet.h
jsk_pcl_ros::EnvironmentPlaneModeling::boundingBoxCallback
virtual void boundingBoxCallback(const jsk_recognition_msgs::BoundingBox::ConstPtr &box_array)
Definition: environment_plane_modeling_nodelet.cpp:247
attention_pose_set.box
box
Definition: attention_pose_set.py:14
jsk_pcl_ros::EnvironmentPlaneModeling::pub_debug_plane_coords_
ros::Publisher pub_debug_plane_coords_
Definition: environment_plane_modeling.h:291
jsk_pcl_ros::EnvironmentPlaneModeling::inputCallback
virtual void inputCallback(const sensor_msgs::PointCloud2::ConstPtr &cloud_msg, const sensor_msgs::PointCloud2::ConstPtr &full_cloud_msg, const jsk_recognition_msgs::PolygonArray::ConstPtr &polygon_msg, const jsk_recognition_msgs::ModelCoefficientsArray::ConstPtr &coefficients_msg, const jsk_recognition_msgs::ClusterPointIndices::ConstPtr &indices_msg)
main callback function
Definition: environment_plane_modeling_nodelet.cpp:254
jsk_pcl_ros::EnvironmentPlaneModeling::complete_footprint_region_
bool complete_footprint_region_
Definition: environment_plane_modeling.h:310
jsk_pcl_ros::EnvironmentPlaneModeling::lookupGroundPlaneForFootprint
virtual int lookupGroundPlaneForFootprint(const std::string &footprint_frame_id, const std_msgs::Header &header, const std::vector< GridPlane::Ptr > &grid_maps)
Definition: environment_plane_modeling_nodelet.cpp:397
jsk_pcl_ros::EnvironmentPlaneModeling::mutex_
boost::mutex mutex_
Definition: environment_plane_modeling.h:278
jsk_pcl_ros::EnvironmentPlaneModeling::publishGridMaps
virtual void publishGridMaps(ros::Publisher &pub, const std_msgs::Header &header, std::vector< GridPlane::Ptr > &grids)
Publish array of GridPlane::Ptr by using specified publisher.
Definition: environment_plane_modeling_nodelet.cpp:511
jsk_pcl_ros::EnvironmentPlaneModeling::sub_polygons_
message_filters::Subscriber< jsk_recognition_msgs::PolygonArray > sub_polygons_
Definition: environment_plane_modeling.h:283
jsk_pcl_ros
Definition: add_color_from_image.h:51
jsk_pcl_ros::EnvironmentPlaneModeling::printInputData
virtual void printInputData(const sensor_msgs::PointCloud2::ConstPtr &cloud_msg, const sensor_msgs::PointCloud2::ConstPtr &full_cloud_msg, const jsk_recognition_msgs::PolygonArray::ConstPtr &polygon_msg, const jsk_recognition_msgs::ModelCoefficientsArray::ConstPtr &coefficients_msg, const jsk_recognition_msgs::ClusterPointIndices::ConstPtr &indices_msg)
Definition: environment_plane_modeling_nodelet.cpp:142
subscriber.h
jsk_pcl_ros::EnvironmentPlaneModeling::completeFootprintRegion
virtual std::vector< GridPlane::Ptr > completeFootprintRegion(const std_msgs::Header &header, std::vector< GridPlane::Ptr > &grid_maps)
Definition: environment_plane_modeling_nodelet.cpp:442
jsk_pcl_ros::EnvironmentPlaneModeling::publishConvexPolygonsBoundaries
virtual void publishConvexPolygonsBoundaries(ros::Publisher &pub, const std_msgs::Header &header, std::vector< jsk_recognition_utils::ConvexPolygon::Ptr > &convexes)
Definition: environment_plane_modeling_nodelet.cpp:491
jsk_pcl_ros::EnvironmentPlaneModeling::sub_cloud_
message_filters::Subscriber< sensor_msgs::PointCloud2 > sub_cloud_
Definition: environment_plane_modeling.h:280
jsk_pcl_ros::EnvironmentPlaneModeling::erode_filter_size_
int erode_filter_size_
Definition: environment_plane_modeling.h:311
jsk_pcl_ros::EnvironmentPlaneModeling::unsubscribe
virtual void unsubscribe()
unsubscription callback function of jsk_topic_tools::DiagnosticNodelet. This method is empty method b...
Definition: environment_plane_modeling.h:172
jsk_pcl_ros::EnvironmentPlaneModeling::configCallback
virtual void configCallback(Config &config, uint32_t level)
Callback method of dynamic reconfigure.
Definition: environment_plane_modeling_nodelet.cpp:129
pcl_conversion_util.h
jsk_pcl_ros::EnvironmentPlaneModeling::morphological_filter_size_
int morphological_filter_size_
Definition: environment_plane_modeling.h:309
jsk_pcl_ros::EnvironmentPlaneModeling::pub_debug_raw_grid_map_
ros::Publisher pub_debug_raw_grid_map_
Definition: environment_plane_modeling.h:289
jsk_pcl_ros::EnvironmentPlaneModeling::pub_debug_magnified_plane_coords_
ros::Publisher pub_debug_magnified_plane_coords_
Definition: environment_plane_modeling.h:292
jsk_pcl_ros::EnvironmentPlaneModeling::subscribe
virtual void subscribe()
subscription callback function of jsk_topic_tools::DiagnosticNodelet. This method is empty method bec...
Definition: environment_plane_modeling.h:165
jsk_pcl_ros::EnvironmentPlaneModeling::srv_
boost::shared_ptr< dynamic_reconfigure::Server< Config > > srv_
Definition: environment_plane_modeling.h:296
jsk_pcl_ros::EnvironmentPlaneModeling::sub_coefficients_
message_filters::Subscriber< jsk_recognition_msgs::ModelCoefficientsArray > sub_coefficients_
Definition: environment_plane_modeling.h:284
jsk_pcl_ros::EnvironmentPlaneModeling::publishConvexPolygons
virtual void publishConvexPolygons(ros::Publisher &pub, const std_msgs::Header &header, std::vector< jsk_recognition_utils::ConvexPolygon::Ptr > &convexes)
Publish array of jsk_recognition_utils::ConvexPolygon::Ptr by using specified publisher.
Definition: environment_plane_modeling_nodelet.cpp:548
jsk_pcl_ros::EnvironmentPlaneModeling::moveBaseSimpleGoalCallback
virtual void moveBaseSimpleGoalCallback(const geometry_msgs::PoseStamped::ConstPtr &msg)
Definition: environment_plane_modeling_nodelet.cpp:195
pcl_util.h
tf::TransformListener
synchronizer.h
mutex
boost::mutex mutex
global mutex.
Definition: depth_camera_error_visualization.cpp:86
jsk_pcl_ros::EnvironmentPlaneModeling::footprint_plane_distance_threshold_
double footprint_plane_distance_threshold_
Definition: environment_plane_modeling.h:312
jsk_pcl_ros::EnvironmentPlaneModeling::distance_threshold_
double distance_threshold_
Definition: environment_plane_modeling.h:306
jsk_pcl_ros::EnvironmentPlaneModeling::footprint_frames_
std::vector< std::string > footprint_frames_
Definition: environment_plane_modeling.h:299
jsk_pcl_ros::EnvironmentPlaneModeling::pub_non_plane_indices_
ros::Publisher pub_non_plane_indices_
Definition: environment_plane_modeling.h:294
message_filters::sync_policies::ExactTime
jsk_pcl_ros::EnvironmentPlaneModeling::pub_snapped_move_base_simple_goal_
ros::Publisher pub_snapped_move_base_simple_goal_
Definition: environment_plane_modeling.h:295
jsk_pcl_ros::EnvironmentPlaneModeling::Config
EnvironmentPlaneModelingConfig Config
Definition: environment_plane_modeling.h:147
pose_with_covariance_sample.msg
msg
Definition: pose_with_covariance_sample.py:22
jsk_pcl_ros::EnvironmentPlaneModeling::convertToConvexPolygons
virtual std::vector< jsk_recognition_utils::ConvexPolygon::Ptr > convertToConvexPolygons(const pcl::PointCloud< pcl::PointNormal >::Ptr &cloud, const jsk_recognition_msgs::ClusterPointIndices::ConstPtr &indices_msg, const jsk_recognition_msgs::ModelCoefficientsArray::ConstPtr &coefficients_msg)
Definition: environment_plane_modeling_nodelet.cpp:580
jsk_pcl_ros::EnvironmentPlaneModeling::sub_leg_bbox_
ros::Subscriber sub_leg_bbox_
Definition: environment_plane_modeling.h:285
jsk_pcl_ros::EnvironmentPlaneModeling::onInit
virtual void onInit()
Definition: environment_plane_modeling_nodelet.cpp:54
jsk_pcl_ros::EnvironmentPlaneModeling::completeGridMapByBoundingBox
virtual GridPlane::Ptr completeGridMapByBoundingBox(const jsk_recognition_msgs::BoundingBox::ConstPtr &box, const std_msgs::Header &header, GridPlane::Ptr grid_map)
Definition: environment_plane_modeling_nodelet.cpp:413
ros::Subscriber


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