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

Private Types

typedef ApproximateTime< Image, CameraInfo, CameraInfo, DisparityImage > ApproximatePolicy
 
typedef message_filters::Synchronizer< ApproximatePolicyApproximateSync
 
typedef ExactTime< Image, CameraInfo, CameraInfo, DisparityImage > ExactPolicy
 
typedef message_filters::Synchronizer< ExactPolicyExactSync
 

Private Member Functions

void connectCb ()
 
void imageCb (const ImageConstPtr &l_image_msg, const CameraInfoConstPtr &l_info_msg, const CameraInfoConstPtr &r_info_msg, const DisparityImageConstPtr &disp_msg)
 
virtual void onInit ()
 

Private Attributes

boost::shared_ptr< ApproximateSyncapproximate_sync_
 
boost::mutex connect_mutex_
 
boost::shared_ptr< ExactSyncexact_sync_
 
boost::shared_ptr< image_transport::ImageTransportit_
 
image_geometry::StereoCameraModel model_
 
cv::Mat_< cv::Vec3f > points_mat_
 
ros::Publisher pub_points2_
 
message_filters::Subscriber< DisparityImage > sub_disparity_
 
image_transport::SubscriberFilter sub_l_image_
 
message_filters::Subscriber< CameraInfo > sub_l_info_
 
message_filters::Subscriber< CameraInfo > sub_r_info_
 

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 92 of file point_cloud2.cpp.

Member Typedef Documentation

◆ ApproximatePolicy

typedef ApproximateTime<Image, CameraInfo, CameraInfo, DisparityImage> stereo_image_proc::PointCloud2Nodelet::ApproximatePolicy
private

Definition at line 101 of file point_cloud2.cpp.

◆ ApproximateSync

Definition at line 103 of file point_cloud2.cpp.

◆ ExactPolicy

typedef ExactTime<Image, CameraInfo, CameraInfo, DisparityImage> stereo_image_proc::PointCloud2Nodelet::ExactPolicy
private

Definition at line 100 of file point_cloud2.cpp.

◆ ExactSync

Definition at line 102 of file point_cloud2.cpp.

Member Function Documentation

◆ connectCb()

void stereo_image_proc::PointCloud2Nodelet::connectCb ( )
private

Definition at line 162 of file point_cloud2.cpp.

◆ imageCb()

void stereo_image_proc::PointCloud2Nodelet::imageCb ( const ImageConstPtr &  l_image_msg,
const CameraInfoConstPtr &  l_info_msg,
const CameraInfoConstPtr &  r_info_msg,
const DisparityImageConstPtr &  disp_msg 
)
private

Definition at line 191 of file point_cloud2.cpp.

◆ onInit()

void stereo_image_proc::PointCloud2Nodelet::onInit ( )
privatevirtual

Implements nodelet::Nodelet.

Definition at line 125 of file point_cloud2.cpp.

Member Data Documentation

◆ approximate_sync_

boost::shared_ptr<ApproximateSync> stereo_image_proc::PointCloud2Nodelet::approximate_sync_
private

Definition at line 105 of file point_cloud2.cpp.

◆ connect_mutex_

boost::mutex stereo_image_proc::PointCloud2Nodelet::connect_mutex_
private

Definition at line 108 of file point_cloud2.cpp.

◆ exact_sync_

boost::shared_ptr<ExactSync> stereo_image_proc::PointCloud2Nodelet::exact_sync_
private

Definition at line 104 of file point_cloud2.cpp.

◆ it_

boost::shared_ptr<image_transport::ImageTransport> stereo_image_proc::PointCloud2Nodelet::it_
private

Definition at line 94 of file point_cloud2.cpp.

◆ model_

image_geometry::StereoCameraModel stereo_image_proc::PointCloud2Nodelet::model_
private

Definition at line 112 of file point_cloud2.cpp.

◆ points_mat_

cv::Mat_<cv::Vec3f> stereo_image_proc::PointCloud2Nodelet::points_mat_
private

Definition at line 113 of file point_cloud2.cpp.

◆ pub_points2_

ros::Publisher stereo_image_proc::PointCloud2Nodelet::pub_points2_
private

Definition at line 109 of file point_cloud2.cpp.

◆ sub_disparity_

message_filters::Subscriber<DisparityImage> stereo_image_proc::PointCloud2Nodelet::sub_disparity_
private

Definition at line 99 of file point_cloud2.cpp.

◆ sub_l_image_

image_transport::SubscriberFilter stereo_image_proc::PointCloud2Nodelet::sub_l_image_
private

Definition at line 97 of file point_cloud2.cpp.

◆ sub_l_info_

message_filters::Subscriber<CameraInfo> stereo_image_proc::PointCloud2Nodelet::sub_l_info_
private

Definition at line 98 of file point_cloud2.cpp.

◆ sub_r_info_

message_filters::Subscriber<CameraInfo> stereo_image_proc::PointCloud2Nodelet::sub_r_info_
private

Definition at line 98 of file point_cloud2.cpp.


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


stereo_image_proc
Author(s): Patrick Mihelich, Kurt Konolige, Jeremy Leibs
autogenerated on Wed May 24 2023 02:56:47