Public Member Functions | Protected Types | Protected Member Functions | Protected Attributes | List of all members
depthcloud::DepthCloudEncoder Class Reference

#include <depthcloud_encoder.h>

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< SyncPolicyDepthColorSynchronizerDepthColor
 
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::SubscriberFiltercolor_sub_
 
boost::mutex connect_mutex_
 
bool connectivityExceptionFlag
 
int crop_size_
 
std::string depth_source_
 
boost::shared_ptr< image_transport::SubscriberFilterdepth_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< SynchronizerDepthColorsync_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

depthcloud::DepthCloudEncoder::DepthCloudEncoder ( ros::NodeHandle nh,
ros::NodeHandle pnh 
)

Definition at line 59 of file depthcloud_encoder.cpp.

depthcloud::DepthCloudEncoder::~DepthCloudEncoder ( )
virtual

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.

void depthcloud::DepthCloudEncoder::connectCb ( )
protected

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.

void depthcloud::DepthCloudEncoder::unsubscribe ( )
protected

Definition at line 209 of file depthcloud_encoder.cpp.

Member Data Documentation

std::string depthcloud::DepthCloudEncoder::camera_frame_id_
protected

Definition at line 124 of file depthcloud_encoder.h.

ros::Subscriber depthcloud::DepthCloudEncoder::camera_info_sub_
protected

Definition at line 109 of file depthcloud_encoder.h.

std::string depthcloud::DepthCloudEncoder::camera_info_topic_
protected

Definition at line 123 of file depthcloud_encoder.h.

ros::Subscriber depthcloud::DepthCloudEncoder::cloud_sub_
protected

Definition at line 108 of file depthcloud_encoder.h.

std::string depthcloud::DepthCloudEncoder::cloud_topic_
protected

Definition at line 122 of file depthcloud_encoder.h.

boost::shared_ptr<image_transport::SubscriberFilter > depthcloud::DepthCloudEncoder::color_sub_
protected

Definition at line 107 of file depthcloud_encoder.h.

boost::mutex depthcloud::DepthCloudEncoder::connect_mutex_
protected

Definition at line 113 of file depthcloud_encoder.h.

bool depthcloud::DepthCloudEncoder::connectivityExceptionFlag
protected

Definition at line 134 of file depthcloud_encoder.h.

int depthcloud::DepthCloudEncoder::crop_size_
protected

Definition at line 118 of file depthcloud_encoder.h.

std::string depthcloud::DepthCloudEncoder::depth_source_
protected

Definition at line 125 of file depthcloud_encoder.h.

boost::shared_ptr<image_transport::SubscriberFilter > depthcloud::DepthCloudEncoder::depth_sub_
protected

Definition at line 106 of file depthcloud_encoder.h.

std::string depthcloud::DepthCloudEncoder::depthmap_topic_
protected

Definition at line 120 of file depthcloud_encoder.h.

double depthcloud::DepthCloudEncoder::f_
protected

Definition at line 129 of file depthcloud_encoder.h.

double depthcloud::DepthCloudEncoder::f_mult_factor_
protected

Definition at line 130 of file depthcloud_encoder.h.

bool depthcloud::DepthCloudEncoder::latch_
protected

Definition at line 132 of file depthcloud_encoder.h.

bool depthcloud::DepthCloudEncoder::lookupExceptionFlag
protected

Definition at line 134 of file depthcloud_encoder.h.

float depthcloud::DepthCloudEncoder::max_depth_per_tile_
protected

Definition at line 131 of file depthcloud_encoder.h.

ros::NodeHandle& depthcloud::DepthCloudEncoder::nh_
protected

Definition at line 102 of file depthcloud_encoder.h.

ros::NodeHandle& depthcloud::DepthCloudEncoder::pnh_
protected

Definition at line 103 of file depthcloud_encoder.h.

image_transport::Publisher depthcloud::DepthCloudEncoder::pub_
protected

Definition at line 116 of file depthcloud_encoder.h.

image_transport::ImageTransport depthcloud::DepthCloudEncoder::pub_it_
protected

Definition at line 115 of file depthcloud_encoder.h.

std::string depthcloud::DepthCloudEncoder::rgb_image_topic_
protected

Definition at line 121 of file depthcloud_encoder.h.

boost::shared_ptr<SynchronizerDepthColor> depthcloud::DepthCloudEncoder::sync_depth_color_
protected

Definition at line 111 of file depthcloud_encoder.h.

tf::TransformListener depthcloud::DepthCloudEncoder::tf_listener_
protected

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 Mon Jun 10 2019 13:06:12