Private Types | Private Member Functions | Private Attributes | List of all members
depth_image_proc::PointCloudXyzRadialNodelet Class Reference
Inheritance diagram for depth_image_proc::PointCloudXyzRadialNodelet:
Inheritance graph
[legend]

Private Types

typedef sensor_msgs::PointCloud2 PointCloud
 

Private Member Functions

void connectCb ()
 
template<typename T >
void convert (const sensor_msgs::ImageConstPtr &depth_msg, PointCloud::Ptr &cloud_msg)
 
void depthCb (const sensor_msgs::ImageConstPtr &depth_msg, const sensor_msgs::CameraInfoConstPtr &info_msg)
 
virtual void onInit ()
 

Private Attributes

cv::Mat binned
 
boost::mutex connect_mutex_
 
std::vector< double > D_
 
int height_
 
boost::shared_ptr< image_transport::ImageTransportit_
 
boost::array< double, 9 > K_
 
ros::Publisher pub_point_cloud_
 
int queue_size_
 
image_transport::CameraSubscriber sub_depth_
 
int width_
 

Additional Inherited Members

- Public Member Functions inherited from nodelet::Nodelet
void init (const std::string &name, const M_string &remapping_args, const V_string &my_argv, ros::CallbackQueueInterface *st_queue=NULL, ros::CallbackQueueInterface *mt_queue=NULL)
 
 Nodelet ()
 
virtual ~Nodelet ()
 
- Protected Member Functions inherited from nodelet::Nodelet
ros::CallbackQueueInterfacegetMTCallbackQueue () const
 
ros::NodeHandlegetMTNodeHandle () const
 
ros::NodeHandlegetMTPrivateNodeHandle () const
 
const V_stringgetMyArgv () const
 
const std::string & getName () const
 
ros::NodeHandlegetNodeHandle () const
 
ros::NodeHandlegetPrivateNodeHandle () const
 
const M_stringgetRemappingArgs () const
 
ros::CallbackQueueInterfacegetSTCallbackQueue () const
 
std::string getSuffixedName (const std::string &suffix) const
 

Detailed Description

Definition at line 81 of file point_cloud_xyz_radial.cpp.

Member Typedef Documentation

◆ PointCloud

typedef sensor_msgs::PointCloud2 depth_image_proc::PointCloudXyzRadialNodelet::PointCloud
private

Definition at line 122 of file point_cloud_xyz_radial.cpp.

Member Function Documentation

◆ connectCb()

void depth_image_proc::PointCloudXyzRadialNodelet::connectCb ( )
private

Definition at line 174 of file point_cloud_xyz_radial.cpp.

◆ convert()

template<typename T >
void depth_image_proc::PointCloudXyzRadialNodelet::convert ( const sensor_msgs::ImageConstPtr &  depth_msg,
PointCloud::Ptr &  cloud_msg 
)
private

Definition at line 232 of file point_cloud_xyz_radial.cpp.

◆ depthCb()

void depth_image_proc::PointCloudXyzRadialNodelet::depthCb ( const sensor_msgs::ImageConstPtr &  depth_msg,
const sensor_msgs::CameraInfoConstPtr &  info_msg 
)
private

Definition at line 191 of file point_cloud_xyz_radial.cpp.

◆ onInit()

void depth_image_proc::PointCloudXyzRadialNodelet::onInit ( )
privatevirtual

Implements nodelet::Nodelet.

Definition at line 156 of file point_cloud_xyz_radial.cpp.

Member Data Documentation

◆ binned

cv::Mat depth_image_proc::PointCloudXyzRadialNodelet::binned
private

Definition at line 132 of file point_cloud_xyz_radial.cpp.

◆ connect_mutex_

boost::mutex depth_image_proc::PointCloudXyzRadialNodelet::connect_mutex_
private

Definition at line 121 of file point_cloud_xyz_radial.cpp.

◆ D_

std::vector<double> depth_image_proc::PointCloudXyzRadialNodelet::D_
private

Definition at line 126 of file point_cloud_xyz_radial.cpp.

◆ height_

int depth_image_proc::PointCloudXyzRadialNodelet::height_
private

Definition at line 130 of file point_cloud_xyz_radial.cpp.

◆ it_

boost::shared_ptr<image_transport::ImageTransport> depth_image_proc::PointCloudXyzRadialNodelet::it_
private

Definition at line 116 of file point_cloud_xyz_radial.cpp.

◆ K_

boost::array<double, 9> depth_image_proc::PointCloudXyzRadialNodelet::K_
private

Definition at line 127 of file point_cloud_xyz_radial.cpp.

◆ pub_point_cloud_

ros::Publisher depth_image_proc::PointCloudXyzRadialNodelet::pub_point_cloud_
private

Definition at line 123 of file point_cloud_xyz_radial.cpp.

◆ queue_size_

int depth_image_proc::PointCloudXyzRadialNodelet::queue_size_
private

Definition at line 118 of file point_cloud_xyz_radial.cpp.

◆ sub_depth_

image_transport::CameraSubscriber depth_image_proc::PointCloudXyzRadialNodelet::sub_depth_
private

Definition at line 117 of file point_cloud_xyz_radial.cpp.

◆ width_

int depth_image_proc::PointCloudXyzRadialNodelet::width_
private

Definition at line 129 of file point_cloud_xyz_radial.cpp.


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


depth_image_proc
Author(s): Patrick Mihelich
autogenerated on Wed Jan 24 2024 03:57:15