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 bool approxSync =
true;
114 double approxSyncMaxInterval = 0.0;
115 pnh.
param(
"approx_sync", approxSync, approxSync);
116 pnh.
param(
"approx_sync_max_interval", approxSyncMaxInterval, approxSyncMaxInterval);
117 pnh.
param(
"queue_size", queueSize, queueSize);
127 pnh.
param(
"roi_ratios", roiStr, roiStr);
133 std::list<std::string> strValues =
uSplit(roiStr,
' ');
134 if(strValues.size() != 4)
136 ROS_ERROR(
"The number of values must be 4 (\"roi_ratios\"=\"%s\")", roiStr.c_str());
140 std::vector<float> tmpValues(4);
142 for(std::list<std::string>::iterator jter = strValues.begin(); jter!=strValues.end(); ++jter)
148 if(tmpValues[0] >= 0 && tmpValues[0] < 1 && tmpValues[0] < 1.0
f-tmpValues[1] &&
149 tmpValues[1] >= 0 && tmpValues[1] < 1 && tmpValues[1] < 1.0
f-tmpValues[0] &&
150 tmpValues[2] >= 0 && tmpValues[2] < 1 && tmpValues[2] < 1.0
f-tmpValues[3] &&
151 tmpValues[3] >= 0 && tmpValues[3] < 1 && tmpValues[3] < 1.0
f-tmpValues[2])
157 ROS_ERROR(
"The roi ratios are not valid (\"roi_ratios\"=\"%s\")", roiStr.c_str());
164 for(rtabmap::ParametersMap::iterator iter=stereoBMParameters_.begin(); iter!=stereoBMParameters_.end(); ++iter)
172 NODELET_INFO(
"point_cloud_xyzrgb: Setting parameter \"%s\"=\"%s\"", iter->first.c_str(), vStr.c_str());
175 else if(pnh.
getParam(iter->first, vBool))
177 NODELET_INFO(
"point_cloud_xyzrgb: Setting parameter \"%s\"=\"%s\"", iter->first.c_str(),
uBool2Str(vBool).c_str());
180 else if(pnh.
getParam(iter->first, vDouble))
182 NODELET_INFO(
"point_cloud_xyzrgb: Setting parameter \"%s\"=\"%s\"", iter->first.c_str(),
uNumber2Str(vDouble).c_str());
185 else if(pnh.
getParam(iter->first, vInt))
187 NODELET_INFO(
"point_cloud_xyzrgb: Setting parameter \"%s\"=\"%s\"", iter->first.c_str(),
uNumber2Str(vInt).c_str());
192 NODELET_INFO(
"Approximate time sync = %s", approxSync?
"true":
"false");
201 if(approxSyncMaxInterval > 0.0)
206 if(approxSyncMaxInterval > 0.0)
211 if(approxSyncMaxInterval > 0.0)
258 const sensor_msgs::ImageConstPtr& image,
259 const sensor_msgs::ImageConstPtr& imageDepth,
260 const sensor_msgs::CameraInfoConstPtr& cameraInfo)
274 NODELET_ERROR(
"Input type must be image=mono8,mono16,rgb8,bgr8 and image_depth=32FC1,16UC1,mono16");
301 pcl::PointCloud<pcl::PointXYZRGB>::Ptr pclCloud;
303 cv::Mat rgb = imagePtr->image;
304 cv::Mat depth = imageDepthPtr->image;
318 depth = cv::Mat(depth, roiDepth);
319 rgb = cv::Mat(rgb, roiRgb);
320 model = model.
roi(roiRgb);
324 NODELET_ERROR(
"Cannot apply ROI ratios [%f,%f,%f,%f] because resulting " 325 "dimension (depth=%dx%d rgb=%dx%d) cannot be divided exactly " 326 "by decimation parameter (%d). Ignoring ROI ratios...",
339 pcl::IndicesPtr indices(
new std::vector<int>);
357 const sensor_msgs::ImageConstPtr& image,
358 const stereo_msgs::DisparityImageConstPtr& imageDisparity,
359 const sensor_msgs::CameraInfoConstPtr& cameraInfo)
379 NODELET_ERROR(
"Input type must be disparity=32FC1 or 16SC1");
386 disparity = cv::Mat(imageDisparity->image.height, imageDisparity->image.width, CV_32FC1, const_cast<uchar*>(imageDisparity->image.data.data()));
390 disparity = cv::Mat(imageDisparity->image.height, imageDisparity->image.width, CV_16SC1, const_cast<uchar*>(imageDisparity->image.data.data()));
399 pcl::PointCloud<pcl::PointXYZRGB>::Ptr pclCloud;
404 pcl::IndicesPtr indices(
new std::vector<int>);
406 cv::Mat(imagePtr->image, roi),
407 cv::Mat(disparity, roi),
421 const sensor_msgs::ImageConstPtr& imageRight,
422 const sensor_msgs::CameraInfoConstPtr& camInfoLeft,
423 const sensor_msgs::CameraInfoConstPtr& camInfoRight)
438 NODELET_ERROR(
"Input type must be image=mono8,mono16,rgb8,bgr8,rgba8,bgra8 (enc=%s)", imageLeft->encoding.c_str());
460 ROS_WARN(
"\"roi_ratios\" set but ignored for stereo images.");
463 pcl::PointCloud<pcl::PointXYZRGB>::Ptr pclCloud;
464 pcl::IndicesPtr indices(
new std::vector<int>);
467 ptrRightImage->image,
488 pcl::PointCloud<pcl::PointXYZRGB>::Ptr pclCloud;
489 pcl::IndicesPtr indices(
new std::vector<int>);
508 void processAndPublish(pcl::PointCloud<pcl::PointXYZRGB>::Ptr & pclCloud, pcl::IndicesPtr & indices,
const std_msgs::Header & header)
513 pclCloud->is_dense =
true;
519 if(pclCloud->is_dense)
527 pcl::PointCloud<pcl::PointXYZRGB>::Ptr tmp(
new pcl::PointCloud<pcl::PointXYZRGB>);
528 pcl::copyPointCloud(*pclCloud, *indices, *tmp);
532 sensor_msgs::PointCloud2 rosCloud;
533 if(!pclCloud->empty() && (pclCloud->is_dense || !indices->empty()) && (
normalK_ > 0 ||
normalRadius_ > 0.0
f))
537 pcl::PointCloud<pcl::PointXYZRGBNormal>::Ptr pclCloudNormal(
new pcl::PointCloud<pcl::PointXYZRGBNormal>);
538 pcl::concatenateFields(*pclCloud, *normals, *pclCloudNormal);
553 rosCloud.header.stamp = header.stamp;
554 rosCloud.header.frame_id = header.frame_id;
ros::Subscriber rgbdImageSub_
CvImageConstPtr toCvShare(const sensor_msgs::ImageConstPtr &source, const std::string &encoding=std::string())
const std::string BAYER_GRBG8
void processAndPublish(pcl::PointCloud< pcl::PointXYZRGB >::Ptr &pclCloud, pcl::IndicesPtr &indices, const std_msgs::Header &header)
void disparityCallback(const sensor_msgs::ImageConstPtr &image, const stereo_msgs::DisparityImageConstPtr &imageDisparity, const sensor_msgs::CameraInfoConstPtr &cameraInfo)
#define NODELET_ERROR(...)
std::vector< float > roiRatios_
rtabmap::SensorData rgbdImageFromROS(const rtabmap_ros::RGBDImageConstPtr &image)
message_filters::Subscriber< sensor_msgs::CameraInfo > cameraInfoSub_
Subscriber subscribe(const std::string &topic, uint32_t queue_size, void(T::*fp)(M), T *obj, const TransportHints &transport_hints=TransportHints())
ros::NodeHandle & getNodeHandle() const
pcl::PointCloud< pcl::PointXYZ >::Ptr RTABMAP_EXP removeNaNFromPointCloud(const pcl::PointCloud< pcl::PointXYZ >::Ptr &cloud)
void stereoCallback(const sensor_msgs::ImageConstPtr &imageLeft, const sensor_msgs::ImageConstPtr &imageRight, const sensor_msgs::CameraInfoConstPtr &camInfoLeft, const sensor_msgs::CameraInfoConstPtr &camInfoRight)
message_filters::sync_policies::ApproximateTime< sensor_msgs::Image, sensor_msgs::Image, sensor_msgs::CameraInfo > MyApproxSyncDepthPolicy
std::map< std::string, std::string > ParametersMap
const std::string TYPE_8UC1
ros::NodeHandle & getPrivateNodeHandle() const
std::string uBool2Str(bool boolean)
image_transport::SubscriberFilter imageRight_
pcl::PointCloud< pcl::PointXYZRGB >::Ptr RTABMAP_EXP cloudFromDepthRGB(const cv::Mat &imageRgb, const cv::Mat &imageDepth, const CameraModel &model, int decimation=1, float maxDepth=0.0f, float minDepth=0.0f, std::vector< int > *validIndices=0)
message_filters::sync_policies::ApproximateTime< sensor_msgs::Image, sensor_msgs::Image, sensor_msgs::CameraInfo, sensor_msgs::CameraInfo > MyApproxSyncStereoPolicy
#define UASSERT(condition)
std::list< std::string > uSplit(const std::string &str, char separator=' ')
message_filters::Synchronizer< MyApproxSyncStereoPolicy > * approxSyncStereo_
message_filters::Synchronizer< MyExactSyncStereoPolicy > * exactSyncStereo_
std::string uNumber2Str(unsigned int number)
bool param(const std::string ¶m_name, T ¶m_val, const T &default_val) const
void publish(const boost::shared_ptr< M > &message) const
message_filters::Synchronizer< MyApproxSyncDepthPolicy > * approxSyncDepth_
image_transport::SubscriberFilter imageDepthSub_
message_filters::sync_policies::ExactTime< sensor_msgs::Image, sensor_msgs::Image, sensor_msgs::CameraInfo > MyExactSyncDepthPolicy
void depthCallback(const sensor_msgs::ImageConstPtr &image, const sensor_msgs::ImageConstPtr &imageDepth, const sensor_msgs::CameraInfoConstPtr &cameraInfo)
message_filters::Synchronizer< MyExactSyncDepthPolicy > * exactSyncDepth_
bool getParam(const std::string &key, std::string &s) const
message_filters::sync_policies::ExactTime< sensor_msgs::Image, stereo_msgs::DisparityImage, sensor_msgs::CameraInfo > MyExactSyncDisparityPolicy
const std::string TYPE_32FC1
pcl::PointCloud< pcl::PointXYZRGB >::Ptr RTABMAP_EXP cloudRGBFromSensorData(const SensorData &sensorData, int decimation=1, float maxDepth=0.0f, float minDepth=0.0f, std::vector< int > *validIndices=0, const ParametersMap &stereoParameters=ParametersMap(), const std::vector< float > &roiRatios=std::vector< float >())
rtabmap::CameraModel cameraModelFromROS(const sensor_msgs::CameraInfo &camInfo, const rtabmap::Transform &localTransform=rtabmap::Transform::getIdentity())
cv::Rect RTABMAP_EXP computeRoi(const cv::Mat &image, const std::string &roiRatios)
CameraModel roi(const cv::Rect &roi) const
image_transport::SubscriberFilter imageSub_
const std::string TYPE_16UC1
cv::Mat RTABMAP_EXP computeNormals(const cv::Mat &laserScan, int searchK, float searchRadius)
std::string resolveName(const std::string &name, bool remap=true) const
Publisher advertise(const std::string &topic, uint32_t queue_size, bool latch=false)
message_filters::Subscriber< sensor_msgs::CameraInfo > cameraInfoRight_
void subscribe(ImageTransport &it, const std::string &base_topic, uint32_t queue_size, const TransportHints &transport_hints=TransportHints())
double noiseFilterRadius_
pcl::IndicesPtr RTABMAP_EXP radiusFiltering(const pcl::PointCloud< pcl::PointXYZ >::Ptr &cloud, float radiusSearch, int minNeighborsInRadius)
static const ParametersMap & getDefaultParameters()
#define NODELET_INFO(...)
virtual ~PointCloudXYZRGB()
void subscribe(ros::NodeHandle &nh, const std::string &topic, uint32_t queue_size, const ros::TransportHints &transport_hints=ros::TransportHints(), ros::CallbackQueueInterface *callback_queue=0)
message_filters::Synchronizer< MyApproxSyncDisparityPolicy > * approxSyncDisparity_
rtabmap::StereoCameraModel stereoCameraModelFromROS(const sensor_msgs::CameraInfo &leftCamInfo, const sensor_msgs::CameraInfo &rightCamInfo, const rtabmap::Transform &localTransform=rtabmap::Transform::getIdentity(), const rtabmap::Transform &stereoTransform=rtabmap::Transform())
void toROSMsg(const sensor_msgs::PointCloud2 &cloud, sensor_msgs::Image &image)
int noiseFilterMinNeighbors_
message_filters::Subscriber< stereo_msgs::DisparityImage > imageDisparitySub_
float uStr2Float(const std::string &str)
PLUGINLIB_EXPORT_CLASS(rtabmap_ros::CoreWrapper, nodelet::Nodelet)
message_filters::sync_policies::ApproximateTime< sensor_msgs::Image, stereo_msgs::DisparityImage, sensor_msgs::CameraInfo > MyApproxSyncDisparityPolicy
pcl::PointCloud< pcl::PointNormal >::Ptr RTABMAP_EXP removeNaNNormalsFromPointCloud(const pcl::PointCloud< pcl::PointNormal >::Ptr &cloud)
pcl::PointCloud< pcl::PointXYZRGB >::Ptr RTABMAP_EXP cloudFromStereoImages(const cv::Mat &imageLeft, const cv::Mat &imageRight, const StereoCameraModel &model, int decimation=1, float maxDepth=0.0f, float minDepth=0.0f, std::vector< int > *validIndices=0, const ParametersMap ¶meters=ParametersMap())
message_filters::sync_policies::ExactTime< sensor_msgs::Image, sensor_msgs::Image, sensor_msgs::CameraInfo, sensor_msgs::CameraInfo > MyExactSyncStereoPolicy
message_filters::Subscriber< sensor_msgs::CameraInfo > cameraInfoLeft_
uint32_t getNumSubscribers() const
pcl::PointCloud< pcl::PointXYZRGB >::Ptr RTABMAP_EXP cloudFromDisparityRGB(const cv::Mat &imageRgb, const cv::Mat &imageDisparity, const StereoCameraModel &model, int decimation=1, float maxDepth=0.0f, float minDepth=0.0f, std::vector< int > *validIndices=0)
pcl::PointCloud< pcl::PointXYZ >::Ptr RTABMAP_EXP voxelize(const pcl::PointCloud< pcl::PointXYZ >::Ptr &cloud, const pcl::IndicesPtr &indices, float voxelSize)
rtabmap::ParametersMap stereoBMParameters_
#define NODELET_DEBUG(...)
void rgbdImageCallback(const rtabmap_ros::RGBDImageConstPtr &image)
image_transport::SubscriberFilter imageLeft_
message_filters::Synchronizer< MyExactSyncDisparityPolicy > * exactSyncDisparity_
const std::string TYPE_16SC1