Go to the documentation of this file.00001
00002
00003
00004
00005
00006
00007
00008
00009
00010
00011
00012
00013
00014
00015
00016
00017
00018
00019
00020
00021
00022
00023
00024
00025
00026
00027
00028
00029
00030
00031
00032
00033
00034
00035
00036
00037 #ifndef DEPTHCLOUD_ENCODER_H
00038 #define DEPTHCLOUD_ENCODER_H
00039
00040 #include <iostream>
00041 #include <string>
00042 #include <boost/thread.hpp>
00043
00044 #include <dynamic_reconfigure/server.h>
00045 #include <depthcloud_encoder/paramsConfig.h>
00046
00047 #include <image_transport/image_transport.h>
00048 #include <image_transport/subscriber_filter.h>
00049
00050 #include <sensor_msgs/image_encodings.h>
00051
00052 #include <message_filters/subscriber.h>
00053 #include <message_filters/synchronizer.h>
00054 #include <message_filters/sync_policies/approximate_time.h>
00055
00056 #include <tf/transform_listener.h>
00057 #include <geometry_msgs/TransformStamped.h>
00058
00059 #include <sensor_msgs/PointCloud2.h>
00060 #include <pcl/point_types.h>
00061
00062 #include "ros/ros.h"
00063
00064 namespace depthcloud
00065 {
00066
00067 class DepthCloudEncoder
00068 {
00069 public:
00070 DepthCloudEncoder(ros::NodeHandle& nh, ros::NodeHandle& pnh);
00071 virtual ~DepthCloudEncoder();
00072
00073 void dynReconfCb(depthcloud_encoder::paramsConfig& config, uint32_t level);
00074
00075 protected:
00076
00077 void connectCb();
00078
00079 void subscribe(std::string& depth_topic, std::string& color_topic);
00080 void subscribeCloud(std::string& cloud_topic);
00081 void unsubscribe();
00082
00083 void cameraInfoCb(const sensor_msgs::CameraInfoConstPtr& cam_info_msg);
00084
00085 void cloudCB(const sensor_msgs::PointCloud2& cloud_msg);
00086
00087 void depthCB(const sensor_msgs::ImageConstPtr& depth_msg);
00088
00089 void depthColorCB(const sensor_msgs::ImageConstPtr& depth_msg, const sensor_msgs::ImageConstPtr& color_msg);
00090
00091 void depthInterpolation(sensor_msgs::ImageConstPtr depth_msg,
00092 sensor_msgs::ImagePtr depth_int_msg,
00093 sensor_msgs::ImagePtr mask_msg);
00094
00095 void cloudToDepth(const sensor_msgs::PointCloud2& cloud_msg, sensor_msgs::ImagePtr depth_msg, sensor_msgs::ImagePtr color_msg);
00096 void process(const sensor_msgs::ImageConstPtr& depth_msg, const sensor_msgs::ImageConstPtr& color_msg, const std::size_t crop_size);
00097
00098
00099 typedef message_filters::sync_policies::ApproximateTime<sensor_msgs::Image, sensor_msgs::Image> SyncPolicyDepthColor;
00100 typedef message_filters::Synchronizer<SyncPolicyDepthColor> SynchronizerDepthColor;
00101
00102 ros::NodeHandle& nh_;
00103 ros::NodeHandle& pnh_;
00104
00105
00106 boost::shared_ptr<image_transport::SubscriberFilter > depth_sub_;
00107 boost::shared_ptr<image_transport::SubscriberFilter > color_sub_;
00108 ros::Subscriber cloud_sub_;
00109 ros::Subscriber camera_info_sub_;
00110
00111 boost::shared_ptr<SynchronizerDepthColor> sync_depth_color_;
00112
00113 boost::mutex connect_mutex_;
00114
00115 image_transport::ImageTransport pub_it_;
00116 image_transport::Publisher pub_;
00117
00118 int crop_size_;
00119
00120 std::string depthmap_topic_;
00121 std::string rgb_image_topic_;
00122 std::string cloud_topic_;
00123 std::string camera_info_topic_;
00124 std::string camera_frame_id_;
00125 std::string depth_source_;
00126
00127 tf::TransformListener tf_listener_;
00128
00129 double f_;
00130 double f_mult_factor_;
00131 float max_depth_per_tile_;
00132 bool latch_;
00133
00134 bool connectivityExceptionFlag, lookupExceptionFlag;
00135 };
00136
00137 }
00138
00139 #endif