pointcloud_cropper.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 Willow Garage 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_INTERACTIVE_MARKER_POINTCLOUD_CLOPPER_H_
38 #define JSK_INTERACTIVE_MARKER_POINTCLOUD_CLOPPER_H_
39 
40 #define BOOST_PARAMETER_MAX_ARITY 7 // its a hack
41 
43 
46 
47 #include <sensor_msgs/PointCloud2.h>
48 
49 #include <pcl/point_types.h>
50 #include <pcl/point_cloud.h>
51 #include <sensor_msgs/PointCloud2.h>
52 
53 #include <tf/transform_listener.h>
54 
55 #include <dynamic_reconfigure/server.h>
56 #include <jsk_interactive_marker/PointCloudCropperConfig.h>
57 
58 namespace jsk_interactive_marker
59 {
60 
61  class Cropper
62  {
63  public:
64  typedef std::shared_ptr<Cropper> Ptr;
65  Cropper(const unsigned int nr_parameter);
66  virtual ~Cropper();
67 
68  virtual void crop(const pcl::PointCloud<pcl::PointXYZ>::Ptr& input,
69  pcl::PointCloud<pcl::PointXYZ>::Ptr output);
70  virtual std::string getName() = 0;
71  virtual visualization_msgs::Marker getMarker() = 0;
72  virtual void updateParameter(const double val, const unsigned int index);
73  // return true if the point p is inside of the cropper
74  virtual bool isInside(const pcl::PointXYZ& p) = 0;
75  virtual void fillInitialParameters() = 0;
76  virtual void setPose(Eigen::Affine3f pose);
77  virtual Eigen::Affine3f getPose();
78  protected:
79  unsigned int nr_parameter_;
80  std::vector<double> parameters_;
81  // pose_ of the Cropper should be respected to the frame_id of pointcloud
82  Eigen::Affine3f pose_;
83  private:
84 
85  };
86 
87  class SphereCropper: public Cropper
88  {
89  public:
90  typedef std::shared_ptr<SphereCropper> Ptr;
91 
92  SphereCropper();
93  virtual ~SphereCropper();
94  virtual std::string getName();
95  virtual visualization_msgs::Marker getMarker();
96  virtual bool isInside(const pcl::PointXYZ& p);
97  virtual void fillInitialParameters();
98  virtual double getRadius();
99  protected:
100  private:
101 
102  };
103 
104  class CubeCropper: public Cropper
105  {
106  public:
107  typedef std::shared_ptr<CubeCropper> Ptr;
108 
109  CubeCropper();
110  virtual ~CubeCropper();
111  virtual std::string getName();
112  virtual visualization_msgs::Marker getMarker();
113  virtual bool isInside(const pcl::PointXYZ& p);
114  virtual void fillInitialParameters();
115  virtual double getWidthX();
116  virtual double getWidthY();
117  virtual double getWidthZ();
118  protected:
119  private:
120 
121  };
122 
123 
125  {
126  public:
128  virtual ~PointCloudCropper();
129  protected:
130  typedef PointCloudCropperConfig Config;
131 
132  typedef std::vector<interactive_markers::MenuHandler::EntryHandle>
134  virtual void changeCropper(Cropper::Ptr next_cropper);
135  virtual void inputCallback(const sensor_msgs::PointCloud2::ConstPtr& msg);
136  virtual void reInitializeInteractiveMarker();
137  virtual void updateInteractiveMarker(
138  Eigen::Affine3f pose_offset = Eigen::Affine3f::Identity());
139  virtual void initializeInteractiveMarker(
140  Eigen::Affine3f pose_offset = Eigen::Affine3f::Identity());
141  virtual void processFeedback(
142  const visualization_msgs::InteractiveMarkerFeedbackConstPtr &feedback);
143  virtual void menuFeedback(
144  const visualization_msgs::InteractiveMarkerFeedbackConstPtr &feedback);
145  virtual void changeCropperCallback(
146  const visualization_msgs::InteractiveMarkerFeedbackConstPtr &feedback );
147  virtual void updateMenuCheckboxStatus();
148  virtual void cropAndPublish(ros::Publisher& pub);
149  virtual void configCallback(Config &config, uint32_t level);
154  std::shared_ptr<interactive_markers::InteractiveMarkerServer> server_;
155  //pcl::PointCloud<pcl::PointXYZ>::Ptr latest_pointcloud_;
156  sensor_msgs::PointCloud2::ConstPtr latest_pointcloud_;
157  std::shared_ptr <dynamic_reconfigure::Server<Config> > srv_;
160  std::vector<Cropper::Ptr> cropper_candidates_;
162  std::shared_ptr<tf::TransformListener> tf_listener_;
163 
164  private:
165  };
166 }
167 
168 #endif
std::shared_ptr< Cropper > Ptr
Cropper(const unsigned int nr_parameter)
sensor_msgs::PointCloud2::ConstPtr latest_pointcloud_
std::shared_ptr< interactive_markers::InteractiveMarkerServer > server_
virtual std::string getName()=0
virtual visualization_msgs::Marker getMarker()=0
virtual void setPose(Eigen::Affine3f pose)
std::vector< double > parameters_
std::shared_ptr< dynamic_reconfigure::Server< Config > > srv_
void processFeedback(const visualization_msgs::InteractiveMarkerFeedbackConstPtr &feedback)
virtual Eigen::Affine3f getPose()
std::vector< Cropper::Ptr > cropper_candidates_
virtual void crop(const pcl::PointCloud< pcl::PointXYZ >::Ptr &input, pcl::PointCloud< pcl::PointXYZ >::Ptr output)
std::shared_ptr< CubeCropper > Ptr
virtual void updateParameter(const double val, const unsigned int index)
virtual bool isInside(const pcl::PointXYZ &p)=0
interactive_markers::MenuHandler menu_handler_
std::shared_ptr< tf::TransformListener > tf_listener_
std::shared_ptr< SphereCropper > Ptr
boost::mutex mutex
virtual void fillInitialParameters()=0
std::vector< interactive_markers::MenuHandler::EntryHandle > EntryHandleVector


jsk_interactive_marker
Author(s): furuta
autogenerated on Sat Mar 20 2021 03:03:33