37 #ifndef DEPTHCLOUD_ENCODER_H 38 #define DEPTHCLOUD_ENCODER_H 42 #include <boost/thread.hpp> 44 #include <dynamic_reconfigure/server.h> 45 #include <depthcloud_encoder/paramsConfig.h> 57 #include <geometry_msgs/TransformStamped.h> 59 #include <sensor_msgs/PointCloud2.h> 60 #include <pcl/point_types.h> 73 void dynReconfCb(depthcloud_encoder::paramsConfig& config, uint32_t level);
79 void subscribe(std::string& depth_topic, std::string& color_topic);
83 void cameraInfoCb(
const sensor_msgs::CameraInfoConstPtr& cam_info_msg);
85 void cloudCB(
const sensor_msgs::PointCloud2& cloud_msg);
87 void depthCB(
const sensor_msgs::ImageConstPtr& depth_msg);
89 void depthColorCB(
const sensor_msgs::ImageConstPtr& depth_msg,
const sensor_msgs::ImageConstPtr& color_msg);
92 sensor_msgs::ImagePtr depth_int_msg,
93 sensor_msgs::ImagePtr mask_msg);
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);
ros::Subscriber camera_info_sub_
void subscribe(std::string &depth_topic, std::string &color_topic)
ros::Subscriber cloud_sub_
void subscribeCloud(std::string &cloud_topic)
void cloudToDepth(const sensor_msgs::PointCloud2 &cloud_msg, sensor_msgs::ImagePtr depth_msg, sensor_msgs::ImagePtr color_msg)
float max_depth_per_tile_
std::string camera_frame_id_
tf::TransformListener tf_listener_
virtual ~DepthCloudEncoder()
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)
std::string camera_info_topic_
std::string depthmap_topic_
void cloudCB(const sensor_msgs::PointCloud2 &cloud_msg)
bool connectivityExceptionFlag
message_filters::Synchronizer< SyncPolicyDepthColor > SynchronizerDepthColor
boost::shared_ptr< image_transport::SubscriberFilter > depth_sub_
image_transport::Publisher pub_
boost::mutex connect_mutex_
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)
std::string rgb_image_topic_
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)
std::string depth_source_