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

Public Member Functions

 PointCloudXYZRGB ()
 
virtual ~PointCloudXYZRGB ()
 
- 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 ()
 

Private Types

typedef message_filters::sync_policies::ApproximateTime< sensor_msgs::Image, sensor_msgs::Image, sensor_msgs::CameraInfo > MyApproxSyncDepthPolicy
 
typedef message_filters::sync_policies::ApproximateTime< sensor_msgs::Image, stereo_msgs::DisparityImage, sensor_msgs::CameraInfo > MyApproxSyncDisparityPolicy
 
typedef message_filters::sync_policies::ApproximateTime< sensor_msgs::Image, sensor_msgs::Image, sensor_msgs::CameraInfo, sensor_msgs::CameraInfo > MyApproxSyncStereoPolicy
 
typedef message_filters::sync_policies::ExactTime< sensor_msgs::Image, sensor_msgs::Image, sensor_msgs::CameraInfo > MyExactSyncDepthPolicy
 
typedef message_filters::sync_policies::ExactTime< sensor_msgs::Image, stereo_msgs::DisparityImage, sensor_msgs::CameraInfo > MyExactSyncDisparityPolicy
 
typedef message_filters::sync_policies::ExactTime< sensor_msgs::Image, sensor_msgs::Image, sensor_msgs::CameraInfo, sensor_msgs::CameraInfo > MyExactSyncStereoPolicy
 

Private Member Functions

void depthCallback (const sensor_msgs::ImageConstPtr &image, const sensor_msgs::ImageConstPtr &imageDepth, const sensor_msgs::CameraInfoConstPtr &cameraInfo)
 
void disparityCallback (const sensor_msgs::ImageConstPtr &image, const stereo_msgs::DisparityImageConstPtr &imageDisparity, const sensor_msgs::CameraInfoConstPtr &cameraInfo)
 
virtual void onInit ()
 
void processAndPublish (pcl::PointCloud< pcl::PointXYZRGB >::Ptr &pclCloud, pcl::IndicesPtr &indices, const std_msgs::Header &header)
 
void rgbdImageCallback (const rtabmap_ros::RGBDImageConstPtr &image)
 
void stereoCallback (const sensor_msgs::ImageConstPtr &imageLeft, const sensor_msgs::ImageConstPtr &imageRight, const sensor_msgs::CameraInfoConstPtr &camInfoLeft, const sensor_msgs::CameraInfoConstPtr &camInfoRight)
 

Private Attributes

message_filters::Synchronizer< MyApproxSyncDepthPolicy > * approxSyncDepth_
 
message_filters::Synchronizer< MyApproxSyncDisparityPolicy > * approxSyncDisparity_
 
message_filters::Synchronizer< MyApproxSyncStereoPolicy > * approxSyncStereo_
 
message_filters::Subscriber< sensor_msgs::CameraInfo > cameraInfoLeft_
 
message_filters::Subscriber< sensor_msgs::CameraInfo > cameraInfoRight_
 
message_filters::Subscriber< sensor_msgs::CameraInfo > cameraInfoSub_
 
ros::Publisher cloudPub_
 
int decimation_
 
message_filters::Synchronizer< MyExactSyncDepthPolicy > * exactSyncDepth_
 
message_filters::Synchronizer< MyExactSyncDisparityPolicy > * exactSyncDisparity_
 
message_filters::Synchronizer< MyExactSyncStereoPolicy > * exactSyncStereo_
 
bool filterNaNs_
 
image_transport::SubscriberFilter imageDepthSub_
 
message_filters::Subscriber< stereo_msgs::DisparityImage > imageDisparitySub_
 
image_transport::SubscriberFilter imageLeft_
 
image_transport::SubscriberFilter imageRight_
 
image_transport::SubscriberFilter imageSub_
 
double maxDepth_
 
double minDepth_
 
int noiseFilterMinNeighbors_
 
double noiseFilterRadius_
 
int normalK_
 
double normalRadius_
 
ros::Subscriber rgbdImageSub_
 
std::vector< float > roiRatios_
 
rtabmap::ParametersMap stereoBMParameters_
 
double voxelSize_
 

Additional Inherited Members

- Protected Member Functions inherited from nodelet::Nodelet
ros::CallbackQueueInterfacegetMTCallbackQueue () const
 
ros::NodeHandlegetMTNodeHandle () const
 
ros::NodeHandlegetMTPrivateNodeHandle () const
 
const V_stringgetMyArgv () const
 
const std::stringgetName () 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 68 of file point_cloud_xyzrgb.cpp.

Member Typedef Documentation

◆ MyApproxSyncDepthPolicy

typedef message_filters::sync_policies::ApproximateTime<sensor_msgs::Image, sensor_msgs::Image, sensor_msgs::CameraInfo> rtabmap_ros::PointCloudXYZRGB::MyApproxSyncDepthPolicy
private

Definition at line 589 of file point_cloud_xyzrgb.cpp.

◆ MyApproxSyncDisparityPolicy

typedef message_filters::sync_policies::ApproximateTime<sensor_msgs::Image, stereo_msgs::DisparityImage, sensor_msgs::CameraInfo> rtabmap_ros::PointCloudXYZRGB::MyApproxSyncDisparityPolicy
private

Definition at line 592 of file point_cloud_xyzrgb.cpp.

◆ MyApproxSyncStereoPolicy

typedef message_filters::sync_policies::ApproximateTime<sensor_msgs::Image, sensor_msgs::Image, sensor_msgs::CameraInfo, sensor_msgs::CameraInfo> rtabmap_ros::PointCloudXYZRGB::MyApproxSyncStereoPolicy
private

Definition at line 595 of file point_cloud_xyzrgb.cpp.

◆ MyExactSyncDepthPolicy

typedef message_filters::sync_policies::ExactTime<sensor_msgs::Image, sensor_msgs::Image, sensor_msgs::CameraInfo> rtabmap_ros::PointCloudXYZRGB::MyExactSyncDepthPolicy
private

Definition at line 598 of file point_cloud_xyzrgb.cpp.

◆ MyExactSyncDisparityPolicy

typedef message_filters::sync_policies::ExactTime<sensor_msgs::Image, stereo_msgs::DisparityImage, sensor_msgs::CameraInfo> rtabmap_ros::PointCloudXYZRGB::MyExactSyncDisparityPolicy
private

Definition at line 601 of file point_cloud_xyzrgb.cpp.

◆ MyExactSyncStereoPolicy

typedef message_filters::sync_policies::ExactTime<sensor_msgs::Image, sensor_msgs::Image, sensor_msgs::CameraInfo, sensor_msgs::CameraInfo> rtabmap_ros::PointCloudXYZRGB::MyExactSyncStereoPolicy
private

Definition at line 604 of file point_cloud_xyzrgb.cpp.

Constructor & Destructor Documentation

◆ PointCloudXYZRGB()

rtabmap_ros::PointCloudXYZRGB::PointCloudXYZRGB ( )
inline

Definition at line 71 of file point_cloud_xyzrgb.cpp.

◆ ~PointCloudXYZRGB()

virtual rtabmap_ros::PointCloudXYZRGB::~PointCloudXYZRGB ( )
inlinevirtual

Definition at line 89 of file point_cloud_xyzrgb.cpp.

Member Function Documentation

◆ depthCallback()

void rtabmap_ros::PointCloudXYZRGB::depthCallback ( const sensor_msgs::ImageConstPtr &  image,
const sensor_msgs::ImageConstPtr &  imageDepth,
const sensor_msgs::CameraInfoConstPtr &  cameraInfo 
)
inlineprivate

Definition at line 257 of file point_cloud_xyzrgb.cpp.

◆ disparityCallback()

void rtabmap_ros::PointCloudXYZRGB::disparityCallback ( const sensor_msgs::ImageConstPtr &  image,
const stereo_msgs::DisparityImageConstPtr &  imageDisparity,
const sensor_msgs::CameraInfoConstPtr &  cameraInfo 
)
inlineprivate

Definition at line 356 of file point_cloud_xyzrgb.cpp.

◆ onInit()

virtual void rtabmap_ros::PointCloudXYZRGB::onInit ( )
inlineprivatevirtual

Implements nodelet::Nodelet.

Definition at line 106 of file point_cloud_xyzrgb.cpp.

◆ processAndPublish()

void rtabmap_ros::PointCloudXYZRGB::processAndPublish ( pcl::PointCloud< pcl::PointXYZRGB >::Ptr &  pclCloud,
pcl::IndicesPtr &  indices,
const std_msgs::Header header 
)
inlineprivate

Definition at line 508 of file point_cloud_xyzrgb.cpp.

◆ rgbdImageCallback()

void rtabmap_ros::PointCloudXYZRGB::rgbdImageCallback ( const rtabmap_ros::RGBDImageConstPtr &  image)
inlineprivate

Definition at line 481 of file point_cloud_xyzrgb.cpp.

◆ stereoCallback()

void rtabmap_ros::PointCloudXYZRGB::stereoCallback ( const sensor_msgs::ImageConstPtr &  imageLeft,
const sensor_msgs::ImageConstPtr &  imageRight,
const sensor_msgs::CameraInfoConstPtr &  camInfoLeft,
const sensor_msgs::CameraInfoConstPtr &  camInfoRight 
)
inlineprivate

Definition at line 420 of file point_cloud_xyzrgb.cpp.

Member Data Documentation

◆ approxSyncDepth_

message_filters::Synchronizer<MyApproxSyncDepthPolicy>* rtabmap_ros::PointCloudXYZRGB::approxSyncDepth_
private

Definition at line 590 of file point_cloud_xyzrgb.cpp.

◆ approxSyncDisparity_

message_filters::Synchronizer<MyApproxSyncDisparityPolicy>* rtabmap_ros::PointCloudXYZRGB::approxSyncDisparity_
private

Definition at line 593 of file point_cloud_xyzrgb.cpp.

◆ approxSyncStereo_

message_filters::Synchronizer<MyApproxSyncStereoPolicy>* rtabmap_ros::PointCloudXYZRGB::approxSyncStereo_
private

Definition at line 596 of file point_cloud_xyzrgb.cpp.

◆ cameraInfoLeft_

message_filters::Subscriber<sensor_msgs::CameraInfo> rtabmap_ros::PointCloudXYZRGB::cameraInfoLeft_
private

Definition at line 586 of file point_cloud_xyzrgb.cpp.

◆ cameraInfoRight_

message_filters::Subscriber<sensor_msgs::CameraInfo> rtabmap_ros::PointCloudXYZRGB::cameraInfoRight_
private

Definition at line 587 of file point_cloud_xyzrgb.cpp.

◆ cameraInfoSub_

message_filters::Subscriber<sensor_msgs::CameraInfo> rtabmap_ros::PointCloudXYZRGB::cameraInfoSub_
private

Definition at line 580 of file point_cloud_xyzrgb.cpp.

◆ cloudPub_

ros::Publisher rtabmap_ros::PointCloudXYZRGB::cloudPub_
private

Definition at line 574 of file point_cloud_xyzrgb.cpp.

◆ decimation_

int rtabmap_ros::PointCloudXYZRGB::decimation_
private

Definition at line 565 of file point_cloud_xyzrgb.cpp.

◆ exactSyncDepth_

message_filters::Synchronizer<MyExactSyncDepthPolicy>* rtabmap_ros::PointCloudXYZRGB::exactSyncDepth_
private

Definition at line 599 of file point_cloud_xyzrgb.cpp.

◆ exactSyncDisparity_

message_filters::Synchronizer<MyExactSyncDisparityPolicy>* rtabmap_ros::PointCloudXYZRGB::exactSyncDisparity_
private

Definition at line 602 of file point_cloud_xyzrgb.cpp.

◆ exactSyncStereo_

message_filters::Synchronizer<MyExactSyncStereoPolicy>* rtabmap_ros::PointCloudXYZRGB::exactSyncStereo_
private

Definition at line 605 of file point_cloud_xyzrgb.cpp.

◆ filterNaNs_

bool rtabmap_ros::PointCloudXYZRGB::filterNaNs_
private

Definition at line 570 of file point_cloud_xyzrgb.cpp.

◆ imageDepthSub_

image_transport::SubscriberFilter rtabmap_ros::PointCloudXYZRGB::imageDepthSub_
private

Definition at line 579 of file point_cloud_xyzrgb.cpp.

◆ imageDisparitySub_

message_filters::Subscriber<stereo_msgs::DisparityImage> rtabmap_ros::PointCloudXYZRGB::imageDisparitySub_
private

Definition at line 582 of file point_cloud_xyzrgb.cpp.

◆ imageLeft_

image_transport::SubscriberFilter rtabmap_ros::PointCloudXYZRGB::imageLeft_
private

Definition at line 584 of file point_cloud_xyzrgb.cpp.

◆ imageRight_

image_transport::SubscriberFilter rtabmap_ros::PointCloudXYZRGB::imageRight_
private

Definition at line 585 of file point_cloud_xyzrgb.cpp.

◆ imageSub_

image_transport::SubscriberFilter rtabmap_ros::PointCloudXYZRGB::imageSub_
private

Definition at line 578 of file point_cloud_xyzrgb.cpp.

◆ maxDepth_

double rtabmap_ros::PointCloudXYZRGB::maxDepth_
private

Definition at line 562 of file point_cloud_xyzrgb.cpp.

◆ minDepth_

double rtabmap_ros::PointCloudXYZRGB::minDepth_
private

Definition at line 563 of file point_cloud_xyzrgb.cpp.

◆ noiseFilterMinNeighbors_

int rtabmap_ros::PointCloudXYZRGB::noiseFilterMinNeighbors_
private

Definition at line 567 of file point_cloud_xyzrgb.cpp.

◆ noiseFilterRadius_

double rtabmap_ros::PointCloudXYZRGB::noiseFilterRadius_
private

Definition at line 566 of file point_cloud_xyzrgb.cpp.

◆ normalK_

int rtabmap_ros::PointCloudXYZRGB::normalK_
private

Definition at line 568 of file point_cloud_xyzrgb.cpp.

◆ normalRadius_

double rtabmap_ros::PointCloudXYZRGB::normalRadius_
private

Definition at line 569 of file point_cloud_xyzrgb.cpp.

◆ rgbdImageSub_

ros::Subscriber rtabmap_ros::PointCloudXYZRGB::rgbdImageSub_
private

Definition at line 576 of file point_cloud_xyzrgb.cpp.

◆ roiRatios_

std::vector<float> rtabmap_ros::PointCloudXYZRGB::roiRatios_
private

Definition at line 571 of file point_cloud_xyzrgb.cpp.

◆ stereoBMParameters_

rtabmap::ParametersMap rtabmap_ros::PointCloudXYZRGB::stereoBMParameters_
private

Definition at line 572 of file point_cloud_xyzrgb.cpp.

◆ voxelSize_

double rtabmap_ros::PointCloudXYZRGB::voxelSize_
private

Definition at line 564 of file point_cloud_xyzrgb.cpp.


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


rtabmap_ros
Author(s): Mathieu Labbe
autogenerated on Tue Jan 24 2023 04:04:40