Public Member Functions | |
PointCloudXYZRGB () | |
virtual | ~PointCloudXYZRGB () |
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_ |
Definition at line 68 of file point_cloud_xyzrgb.cpp.
typedef message_filters::sync_policies::ApproximateTime<sensor_msgs::Image, sensor_msgs::Image, sensor_msgs::CameraInfo> rtabmap_ros::PointCloudXYZRGB::MyApproxSyncDepthPolicy [private] |
Definition at line 548 of file point_cloud_xyzrgb.cpp.
typedef message_filters::sync_policies::ApproximateTime<sensor_msgs::Image, stereo_msgs::DisparityImage, sensor_msgs::CameraInfo> rtabmap_ros::PointCloudXYZRGB::MyApproxSyncDisparityPolicy [private] |
Definition at line 551 of file point_cloud_xyzrgb.cpp.
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 554 of file point_cloud_xyzrgb.cpp.
typedef message_filters::sync_policies::ExactTime<sensor_msgs::Image, sensor_msgs::Image, sensor_msgs::CameraInfo> rtabmap_ros::PointCloudXYZRGB::MyExactSyncDepthPolicy [private] |
Definition at line 557 of file point_cloud_xyzrgb.cpp.
typedef message_filters::sync_policies::ExactTime<sensor_msgs::Image, stereo_msgs::DisparityImage, sensor_msgs::CameraInfo> rtabmap_ros::PointCloudXYZRGB::MyExactSyncDisparityPolicy [private] |
Definition at line 560 of file point_cloud_xyzrgb.cpp.
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 563 of file point_cloud_xyzrgb.cpp.
rtabmap_ros::PointCloudXYZRGB::PointCloudXYZRGB | ( | ) | [inline] |
Definition at line 71 of file point_cloud_xyzrgb.cpp.
virtual rtabmap_ros::PointCloudXYZRGB::~PointCloudXYZRGB | ( | ) | [inline, virtual] |
Definition at line 89 of file point_cloud_xyzrgb.cpp.
void rtabmap_ros::PointCloudXYZRGB::depthCallback | ( | const sensor_msgs::ImageConstPtr & | image, |
const sensor_msgs::ImageConstPtr & | imageDepth, | ||
const sensor_msgs::CameraInfoConstPtr & | cameraInfo | ||
) | [inline, private] |
Definition at line 250 of file point_cloud_xyzrgb.cpp.
void rtabmap_ros::PointCloudXYZRGB::disparityCallback | ( | const sensor_msgs::ImageConstPtr & | image, |
const stereo_msgs::DisparityImageConstPtr & | imageDisparity, | ||
const sensor_msgs::CameraInfoConstPtr & | cameraInfo | ||
) | [inline, private] |
Definition at line 323 of file point_cloud_xyzrgb.cpp.
virtual void rtabmap_ros::PointCloudXYZRGB::onInit | ( | ) | [inline, private, virtual] |
Implements nodelet::Nodelet.
Definition at line 106 of file point_cloud_xyzrgb.cpp.
void rtabmap_ros::PointCloudXYZRGB::processAndPublish | ( | pcl::PointCloud< pcl::PointXYZRGB >::Ptr & | pclCloud, |
pcl::IndicesPtr & | indices, | ||
const std_msgs::Header & | header | ||
) | [inline, private] |
Definition at line 468 of file point_cloud_xyzrgb.cpp.
void rtabmap_ros::PointCloudXYZRGB::rgbdImageCallback | ( | const rtabmap_ros::RGBDImageConstPtr & | image | ) | [inline, private] |
Definition at line 442 of file point_cloud_xyzrgb.cpp.
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 | ||
) | [inline, private] |
Definition at line 385 of file point_cloud_xyzrgb.cpp.
message_filters::Synchronizer<MyApproxSyncDepthPolicy>* rtabmap_ros::PointCloudXYZRGB::approxSyncDepth_ [private] |
Definition at line 549 of file point_cloud_xyzrgb.cpp.
message_filters::Synchronizer<MyApproxSyncDisparityPolicy>* rtabmap_ros::PointCloudXYZRGB::approxSyncDisparity_ [private] |
Definition at line 552 of file point_cloud_xyzrgb.cpp.
message_filters::Synchronizer<MyApproxSyncStereoPolicy>* rtabmap_ros::PointCloudXYZRGB::approxSyncStereo_ [private] |
Definition at line 555 of file point_cloud_xyzrgb.cpp.
message_filters::Subscriber<sensor_msgs::CameraInfo> rtabmap_ros::PointCloudXYZRGB::cameraInfoLeft_ [private] |
Definition at line 545 of file point_cloud_xyzrgb.cpp.
message_filters::Subscriber<sensor_msgs::CameraInfo> rtabmap_ros::PointCloudXYZRGB::cameraInfoRight_ [private] |
Definition at line 546 of file point_cloud_xyzrgb.cpp.
message_filters::Subscriber<sensor_msgs::CameraInfo> rtabmap_ros::PointCloudXYZRGB::cameraInfoSub_ [private] |
Definition at line 539 of file point_cloud_xyzrgb.cpp.
Definition at line 533 of file point_cloud_xyzrgb.cpp.
int rtabmap_ros::PointCloudXYZRGB::decimation_ [private] |
Definition at line 524 of file point_cloud_xyzrgb.cpp.
message_filters::Synchronizer<MyExactSyncDepthPolicy>* rtabmap_ros::PointCloudXYZRGB::exactSyncDepth_ [private] |
Definition at line 558 of file point_cloud_xyzrgb.cpp.
message_filters::Synchronizer<MyExactSyncDisparityPolicy>* rtabmap_ros::PointCloudXYZRGB::exactSyncDisparity_ [private] |
Definition at line 561 of file point_cloud_xyzrgb.cpp.
message_filters::Synchronizer<MyExactSyncStereoPolicy>* rtabmap_ros::PointCloudXYZRGB::exactSyncStereo_ [private] |
Definition at line 564 of file point_cloud_xyzrgb.cpp.
bool rtabmap_ros::PointCloudXYZRGB::filterNaNs_ [private] |
Definition at line 529 of file point_cloud_xyzrgb.cpp.
Definition at line 538 of file point_cloud_xyzrgb.cpp.
message_filters::Subscriber<stereo_msgs::DisparityImage> rtabmap_ros::PointCloudXYZRGB::imageDisparitySub_ [private] |
Definition at line 541 of file point_cloud_xyzrgb.cpp.
Definition at line 543 of file point_cloud_xyzrgb.cpp.
Definition at line 544 of file point_cloud_xyzrgb.cpp.
Definition at line 537 of file point_cloud_xyzrgb.cpp.
double rtabmap_ros::PointCloudXYZRGB::maxDepth_ [private] |
Definition at line 521 of file point_cloud_xyzrgb.cpp.
double rtabmap_ros::PointCloudXYZRGB::minDepth_ [private] |
Definition at line 522 of file point_cloud_xyzrgb.cpp.
int rtabmap_ros::PointCloudXYZRGB::noiseFilterMinNeighbors_ [private] |
Definition at line 526 of file point_cloud_xyzrgb.cpp.
double rtabmap_ros::PointCloudXYZRGB::noiseFilterRadius_ [private] |
Definition at line 525 of file point_cloud_xyzrgb.cpp.
int rtabmap_ros::PointCloudXYZRGB::normalK_ [private] |
Definition at line 527 of file point_cloud_xyzrgb.cpp.
double rtabmap_ros::PointCloudXYZRGB::normalRadius_ [private] |
Definition at line 528 of file point_cloud_xyzrgb.cpp.
Definition at line 535 of file point_cloud_xyzrgb.cpp.
std::vector<float> rtabmap_ros::PointCloudXYZRGB::roiRatios_ [private] |
Definition at line 530 of file point_cloud_xyzrgb.cpp.
Definition at line 531 of file point_cloud_xyzrgb.cpp.
double rtabmap_ros::PointCloudXYZRGB::voxelSize_ [private] |
Definition at line 523 of file point_cloud_xyzrgb.cpp.