32 #include <pcl/point_cloud.h>
33 #include <pcl/point_types.h>
38 #include <sensor_msgs/PointCloud2.h>
39 #include <sensor_msgs/Image.h>
41 #include <sensor_msgs/CameraInfo.h>
43 #include <stereo_msgs/DisparityImage.h>
56 #include <opencv2/highgui/highgui.hpp>
112 int syncQueueSize = 10;
113 bool approxSync =
true;
115 double approxSyncMaxInterval = 0.0;
116 pnh.
param(
"approx_sync", approxSync, approxSync);
117 pnh.
param(
"approx_sync_max_interval", approxSyncMaxInterval, approxSyncMaxInterval);
118 pnh.
param(
"topic_queue_size", queueSize, queueSize);
121 pnh.
param(
"queue_size", syncQueueSize, syncQueueSize);
122 ROS_WARN(
"Parameter \"queue_size\" has been renamed "
123 "to \"sync_queue_size\" and will be removed "
124 "in future versions! The value (%d) is copied to "
125 "\"sync_queue_size\".", syncQueueSize);
129 pnh.
param(
"sync_queue_size", syncQueueSize, syncQueueSize);
140 pnh.
param(
"roi_ratios", roiStr, roiStr);
146 std::list<std::string> strValues =
uSplit(roiStr,
' ');
147 if(strValues.size() != 4)
149 ROS_ERROR(
"The number of values must be 4 (\"roi_ratios\"=\"%s\")", roiStr.c_str());
153 std::vector<float> tmpValues(4);
155 for(std::list<std::string>::iterator jter = strValues.begin(); jter!=strValues.end(); ++jter)
161 if(tmpValues[0] >= 0 && tmpValues[0] < 1 && tmpValues[0] < 1.0
f-tmpValues[1] &&
162 tmpValues[1] >= 0 && tmpValues[1] < 1 && tmpValues[1] < 1.0
f-tmpValues[0] &&
163 tmpValues[2] >= 0 && tmpValues[2] < 1 && tmpValues[2] < 1.0
f-tmpValues[3] &&
164 tmpValues[3] >= 0 && tmpValues[3] < 1 && tmpValues[3] < 1.0
f-tmpValues[2])
170 ROS_ERROR(
"The roi ratios are not valid (\"roi_ratios\"=\"%s\")", roiStr.c_str());
187 NODELET_INFO(
"point_cloud_xyzrgb: Setting parameter \"%s\"=\"%s\"",
iter->first.c_str(), vStr.c_str());
207 NODELET_INFO(
"Approximate time sync = %s", approxSync?
"true":
"false");
216 if(approxSyncMaxInterval > 0.0)
221 if(approxSyncMaxInterval > 0.0)
226 if(approxSyncMaxInterval > 0.0)
273 const sensor_msgs::ImageConstPtr& image,
274 const sensor_msgs::ImageConstPtr& imageDepth,
275 const sensor_msgs::CameraInfoConstPtr& cameraInfo)
289 NODELET_ERROR(
"Input type must be image=mono8,mono16,rgb8,bgr8 and image_depth=32FC1,16UC1,mono16");
316 pcl::PointCloud<pcl::PointXYZRGB>::Ptr pclCloud;
318 cv::Mat rgb = imagePtr->image;
319 cv::Mat depth = imageDepthPtr->image;
333 depth = cv::Mat(depth, roiDepth);
334 rgb = cv::Mat(rgb, roiRgb);
339 NODELET_ERROR(
"Cannot apply ROI ratios [%f,%f,%f,%f] because resulting "
340 "dimension (depth=%dx%d rgb=%dx%d) cannot be divided exactly "
341 "by decimation parameter (%d). Ignoring ROI ratios...",
354 pcl::IndicesPtr
indices(
new std::vector<int>);
372 const sensor_msgs::ImageConstPtr& image,
373 const stereo_msgs::DisparityImageConstPtr& imageDisparity,
374 const sensor_msgs::CameraInfoConstPtr& cameraInfo)
394 NODELET_ERROR(
"Input type must be disparity=32FC1 or 16SC1");
401 disparity = cv::Mat(imageDisparity->image.height, imageDisparity->image.width, CV_32FC1,
const_cast<uchar*
>(imageDisparity->image.data.data()));
405 disparity = cv::Mat(imageDisparity->image.height, imageDisparity->image.width, CV_16SC1,
const_cast<uchar*
>(imageDisparity->image.data.data()));
414 pcl::PointCloud<pcl::PointXYZRGB>::Ptr pclCloud;
419 pcl::IndicesPtr
indices(
new std::vector<int>);
421 cv::Mat(imagePtr->image, roi),
422 cv::Mat(disparity, roi),
436 const sensor_msgs::ImageConstPtr& imageRight,
437 const sensor_msgs::CameraInfoConstPtr& camInfoLeft,
438 const sensor_msgs::CameraInfoConstPtr& camInfoRight)
453 NODELET_ERROR(
"Input type must be image=mono8,mono16,rgb8,bgr8,rgba8,bgra8 (enc=%s)", imageLeft->encoding.c_str());
475 ROS_WARN(
"\"roi_ratios\" set but ignored for stereo images.");
478 pcl::PointCloud<pcl::PointXYZRGB>::Ptr pclCloud;
479 pcl::IndicesPtr
indices(
new std::vector<int>);
482 ptrRightImage->image,
503 pcl::PointCloud<pcl::PointXYZRGB>::Ptr pclCloud;
504 pcl::IndicesPtr
indices(
new std::vector<int>);
523 void processAndPublish(pcl::PointCloud<pcl::PointXYZRGB>::Ptr & pclCloud, pcl::IndicesPtr & indices,
const std_msgs::Header & header)
528 pclCloud->is_dense =
true;
534 if(pclCloud->is_dense)
542 pcl::PointCloud<pcl::PointXYZRGB>::Ptr tmp(
new pcl::PointCloud<pcl::PointXYZRGB>);
543 pcl::copyPointCloud(*pclCloud, *
indices, *tmp);
547 sensor_msgs::PointCloud2 rosCloud;
552 pcl::PointCloud<pcl::PointXYZRGBNormal>::Ptr pclCloudNormal(
new pcl::PointCloud<pcl::PointXYZRGBNormal>);
553 pcl::concatenateFields(*pclCloud, *normals, *pclCloudNormal);
568 rosCloud.header.stamp =
header.stamp;
569 rosCloud.header.frame_id =
header.frame_id;