depth_image_creator.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 #ifndef JSK_PCL_ROS_IMAGE_CREATOR_H_
37 #define JSK_PCL_ROS_IMAGE_CREATOR_H_
38 
39 #include <pcl_ros/pcl_nodelet.h>
40 #include <pcl_ros/transforms.h>
41 
43 #include <dynamic_reconfigure/server.h>
44 
45 #include <pcl/range_image/range_image_planar.h>
46 #if ( PCL_MAJOR_VERSION >= 1 && PCL_MINOR_VERSION >= 5 )
47 #include <pcl/common/transforms.h>
48 #else
49 #include <pcl/common/transform.h>
50 #endif
51 
52 #include <sensor_msgs/Image.h>
53 #include <sensor_msgs/CameraInfo.h>
54 #include <sensor_msgs/PointCloud2.h>
56 #include <stereo_msgs/DisparityImage.h>
57 
58 #include <opencv2/opencv.hpp>
59 
60 #include <std_srvs/Empty.h>
61 #include <boost/thread/mutex.hpp>
62 
65 
66 namespace jsk_pcl_ros
67 {
69  {
70  protected:
80 
81  sensor_msgs::PointCloud2ConstPtr points_ptr_;
82 
98  double scale_depth;
99  double tf_duration_;
100  float fill_value;
101  typedef pcl::PointXYZRGB Point;
102  typedef pcl::PointCloud< Point > PointCloud;
103 
104  void onInit();
105 
106  bool service_cb (std_srvs::Empty::Request &req,
107  std_srvs::Empty::Response &res);
108 
109  void callback_sync(const sensor_msgs::CameraInfoConstPtr& info,
110  const sensor_msgs::PointCloud2ConstPtr& pcloud2);
111 
112  void callback_cloud(const sensor_msgs::PointCloud2ConstPtr& pcloud2);
113 
114  void callback_info(const sensor_msgs::CameraInfoConstPtr& info);
115 
116  void publish_points(const sensor_msgs::CameraInfoConstPtr& info,
117  const sensor_msgs::PointCloud2ConstPtr& pcloud2);
118 
119  void subscribe();
120  void unsubscribe();
121  public:
122  };
123 }
124 
125 #endif
126 
message_filters::Subscriber< sensor_msgs::CameraInfo > sub_info_
bool service_cb(std_srvs::Empty::Request &req, std_srvs::Empty::Response &res)
void callback_info(const sensor_msgs::CameraInfoConstPtr &info)
void callback_cloud(const sensor_msgs::PointCloud2ConstPtr &pcloud2)
boost::shared_ptr< message_filters::Synchronizer< message_filters::sync_policies::ApproximateTime< sensor_msgs::CameraInfo, sensor_msgs::PointCloud2 > > > sync_inputs_a_
boost::mutex mutex
global mutex.
sensor_msgs::PointCloud2ConstPtr points_ptr_
boost::shared_ptr< message_filters::Synchronizer< message_filters::sync_policies::ExactTime< sensor_msgs::CameraInfo, sensor_msgs::PointCloud2 > > > sync_inputs_e_
void publish_points(const sensor_msgs::CameraInfoConstPtr &info, const sensor_msgs::PointCloud2ConstPtr &pcloud2)
void callback_sync(const sensor_msgs::CameraInfoConstPtr &info, const sensor_msgs::PointCloud2ConstPtr &pcloud2)
message_filters::Subscriber< sensor_msgs::PointCloud2 > sub_cloud_
tf::TransformListener * tf_listener_
pcl::PointCloud< Point > PointCloud
tf::StampedTransform fixed_transform


jsk_pcl_ros
Author(s): Yohei Kakiuchi
autogenerated on Mon May 3 2021 03:03:46