#include <depthcloud_encoder.h>
|
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 () |
|
Definition at line 67 of file depthcloud_encoder.h.
depthcloud::DepthCloudEncoder::~DepthCloudEncoder |
( |
| ) |
|
|
virtual |
void depthcloud::DepthCloudEncoder::cameraInfoCb |
( |
const sensor_msgs::CameraInfoConstPtr & |
cam_info_msg | ) |
|
|
protected |
void depthcloud::DepthCloudEncoder::cloudCB |
( |
const sensor_msgs::PointCloud2 & |
cloud_msg | ) |
|
|
protected |
void depthcloud::DepthCloudEncoder::cloudToDepth |
( |
const sensor_msgs::PointCloud2 & |
cloud_msg, |
|
|
sensor_msgs::ImagePtr |
depth_msg, |
|
|
sensor_msgs::ImagePtr |
color_msg |
|
) |
| |
|
protected |
void depthcloud::DepthCloudEncoder::connectCb |
( |
| ) |
|
|
protected |
void depthcloud::DepthCloudEncoder::depthCB |
( |
const sensor_msgs::ImageConstPtr & |
depth_msg | ) |
|
|
protected |
void depthcloud::DepthCloudEncoder::depthColorCB |
( |
const sensor_msgs::ImageConstPtr & |
depth_msg, |
|
|
const sensor_msgs::ImageConstPtr & |
color_msg |
|
) |
| |
|
protected |
void depthcloud::DepthCloudEncoder::depthInterpolation |
( |
sensor_msgs::ImageConstPtr |
depth_msg, |
|
|
sensor_msgs::ImagePtr |
depth_int_msg, |
|
|
sensor_msgs::ImagePtr |
mask_msg |
|
) |
| |
|
protected |
void depthcloud::DepthCloudEncoder::dynReconfCb |
( |
depthcloud_encoder::paramsConfig & |
config, |
|
|
uint32_t |
level |
|
) |
| |
void depthcloud::DepthCloudEncoder::process |
( |
const sensor_msgs::ImageConstPtr & |
depth_msg, |
|
|
const sensor_msgs::ImageConstPtr & |
color_msg, |
|
|
const std::size_t |
crop_size |
|
) |
| |
|
protected |
void depthcloud::DepthCloudEncoder::subscribe |
( |
std::string & |
depth_topic, |
|
|
std::string & |
color_topic |
|
) |
| |
|
protected |
void depthcloud::DepthCloudEncoder::subscribeCloud |
( |
std::string & |
cloud_topic | ) |
|
|
protected |
void depthcloud::DepthCloudEncoder::unsubscribe |
( |
| ) |
|
|
protected |
std::string depthcloud::DepthCloudEncoder::camera_frame_id_ |
|
protected |
std::string depthcloud::DepthCloudEncoder::camera_info_topic_ |
|
protected |
std::string depthcloud::DepthCloudEncoder::cloud_topic_ |
|
protected |
boost::mutex depthcloud::DepthCloudEncoder::connect_mutex_ |
|
protected |
bool depthcloud::DepthCloudEncoder::connectivityExceptionFlag |
|
protected |
int depthcloud::DepthCloudEncoder::crop_size_ |
|
protected |
std::string depthcloud::DepthCloudEncoder::depth_source_ |
|
protected |
std::string depthcloud::DepthCloudEncoder::depthmap_topic_ |
|
protected |
double depthcloud::DepthCloudEncoder::f_ |
|
protected |
double depthcloud::DepthCloudEncoder::f_mult_factor_ |
|
protected |
bool depthcloud::DepthCloudEncoder::latch_ |
|
protected |
bool depthcloud::DepthCloudEncoder::lookupExceptionFlag |
|
protected |
float depthcloud::DepthCloudEncoder::max_depth_per_tile_ |
|
protected |
std::string depthcloud::DepthCloudEncoder::rgb_image_topic_ |
|
protected |
The documentation for this class was generated from the following files: