Private Types | Private Member Functions | Private Attributes
depth_image_proc::PointCloudXyziRadialNodelet Class Reference
Inheritance diagram for depth_image_proc::PointCloudXyziRadialNodelet:
Inheritance graph
[legend]

List of all members.

Private Types

typedef sensor_msgs::PointCloud2 PointCloud
typedef
message_filters::Synchronizer
< SyncPolicy
Synchronizer

Private Member Functions

void connectCb ()
template<typename T >
void convert_depth (const sensor_msgs::ImageConstPtr &depth_msg, PointCloud::Ptr &cloud_msg)
template<typename T >
void convert_intensity (const sensor_msgs::ImageConstPtr &inten_msg, PointCloud::Ptr &cloud_msg)
void imageCb (const sensor_msgs::ImageConstPtr &depth_msg, const sensor_msgs::ImageConstPtr &intensity_msg_in, const sensor_msgs::CameraInfoConstPtr &info_msg)
cv::Mat initMatrix (cv::Mat cameraMatrix, cv::Mat distCoeffs, int width, int height, bool radial)
virtual void onInit ()

Private Attributes

boost::mutex connect_mutex_
std::vector< double > D_
boost::shared_ptr
< image_transport::ImageTransport
depth_it_
int height_
boost::shared_ptr
< image_transport::ImageTransport
intensity_it_
ros::NodeHandlePtr intensity_nh_
boost::array< double, 9 > K_
ros::Publisher pub_point_cloud_
int queue_size_
image_transport::SubscriberFilter sub_depth_
message_filters::Subscriber
< sensor_msgs::CameraInfo > 
sub_info_
image_transport::SubscriberFilter sub_intensity_
boost::shared_ptr< Synchronizersync_
cv::Mat transform_
int width_

Detailed Description

Definition at line 54 of file point_cloud_xyzi_radial.cpp.


Member Typedef Documentation

typedef sensor_msgs::PointCloud2 depth_image_proc::PointCloudXyziRadialNodelet::PointCloud [private]

Definition at line 67 of file point_cloud_xyzi_radial.cpp.

Definition at line 71 of file point_cloud_xyzi_radial.cpp.


Member Function Documentation

Definition at line 169 of file point_cloud_xyzi_radial.cpp.

template<typename T >
void depth_image_proc::PointCloudXyziRadialNodelet::convert_depth ( const sensor_msgs::ImageConstPtr &  depth_msg,
PointCloud::Ptr &  cloud_msg 
) [private]

Definition at line 258 of file point_cloud_xyzi_radial.cpp.

template<typename T >
void depth_image_proc::PointCloudXyziRadialNodelet::convert_intensity ( const sensor_msgs::ImageConstPtr &  inten_msg,
PointCloud::Ptr &  cloud_msg 
) [private]

Definition at line 293 of file point_cloud_xyzi_radial.cpp.

void depth_image_proc::PointCloudXyziRadialNodelet::imageCb ( const sensor_msgs::ImageConstPtr &  depth_msg,
const sensor_msgs::ImageConstPtr &  intensity_msg_in,
const sensor_msgs::CameraInfoConstPtr &  info_msg 
) [private]

Definition at line 196 of file point_cloud_xyzi_radial.cpp.

cv::Mat depth_image_proc::PointCloudXyziRadialNodelet::initMatrix ( cv::Mat  cameraMatrix,
cv::Mat  distCoeffs,
int  width,
int  height,
bool  radial 
) [private]

Definition at line 101 of file point_cloud_xyzi_radial.cpp.

Implements nodelet::Nodelet.

Definition at line 143 of file point_cloud_xyzi_radial.cpp.


Member Data Documentation

Definition at line 66 of file point_cloud_xyzi_radial.cpp.

Definition at line 74 of file point_cloud_xyzi_radial.cpp.

Definition at line 59 of file point_cloud_xyzi_radial.cpp.

Definition at line 78 of file point_cloud_xyzi_radial.cpp.

Definition at line 59 of file point_cloud_xyzi_radial.cpp.

Definition at line 56 of file point_cloud_xyzi_radial.cpp.

boost::array<double, 9> depth_image_proc::PointCloudXyziRadialNodelet::K_ [private]

Definition at line 75 of file point_cloud_xyzi_radial.cpp.

Definition at line 68 of file point_cloud_xyzi_radial.cpp.

Definition at line 63 of file point_cloud_xyzi_radial.cpp.

Definition at line 60 of file point_cloud_xyzi_radial.cpp.

Definition at line 61 of file point_cloud_xyzi_radial.cpp.

Definition at line 60 of file point_cloud_xyzi_radial.cpp.

Definition at line 72 of file point_cloud_xyzi_radial.cpp.

Definition at line 80 of file point_cloud_xyzi_radial.cpp.

Definition at line 77 of file point_cloud_xyzi_radial.cpp.


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


depth_image_proc
Author(s): Patrick Mihelich
autogenerated on Wed May 1 2019 02:51:42