Point Cloud Library (PCL)  1.9.1
 All Classes Namespaces Functions Variables Typedefs Enumerations Enumerator Friends Modules Pages
davidsdk_grabber.h
1 /*
2  * Software License Agreement (BSD License)
3  *
4  * Point Cloud Library (PCL) - www.pointclouds.org
5  * Copyright (c) 2014-, Open Perception, Inc.
6  *
7  * All rights reserved.
8  *
9  * Redistribution and use in source and binary forms, with or without
10  * modification, are permitted provided that the following conditions
11  * are met:
12  *
13  * * Redistributions of source code must retain the above copyright
14  * notice, this list of conditions and the following disclaimer.
15  * * Redistributions in binary form must reproduce the above
16  * copyright notice, this list of conditions and the following
17  * disclaimer in the documentation and/or other materials provided
18  * with the distribution.
19  * * Neither the name of the copyright holder(s) nor the names of its
20  * contributors may be used to endorse or promote products derived
21  * from this software without specific prior written permission.
22  *
23  * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
24  * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
25  * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
26  * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
27  * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
28  * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
29  * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES;
30  * LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER
31  * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
32  * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
33  * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
34  * POSSIBILITY OF SUCH DAMAGE.
35  *
36  * Author: Victor Lamoine (victor.lamoine@gmail.com)
37  */
38 
39 #include <pcl/pcl_config.h>
40 
41 #ifndef __PCL_IO_DAVIDSDK_GRABBER__
42 #define __PCL_IO_DAVIDSDK_GRABBER__
43 
44 #include <pcl/common/time.h>
45 #include <pcl/common/io.h>
46 #include <boost/thread.hpp>
47 #include <pcl/PolygonMesh.h>
48 #include <pcl/io/grabber.h>
49 
50 #include <david.h>
51 
52 namespace pcl
53 {
54  struct PointXYZ;
55  template <typename T> class PointCloud;
56 
57  /** @brief Grabber for davidSDK structured light compliant devices.\n
58  * The [davidSDK SDK](http://www.david-3d.com/en/products/david-sdk) allows to use a structured light scanner to
59  * fetch clouds/meshes.\n
60  * The purpose of this grabber is NOT to provide all davidSDK functionalities but rather provide a PCL-unified interface to the sensor for
61  * basic operations.\n
62  * Please consult the [David-3d wiki](http://wiki.david-3d.com/david-wiki) for more information.
63  * @author Victor Lamoine (victor.lamoine@gmail.com)\n
64  * @ingroup io
65  */
66  class PCL_EXPORTS DavidSDKGrabber : public Grabber
67  {
68  public:
69  /** @cond */
70  typedef boost::shared_ptr<DavidSDKGrabber> Ptr;
71  typedef boost::shared_ptr<const DavidSDKGrabber> ConstPtr;
72 
73  // Define callback signature typedefs
74  typedef void
75  (sig_cb_davidsdk_point_cloud) (const pcl::PointCloud<pcl::PointXYZ>::Ptr &);
76 
77  typedef void
78  (sig_cb_davidsdk_mesh) (const pcl::PolygonMesh::Ptr &);
79 
80  typedef void
81  (sig_cb_davidsdk_image) (const boost::shared_ptr<pcl::PCLImage> &);
82 
83  typedef void
84  (sig_cb_davidsdk_point_cloud_image) (const pcl::PointCloud<pcl::PointXYZ>::Ptr &,
85  const boost::shared_ptr<pcl::PCLImage> &);
86 
87  typedef void
88  (sig_cb_davidsdk_mesh_image) (const pcl::PolygonMesh::Ptr &,
89  const boost::shared_ptr<pcl::PCLImage> &);
90  /** @endcond */
91 
92  /** @brief Constructor */
93  DavidSDKGrabber ();
94 
95  /** @brief Destructor inherited from the Grabber interface. It never throws. */
96  virtual
97  ~DavidSDKGrabber () throw ();
98 
99  /** @brief [Connect](http://docs.david-3d.com/sdk/en/classdavid_1_1_client_json_rpc.html#a4b948e57a2e5e7f9cdcf1171c500aa24) client
100  * @param[in] address
101  * @param[in] port
102  * @return Server info*/
103  david::ServerInfo
104  connect (const std::string & address = "127.0.0.1",
105  uint16_t port = david::DAVID_SDK_DefaultPort);
106 
107  /** @brief [Disconnect](http://docs.david-3d.com/sdk/en/classdavid_1_1_client_json_rpc.html#a2770728a6de2c708df767bedf8be0814) client
108  * @param[in] stop_server */
109  void
110  disconnect (const bool stop_server);
111 
112  /** @brief Start the point cloud and or image acquisition */
113  void
114  start ();
115 
116  /** @brief Stop the data acquisition */
117  void
118  stop ();
119 
120  /** @brief Check if the data acquisition is still running
121  * @return True if running, false otherwise */
122  bool
123  isRunning () const;
124 
125  /** @brief Check if the client is connected
126  * @return True if connected, false otherwise */
127  bool
128  isConnected () const;
129 
130  /** @brief Get class name
131  * @returns A string containing the class name */
132  std::string
133  getName () const;
134 
135  /** @brief Get @ref local_path_ path directory
136  * @returns the path */
137  std::string
138  getLocalPath ();
139 
140  /** @brief Get @ref remote_path_ path directory
141  * @returns the path */
142  std::string
143  getRemotePath ();
144 
145  /** @brief Set @ref file_format_ to "obj" */
146  void
147  setFileFormatToOBJ ();
148 
149  /** @brief Set @ref file_format_ to "ply"
150  * @warning This format is NOT available with trial versions of the davidSDK server! */
151  void
152  setFileFormatToPLY ();
153 
154  /** @brief Set @ref file_format_ to "stl" */
155  void
156  setFileFormatToSTL ();
157 
158  /** @brief Get @ref file_format_
159  * @returns the file format */
160  std::string
161  getFileFormat ();
162 
163  /** @brief Set @ref local_path_ path directory for scanning files
164  * @param[in] path The directory path
165  *
166  * If the path is empty, using default value ("C:/temp") */
167  void
168  setLocalPath (std::string path);
169 
170  /** @brief Set @ref remote_path_ path directory for scanning files
171  * @param[in] path The directory path
172  *
173  * If the string is empty, @ref remote_path_ = @ref local_path_ */
174  void
175  setRemotePath (std::string path);
176 
177  /** @brief Set @ref local_path_ and @ref remote_path_ directory paths
178  * @param[in] local_path
179  * @param[in] remote_path
180  *
181  * If the path is empty, using default value ("C:/temp") */
182  void
183  setLocalAndRemotePaths (std::string local_path,
184  std::string remote_path);
185 
186  /** @brief Calibrate the scanner
187  * @param[in] grid_size Size of the calibration grid in millimeters
188  * @return True if successful, false otherwise
189  *
190  * More information [here](http://wiki.david-3d.com/david3_user_manual/structured_light).\n
191  * Also see [ImportCalibration](http://docs.david-3d.com/sdk/en/classdavid_1_1_i_structured_light_scanner.html#a68e888636883d90aac7891d2ef9e6b27).\n
192  * and [ExportCalibration](http://docs.david-3d.com/sdk/en/classdavid_1_1_i_structured_light_scanner.html#a66817b07227f9a8852663d9141ae48db).
193  *
194  * @warning You MUST perform calibration each time you modify the camera/projector focus or move the camera relatively to the projector.\n
195  */
196  bool
197  calibrate (double grid_size);
198 
199  /** @brief Capture a single point cloud and store it
200  * @param[out] cloud The cloud to be filled
201  * @return True if successful, false otherwise
202  * @warning Calls [DeleteAllMeshes()](http://docs.david-3d.com/sdk/en/classdavid_1_1_i_shape_fusion.html#aed22e458b51f1361803360c02c2d1403) */
203  bool
204  grabSingleCloud (pcl::PointCloud<pcl::PointXYZ> &cloud);
205 
206  /** @brief Capture a single mesh and store it
207  * @param[out] mesh The mesh to be filled
208  * @return True if successful, false otherwise
209  * @warning Calls [DeleteAllMeshes()](http://docs.david-3d.com/sdk/en/classdavid_1_1_i_shape_fusion.html#aed22e458b51f1361803360c02c2d1403) */
210  bool
211  grabSingleMesh (pcl::PolygonMesh &mesh);
212 
213  /** @brief Obtain the number of frames per second (FPS) */
214  float
215  getFramesPerSecond () const;
216 
217  /** @brief davidSDK client */
218  david::Client david_;
219 
220  protected:
221  /** @brief Grabber thread */
222  boost::thread grabber_thread_;
223 
224  /** @brief Boost point cloud signal */
225  boost::signals2::signal<sig_cb_davidsdk_point_cloud>* point_cloud_signal_;
226 
227  /** @brief Boost mesh signal */
228  boost::signals2::signal<sig_cb_davidsdk_mesh>* mesh_signal_;
229 
230  /** @brief Boost image signal */
231  boost::signals2::signal<sig_cb_davidsdk_image>* image_signal_;
232 
233  /** @brief Boost image + point cloud signal */
234  boost::signals2::signal<sig_cb_davidsdk_point_cloud_image>* point_cloud_image_signal_;
235 
236  /** @brief Boost mesh + image signal */
237  boost::signals2::signal<sig_cb_davidsdk_mesh_image>* mesh_image_signal_;
238 
239  /** @brief Whether the client is connected */
241 
242  /** @brief Whether an davidSDK device is running or not */
243  bool running_;
244 
245  /** @brief Local path of directory where the scanning file will be located.
246  * @note Default value is @c C:/temp */
247  std::string local_path_;
248 
249  /** @brief Remote path of directory where the scanning file will be located.
250  * @note If this is empty, the @ref local_path_ will be used instead
251  * Default value is @c C:/temp */
252  std::string remote_path_;
253 
254  /** @brief Export file extension, available formats are STL, OBJ, PLY */
255  std::string file_format_;
256 
257  /** @brief processGrabbing capture/processing frequency */
259 
260  /** @brief Mutual exclusion for FPS computation */
261  mutable boost::mutex fps_mutex_;
262 
263  /** @brief Continuously asks for images and or point clouds/meshes data from the device and publishes them if available. */
264  void
265  processGrabbing ();
266  };
267 } // namespace pcl
268 
269 #endif // __PCL_IO_DAVIDSDK_GRABBER__
boost::signals2::signal< sig_cb_davidsdk_point_cloud > * point_cloud_signal_
Boost point cloud signal.
boost::shared_ptr< PointCloud< PointT > > Ptr
Definition: point_cloud.h:428
boost::mutex fps_mutex_
Mutual exclusion for FPS computation.
boost::signals2::signal< sig_cb_davidsdk_image > * image_signal_
Boost image signal.
pcl::EventFrequency frequency_
processGrabbing capture/processing frequency
david::Client david_
davidSDK client
This file defines compatibility wrappers for low level I/O functions.
Definition: convolution.h:45
A helper class to measure frequency of a certain event.
Definition: time.h:151
Grabber interface for PCL 1.x device drivers.
Definition: grabber.h:58
boost::signals2::signal< sig_cb_davidsdk_point_cloud_image > * point_cloud_image_signal_
Boost image + point cloud signal.
Grabber for davidSDK structured light compliant devices.
boost::shared_ptr< ::pcl::PolygonMesh > Ptr
Definition: PolygonMesh.h:28
boost::signals2::signal< sig_cb_davidsdk_mesh > * mesh_signal_
Boost mesh signal.
std::string file_format_
Export file extension, available formats are STL, OBJ, PLY.
PointCloud represents the base class in PCL for storing collections of 3D points. ...
bool running_
Whether an davidSDK device is running or not.
boost::signals2::signal< sig_cb_davidsdk_mesh_image > * mesh_image_signal_
Boost mesh + image signal.
boost::thread grabber_thread_
Grabber thread.
bool client_connected_
Whether the client is connected.
std::string local_path_
Local path of directory where the scanning file will be located.
std::string remote_path_
Remote path of directory where the scanning file will be located.