34 #include <pcl/point_cloud.h>
35 #include <pcl/point_types.h>
38 #include <sensor_msgs/PointCloud2.h>
39 #include <sensor_msgs/Image.h>
41 #include <sensor_msgs/CameraInfo.h>
42 #include <stereo_msgs/DisparityImage.h>
54 #include <opencv2/highgui/highgui.hpp>
104 int syncQueueSize = 10;
105 bool approxSync =
true;
107 double approxSyncMaxInterval = 0.0;
108 pnh.
param(
"approx_sync", approxSync, approxSync);
109 pnh.
param(
"approx_sync_max_interval", approxSyncMaxInterval, approxSyncMaxInterval);
110 pnh.
param(
"topic_queue_size", queueSize, queueSize);
113 pnh.
param(
"queue_size", syncQueueSize, syncQueueSize);
114 ROS_WARN(
"Parameter \"queue_size\" has been renamed "
115 "to \"sync_queue_size\" and will be removed "
116 "in future versions! The value (%d) is copied to "
117 "\"sync_queue_size\".", syncQueueSize);
121 pnh.
param(
"sync_queue_size", syncQueueSize, syncQueueSize);
132 pnh.
param(
"roi_ratios", roiStr, roiStr);
137 ROS_ERROR(
"\"cut_left\" parameter is replaced by \"roi_ratios\". It will be ignored.");
141 ROS_ERROR(
"\"cut_right\" parameter is replaced by \"roi_ratios\". It will be ignored.");
143 if(pnh.
hasParam(
"special_filter_close_object"))
145 ROS_ERROR(
"\"special_filter_close_object\" parameter is removed. This kind of processing "
146 "should be done before or after this nodelet. See old implementation here: "
147 "https://github.com/introlab/rtabmap_ros/blob/f0026b071c7c54fbcc71df778dd7e17f52f78fc4/src/nodelets/point_cloud_xyz.cpp#L178-L201.");
154 std::list<std::string> strValues =
uSplit(roiStr,
' ');
155 if(strValues.size() != 4)
157 ROS_ERROR(
"The number of values must be 4 (\"roi_ratios\"=\"%s\")", roiStr.c_str());
161 std::vector<float> tmpValues(4);
163 for(std::list<std::string>::iterator jter = strValues.begin(); jter!=strValues.end(); ++jter)
169 if(tmpValues[0] >= 0 && tmpValues[0] < 1 && tmpValues[0] < 1.0
f-tmpValues[1] &&
170 tmpValues[1] >= 0 && tmpValues[1] < 1 && tmpValues[1] < 1.0
f-tmpValues[0] &&
171 tmpValues[2] >= 0 && tmpValues[2] < 1 && tmpValues[2] < 1.0
f-tmpValues[3] &&
172 tmpValues[3] >= 0 && tmpValues[3] < 1 && tmpValues[3] < 1.0
f-tmpValues[2])
178 ROS_ERROR(
"The roi ratios are not valid (\"roi_ratios\"=\"%s\")", roiStr.c_str());
183 NODELET_INFO(
"Approximate time sync = %s", approxSync?
"true":
"false");
188 if(approxSyncMaxInterval > 0.0)
193 if(approxSyncMaxInterval > 0.0)
221 const sensor_msgs::ImageConstPtr& depthMsg,
222 const sensor_msgs::CameraInfoConstPtr& cameraInfo)
241 pcl::PointCloud<pcl::PointXYZ>::Ptr pclCloud;
243 cv::Mat depth = imageDepthPtr->image;
258 (roiRgb.width != 0 ||
262 depth = cv::Mat(depth, roiDepth);
263 if(
model.imageWidth() != 0 &&
model.imageHeight() != 0)
274 NODELET_ERROR(
"Cannot apply ROI ratios [%f,%f,%f,%f] because resulting "
275 "dimension (depth=%dx%d rgb=%dx%d) cannot be divided exactly "
276 "by decimation parameter (%d). Ignoring ROI ratios...",
289 pcl::IndicesPtr
indices(
new std::vector<int>);
304 const stereo_msgs::DisparityImageConstPtr& disparityMsg,
305 const sensor_msgs::CameraInfoConstPtr& cameraInfo)
310 NODELET_ERROR(
"Input type must be disparity=32FC1 or 16SC1");
317 disparity = cv::Mat(disparityMsg->image.height, disparityMsg->image.width, CV_32FC1,
const_cast<uchar*
>(disparityMsg->image.data.data()));
321 disparity = cv::Mat(disparityMsg->image.height, disparityMsg->image.width, CV_16SC1,
const_cast<uchar*
>(disparityMsg->image.data.data()));
330 pcl::PointCloud<pcl::PointXYZ>::Ptr pclCloud;
334 pcl::IndicesPtr
indices(
new std::vector<int>);
336 cv::Mat(disparity, roi),
349 void processAndPublish(pcl::PointCloud<pcl::PointXYZ>::Ptr & pclCloud, pcl::IndicesPtr & indices,
const std_msgs::Header & header)
354 pclCloud->is_dense =
true;
360 if(pclCloud->is_dense)
368 pcl::PointCloud<pcl::PointXYZ>::Ptr tmp(
new pcl::PointCloud<pcl::PointXYZ>);
369 pcl::copyPointCloud(*pclCloud, *
indices, *tmp);
373 sensor_msgs::PointCloud2 rosCloud;
378 pcl::PointCloud<pcl::PointNormal>::Ptr pclCloudNormal(
new pcl::PointCloud<pcl::PointNormal>);
379 pcl::concatenateFields(*pclCloud, *normals, *pclCloudNormal);
394 rosCloud.header.stamp =
header.stamp;
395 rosCloud.header.frame_id =
header.frame_id;