Public Member Functions | Protected Types | Protected Member Functions | Protected Attributes
depthcloud::DepthCloudEncoder Class Reference

#include <depthcloud_encoder.h>

List of all members.

Public Member Functions

 DepthCloudEncoder (ros::NodeHandle &nh, ros::NodeHandle &pnh)
void dynReconfCb (depthcloud_encoder::paramsConfig &config, uint32_t level)
virtual ~DepthCloudEncoder ()

Protected Types

typedef
message_filters::Synchronizer
< SyncPolicyDepthColor
SynchronizerDepthColor
typedef
message_filters::sync_policies::ApproximateTime
< sensor_msgs::Image,
sensor_msgs::Image > 
SyncPolicyDepthColor

Protected Member Functions

void cameraInfoCb (const sensor_msgs::CameraInfoConstPtr &cam_info_msg)
void cloudCB (const sensor_msgs::PointCloud2 &cloud_msg)
void cloudToDepth (const sensor_msgs::PointCloud2 &cloud_msg, sensor_msgs::ImagePtr depth_msg, sensor_msgs::ImagePtr color_msg)
void connectCb ()
void depthCB (const sensor_msgs::ImageConstPtr &depth_msg)
void depthColorCB (const sensor_msgs::ImageConstPtr &depth_msg, const sensor_msgs::ImageConstPtr &color_msg)
void depthInterpolation (sensor_msgs::ImageConstPtr depth_msg, sensor_msgs::ImagePtr depth_int_msg, sensor_msgs::ImagePtr mask_msg)
void process (const sensor_msgs::ImageConstPtr &depth_msg, const sensor_msgs::ImageConstPtr &color_msg, const std::size_t crop_size)
void subscribe (std::string &depth_topic, std::string &color_topic)
void subscribeCloud (std::string &cloud_topic)
void unsubscribe ()

Protected Attributes

std::string camera_frame_id_
ros::Subscriber camera_info_sub_
std::string camera_info_topic_
ros::Subscriber cloud_sub_
std::string cloud_topic_
boost::shared_ptr
< image_transport::SubscriberFilter
color_sub_
boost::mutex connect_mutex_
bool connectivityExceptionFlag
int crop_size_
std::string depth_source_
boost::shared_ptr
< image_transport::SubscriberFilter
depth_sub_
std::string depthmap_topic_
double f_
double f_mult_factor_
bool latch_
bool lookupExceptionFlag
float max_depth_per_tile_
ros::NodeHandlenh_
ros::NodeHandlepnh_
image_transport::Publisher pub_
image_transport::ImageTransport pub_it_
std::string rgb_image_topic_
boost::shared_ptr
< SynchronizerDepthColor
sync_depth_color_
tf::TransformListener tf_listener_

Detailed Description

Definition at line 67 of file depthcloud_encoder.h.


Member Typedef Documentation

Definition at line 100 of file depthcloud_encoder.h.

Definition at line 99 of file depthcloud_encoder.h.


Constructor & Destructor Documentation

Definition at line 59 of file depthcloud_encoder.cpp.

Definition at line 111 of file depthcloud_encoder.cpp.


Member Function Documentation

void depthcloud::DepthCloudEncoder::cameraInfoCb ( const sensor_msgs::CameraInfoConstPtr &  cam_info_msg) [protected]

Definition at line 139 of file depthcloud_encoder.cpp.

void depthcloud::DepthCloudEncoder::cloudCB ( const sensor_msgs::PointCloud2 &  cloud_msg) [protected]

Definition at line 226 of file depthcloud_encoder.cpp.

void depthcloud::DepthCloudEncoder::cloudToDepth ( const sensor_msgs::PointCloud2 &  cloud_msg,
sensor_msgs::ImagePtr  depth_msg,
sensor_msgs::ImagePtr  color_msg 
) [protected]

Definition at line 279 of file depthcloud_encoder.cpp.

Definition at line 115 of file depthcloud_encoder.cpp.

void depthcloud::DepthCloudEncoder::depthCB ( const sensor_msgs::ImageConstPtr &  depth_msg) [protected]

Definition at line 268 of file depthcloud_encoder.cpp.

void depthcloud::DepthCloudEncoder::depthColorCB ( const sensor_msgs::ImageConstPtr &  depth_msg,
const sensor_msgs::ImageConstPtr &  color_msg 
) [protected]

Definition at line 273 of file depthcloud_encoder.cpp.

void depthcloud::DepthCloudEncoder::depthInterpolation ( sensor_msgs::ImageConstPtr  depth_msg,
sensor_msgs::ImagePtr  depth_int_msg,
sensor_msgs::ImagePtr  mask_msg 
) [protected]

Definition at line 565 of file depthcloud_encoder.cpp.

void depthcloud::DepthCloudEncoder::dynReconfCb ( depthcloud_encoder::paramsConfig &  config,
uint32_t  level 
)

Definition at line 149 of file depthcloud_encoder.cpp.

void depthcloud::DepthCloudEncoder::process ( const sensor_msgs::ImageConstPtr &  depth_msg,
const sensor_msgs::ImageConstPtr &  color_msg,
const std::size_t  crop_size 
) [protected]

Definition at line 363 of file depthcloud_encoder.cpp.

void depthcloud::DepthCloudEncoder::subscribe ( std::string &  depth_topic,
std::string &  color_topic 
) [protected]

Definition at line 168 of file depthcloud_encoder.cpp.

void depthcloud::DepthCloudEncoder::subscribeCloud ( std::string &  cloud_topic) [protected]

Definition at line 155 of file depthcloud_encoder.cpp.

Definition at line 209 of file depthcloud_encoder.cpp.


Member Data Documentation

Definition at line 124 of file depthcloud_encoder.h.

Definition at line 109 of file depthcloud_encoder.h.

Definition at line 123 of file depthcloud_encoder.h.

Definition at line 108 of file depthcloud_encoder.h.

Definition at line 122 of file depthcloud_encoder.h.

Definition at line 107 of file depthcloud_encoder.h.

Definition at line 113 of file depthcloud_encoder.h.

Definition at line 134 of file depthcloud_encoder.h.

Definition at line 118 of file depthcloud_encoder.h.

Definition at line 125 of file depthcloud_encoder.h.

Definition at line 106 of file depthcloud_encoder.h.

Definition at line 120 of file depthcloud_encoder.h.

Definition at line 129 of file depthcloud_encoder.h.

Definition at line 130 of file depthcloud_encoder.h.

Definition at line 132 of file depthcloud_encoder.h.

Definition at line 134 of file depthcloud_encoder.h.

Definition at line 131 of file depthcloud_encoder.h.

Definition at line 102 of file depthcloud_encoder.h.

Definition at line 103 of file depthcloud_encoder.h.

Definition at line 116 of file depthcloud_encoder.h.

Definition at line 115 of file depthcloud_encoder.h.

Definition at line 121 of file depthcloud_encoder.h.

Definition at line 111 of file depthcloud_encoder.h.

Definition at line 127 of file depthcloud_encoder.h.


The documentation for this class was generated from the following files:


depthcloud_encoder
Author(s): Julius Kammer
autogenerated on Wed Apr 3 2019 02:59:18