
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, 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, 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) |
| virtual void | onInit () |
| void | processAndPublish (pcl::PointCloud< pcl::PointXYZRGB >::Ptr &pclCloud, const std_msgs::Header &header) |
| 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 < 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 < MyExactSyncStereoPolicy > * | exactSyncStereo_ |
| image_transport::SubscriberFilter | imageDepthSub_ |
| image_transport::SubscriberFilter | imageLeft_ |
| image_transport::SubscriberFilter | imageRight_ |
| image_transport::SubscriberFilter | imageSub_ |
| double | maxDepth_ |
| double | minDepth_ |
| int | noiseFilterMinNeighbors_ |
| double | noiseFilterRadius_ |
| std::vector< float > | roiRatios_ |
| double | voxelSize_ |
Definition at line 65 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 371 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 374 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 377 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 380 of file point_cloud_xyzrgb.cpp.
| rtabmap_ros::PointCloudXYZRGB::PointCloudXYZRGB | ( | ) | [inline] |
Definition at line 68 of file point_cloud_xyzrgb.cpp.
| virtual rtabmap_ros::PointCloudXYZRGB::~PointCloudXYZRGB | ( | ) | [inline, virtual] |
Definition at line 81 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 196 of file point_cloud_xyzrgb.cpp.
| virtual void rtabmap_ros::PointCloudXYZRGB::onInit | ( | ) | [inline, private, virtual] |
Implements nodelet::Nodelet.
Definition at line 94 of file point_cloud_xyzrgb.cpp.
| void rtabmap_ros::PointCloudXYZRGB::processAndPublish | ( | pcl::PointCloud< pcl::PointXYZRGB >::Ptr & | pclCloud, |
| const std_msgs::Header & | header | ||
| ) | [inline, private] |
Definition at line 314 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 262 of file point_cloud_xyzrgb.cpp.
message_filters::Synchronizer<MyApproxSyncDepthPolicy>* rtabmap_ros::PointCloudXYZRGB::approxSyncDepth_ [private] |
Definition at line 372 of file point_cloud_xyzrgb.cpp.
message_filters::Synchronizer<MyApproxSyncStereoPolicy>* rtabmap_ros::PointCloudXYZRGB::approxSyncStereo_ [private] |
Definition at line 375 of file point_cloud_xyzrgb.cpp.
message_filters::Subscriber<sensor_msgs::CameraInfo> rtabmap_ros::PointCloudXYZRGB::cameraInfoLeft_ [private] |
Definition at line 368 of file point_cloud_xyzrgb.cpp.
message_filters::Subscriber<sensor_msgs::CameraInfo> rtabmap_ros::PointCloudXYZRGB::cameraInfoRight_ [private] |
Definition at line 369 of file point_cloud_xyzrgb.cpp.
message_filters::Subscriber<sensor_msgs::CameraInfo> rtabmap_ros::PointCloudXYZRGB::cameraInfoSub_ [private] |
Definition at line 364 of file point_cloud_xyzrgb.cpp.
Definition at line 360 of file point_cloud_xyzrgb.cpp.
int rtabmap_ros::PointCloudXYZRGB::decimation_ [private] |
Definition at line 355 of file point_cloud_xyzrgb.cpp.
message_filters::Synchronizer<MyExactSyncDepthPolicy>* rtabmap_ros::PointCloudXYZRGB::exactSyncDepth_ [private] |
Definition at line 378 of file point_cloud_xyzrgb.cpp.
message_filters::Synchronizer<MyExactSyncStereoPolicy>* rtabmap_ros::PointCloudXYZRGB::exactSyncStereo_ [private] |
Definition at line 381 of file point_cloud_xyzrgb.cpp.
Definition at line 363 of file point_cloud_xyzrgb.cpp.
Definition at line 366 of file point_cloud_xyzrgb.cpp.
Definition at line 367 of file point_cloud_xyzrgb.cpp.
Definition at line 362 of file point_cloud_xyzrgb.cpp.
double rtabmap_ros::PointCloudXYZRGB::maxDepth_ [private] |
Definition at line 352 of file point_cloud_xyzrgb.cpp.
double rtabmap_ros::PointCloudXYZRGB::minDepth_ [private] |
Definition at line 353 of file point_cloud_xyzrgb.cpp.
int rtabmap_ros::PointCloudXYZRGB::noiseFilterMinNeighbors_ [private] |
Definition at line 357 of file point_cloud_xyzrgb.cpp.
double rtabmap_ros::PointCloudXYZRGB::noiseFilterRadius_ [private] |
Definition at line 356 of file point_cloud_xyzrgb.cpp.
std::vector<float> rtabmap_ros::PointCloudXYZRGB::roiRatios_ [private] |
Definition at line 358 of file point_cloud_xyzrgb.cpp.
double rtabmap_ros::PointCloudXYZRGB::voxelSize_ [private] |
Definition at line 354 of file point_cloud_xyzrgb.cpp.