depthcloud_encoder.h
Go to the documentation of this file.
1 /*********************************************************************
2  *
3  * Copyright (c) 2014, Willow Garage, Inc.
4  * All rights reserved.
5  *
6  * Redistribution and use in source and binary forms, with or without
7  * modification, are permitted provided that the following conditions
8  * are met:
9  *
10  * * Redistributions of source code must retain the above copyright
11  * notice, this list of conditions and the following disclaimer.
12  * * Redistributions in binary form must reproduce the above
13  * copyright notice, this list of conditions and the following
14  * disclaimer in the documentation and/or other materials provided
15  * with the distribution.
16  * * Neither the name of the Willow Garage nor the names of its
17  * contributors may be used to endorse or promote products derived
18  * from this software without specific prior written permission.
19  *
20  * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
21  * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
22  * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
23  * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
24  * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
25  * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
26  * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES;
27  * LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER
28  * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
29  * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
30  * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
31  * POSSIBILITY OF SUCH DAMAGE.
32 
33  * Author: Julius Kammerl (jkammerl@willowgarage.com)
34  *
35  */
36 
37 #ifndef DEPTHCLOUD_ENCODER_H
38 #define DEPTHCLOUD_ENCODER_H
39 
40 #include <iostream>
41 #include <string>
42 #include <boost/thread.hpp>
43 
44 #include <dynamic_reconfigure/server.h>
45 #include <depthcloud_encoder/paramsConfig.h>
46 
49 
51 
55 
56 #include <tf/transform_listener.h>
57 #include <geometry_msgs/TransformStamped.h>
58 
59 #include <sensor_msgs/PointCloud2.h>
60 #include <pcl/point_types.h>
61 
62 #include "ros/ros.h"
63 
64 namespace depthcloud
65 {
66 
68 {
69 public:
71  virtual ~DepthCloudEncoder();
72 
73  void dynReconfCb(depthcloud_encoder::paramsConfig& config, uint32_t level);
74 
75 protected:
76 
77  void connectCb();
78 
79  void subscribe(std::string& depth_topic, std::string& color_topic);
80  void subscribeCloud(std::string& cloud_topic);
81  void unsubscribe();
82 
83  void cameraInfoCb(const sensor_msgs::CameraInfoConstPtr& cam_info_msg);
84 
85  void cloudCB(const sensor_msgs::PointCloud2& cloud_msg);
86 
87  void depthCB(const sensor_msgs::ImageConstPtr& depth_msg);
88 
89  void depthColorCB(const sensor_msgs::ImageConstPtr& depth_msg, const sensor_msgs::ImageConstPtr& color_msg);
90 
91  void depthInterpolation(sensor_msgs::ImageConstPtr depth_msg,
92  sensor_msgs::ImagePtr depth_int_msg,
93  sensor_msgs::ImagePtr mask_msg);
94 
95  void cloudToDepth(const sensor_msgs::PointCloud2& cloud_msg, sensor_msgs::ImagePtr depth_msg, sensor_msgs::ImagePtr color_msg);
96  void process(const sensor_msgs::ImageConstPtr& depth_msg, const sensor_msgs::ImageConstPtr& color_msg, const std::size_t crop_size);
97 
98 
101 
104 
105  // ROS stuff
110 
112 
113  boost::mutex connect_mutex_;
114 
117 
119 
120  std::string depthmap_topic_;
121  std::string rgb_image_topic_;
122  std::string cloud_topic_;
123  std::string camera_info_topic_;
124  std::string camera_frame_id_;
125  std::string depth_source_;
126 
128 
129  double f_;
132  bool latch_;
133 
135 };
136 
137 }
138 
139 #endif
void subscribe(std::string &depth_topic, std::string &color_topic)
void subscribeCloud(std::string &cloud_topic)
void cloudToDepth(const sensor_msgs::PointCloud2 &cloud_msg, sensor_msgs::ImagePtr depth_msg, sensor_msgs::ImagePtr color_msg)
tf::TransformListener tf_listener_
void cameraInfoCb(const sensor_msgs::CameraInfoConstPtr &cam_info_msg)
boost::shared_ptr< SynchronizerDepthColor > sync_depth_color_
void depthCB(const sensor_msgs::ImageConstPtr &depth_msg)
image_transport::ImageTransport pub_it_
void depthInterpolation(sensor_msgs::ImageConstPtr depth_msg, sensor_msgs::ImagePtr depth_int_msg, sensor_msgs::ImagePtr mask_msg)
DepthCloudEncoder(ros::NodeHandle &nh, ros::NodeHandle &pnh)
void cloudCB(const sensor_msgs::PointCloud2 &cloud_msg)
message_filters::Synchronizer< SyncPolicyDepthColor > SynchronizerDepthColor
boost::shared_ptr< image_transport::SubscriberFilter > depth_sub_
image_transport::Publisher pub_
boost::shared_ptr< image_transport::SubscriberFilter > color_sub_
message_filters::sync_policies::ApproximateTime< sensor_msgs::Image, sensor_msgs::Image > SyncPolicyDepthColor
void dynReconfCb(depthcloud_encoder::paramsConfig &config, uint32_t level)
void process(const sensor_msgs::ImageConstPtr &depth_msg, const sensor_msgs::ImageConstPtr &color_msg, const std::size_t crop_size)
void depthColorCB(const sensor_msgs::ImageConstPtr &depth_msg, const sensor_msgs::ImageConstPtr &color_msg)


depthcloud_encoder
Author(s): Julius Kammer
autogenerated on Mon Jun 10 2019 13:06:12