Definition at line 57 of file pointcloud_to_depthimage.cpp.
typedef message_filters::sync_policies::ApproximateTime<sensor_msgs::PointCloud2, sensor_msgs::CameraInfo> rtabmap_ros::PointCloudToDepthImage::MyApproxSyncPolicy [private] |
Definition at line 240 of file pointcloud_to_depthimage.cpp.
typedef message_filters::sync_policies::ExactTime<sensor_msgs::PointCloud2, sensor_msgs::CameraInfo> rtabmap_ros::PointCloudToDepthImage::MyExactSyncPolicy [private] |
Definition at line 242 of file pointcloud_to_depthimage.cpp.
Definition at line 60 of file pointcloud_to_depthimage.cpp.
virtual rtabmap_ros::PointCloudToDepthImage::~PointCloudToDepthImage | ( | ) | [inline, virtual] |
Definition at line 71 of file pointcloud_to_depthimage.cpp.
void rtabmap_ros::PointCloudToDepthImage::callback | ( | const sensor_msgs::PointCloud2ConstPtr & | pointCloud2Msg, |
const sensor_msgs::CameraInfoConstPtr & | cameraInfoMsg | ||
) | [inline, private] |
Definition at line 141 of file pointcloud_to_depthimage.cpp.
virtual void rtabmap_ros::PointCloudToDepthImage::onInit | ( | ) | [inline, private, virtual] |
Implements nodelet::Nodelet.
Definition at line 85 of file pointcloud_to_depthimage.cpp.
message_filters::Synchronizer<MyApproxSyncPolicy>* rtabmap_ros::PointCloudToDepthImage::approxSync_ [private] |
Definition at line 241 of file pointcloud_to_depthimage.cpp.
message_filters::Subscriber<sensor_msgs::CameraInfo> rtabmap_ros::PointCloudToDepthImage::cameraInfoSub_ [private] |
Definition at line 231 of file pointcloud_to_depthimage.cpp.
int rtabmap_ros::PointCloudToDepthImage::decimation_ [private] |
Definition at line 238 of file pointcloud_to_depthimage.cpp.
Definition at line 228 of file pointcloud_to_depthimage.cpp.
Definition at line 229 of file pointcloud_to_depthimage.cpp.
message_filters::Synchronizer<MyExactSyncPolicy>* rtabmap_ros::PointCloudToDepthImage::exactSync_ [private] |
Definition at line 243 of file pointcloud_to_depthimage.cpp.
double rtabmap_ros::PointCloudToDepthImage::fillHolesError_ [private] |
Definition at line 236 of file pointcloud_to_depthimage.cpp.
int rtabmap_ros::PointCloudToDepthImage::fillHolesSize_ [private] |
Definition at line 235 of file pointcloud_to_depthimage.cpp.
int rtabmap_ros::PointCloudToDepthImage::fillIterations_ [private] |
Definition at line 237 of file pointcloud_to_depthimage.cpp.
std::string rtabmap_ros::PointCloudToDepthImage::fixedFrameId_ [private] |
Definition at line 232 of file pointcloud_to_depthimage.cpp.
Definition at line 233 of file pointcloud_to_depthimage.cpp.
message_filters::Subscriber<sensor_msgs::PointCloud2> rtabmap_ros::PointCloudToDepthImage::pointCloudSub_ [private] |
Definition at line 230 of file pointcloud_to_depthimage.cpp.
double rtabmap_ros::PointCloudToDepthImage::waitForTransform_ [private] |
Definition at line 234 of file pointcloud_to_depthimage.cpp.