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 bool approxSync =
true;
106 pnh.
param(
"approx_sync", approxSync, approxSync);
107 pnh.
param(
"queue_size", queueSize, queueSize);
117 pnh.
param(
"roi_ratios", roiStr, roiStr);
122 ROS_ERROR(
"\"cut_left\" parameter is replaced by \"roi_ratios\". It will be ignored.");
126 ROS_ERROR(
"\"cut_right\" parameter is replaced by \"roi_ratios\". It will be ignored.");
128 if(pnh.
hasParam(
"special_filter_close_object"))
130 ROS_ERROR(
"\"special_filter_close_object\" parameter is removed. This kind of processing " 131 "should be done before or after this nodelet. See old implementation here: " 132 "https://github.com/introlab/rtabmap_ros/blob/f0026b071c7c54fbcc71df778dd7e17f52f78fc4/src/nodelets/point_cloud_xyz.cpp#L178-L201.");
139 std::list<std::string> strValues =
uSplit(roiStr,
' ');
140 if(strValues.size() != 4)
142 ROS_ERROR(
"The number of values must be 4 (\"roi_ratios\"=\"%s\")", roiStr.c_str());
146 std::vector<float> tmpValues(4);
148 for(std::list<std::string>::iterator jter = strValues.begin(); jter!=strValues.end(); ++jter)
154 if(tmpValues[0] >= 0 && tmpValues[0] < 1 && tmpValues[0] < 1.0
f-tmpValues[1] &&
155 tmpValues[1] >= 0 && tmpValues[1] < 1 && tmpValues[1] < 1.0
f-tmpValues[0] &&
156 tmpValues[2] >= 0 && tmpValues[2] < 1 && tmpValues[2] < 1.0
f-tmpValues[3] &&
157 tmpValues[3] >= 0 && tmpValues[3] < 1 && tmpValues[3] < 1.0
f-tmpValues[2])
163 ROS_ERROR(
"The roi ratios are not valid (\"roi_ratios\"=\"%s\")", roiStr.c_str());
168 NODELET_INFO(
"Approximate time sync = %s", approxSync?
"true":
"false");
202 const sensor_msgs::ImageConstPtr& depth,
203 const sensor_msgs::CameraInfoConstPtr& cameraInfo)
223 pcl::PointCloud<pcl::PointXYZ>::Ptr pclCloud;
227 model.
cx()-
roiRatios_[0]*double(imageDepthPtr->image.cols),
228 model.
cy()-
roiRatios_[2]*double(imageDepthPtr->image.rows));
230 pcl::IndicesPtr indices(
new std::vector<int>);
232 cv::Mat(imageDepthPtr->image, roi),
245 const stereo_msgs::DisparityImageConstPtr& disparityMsg,
246 const sensor_msgs::CameraInfoConstPtr& cameraInfo)
251 NODELET_ERROR(
"Input type must be disparity=32FC1 or 16SC1");
258 disparity = cv::Mat(disparityMsg->image.height, disparityMsg->image.width, CV_32FC1, const_cast<uchar*>(disparityMsg->image.data.data()));
262 disparity = cv::Mat(disparityMsg->image.height, disparityMsg->image.width, CV_16SC1, const_cast<uchar*>(disparityMsg->image.data.data()));
271 pcl::PointCloud<pcl::PointXYZ>::Ptr pclCloud;
274 pcl::IndicesPtr indices(
new std::vector<int>);
276 cv::Mat(disparity, roi),
289 void processAndPublish(pcl::PointCloud<pcl::PointXYZ>::Ptr & pclCloud, pcl::IndicesPtr & indices,
const std_msgs::Header & header)
299 if(pclCloud->is_dense)
307 pcl::PointCloud<pcl::PointXYZ>::Ptr tmp(
new pcl::PointCloud<pcl::PointXYZ>);
308 pcl::copyPointCloud(*pclCloud, *indices, *tmp);
312 sensor_msgs::PointCloud2 rosCloud;
317 pcl::PointCloud<pcl::PointNormal>::Ptr pclCloudNormal(
new pcl::PointCloud<pcl::PointNormal>);
318 pcl::concatenateFields(*pclCloud, *normals, *pclCloudNormal);
333 rosCloud.header.stamp = header.stamp;
334 rosCloud.header.frame_id = header.frame_id;
CvImageConstPtr toCvShare(const sensor_msgs::ImageConstPtr &source, const std::string &encoding=std::string())
std::vector< float > roiRatios_
pcl::PointCloud< pcl::PointXYZ >::Ptr RTABMAP_EXP cloudFromDisparity(const cv::Mat &imageDisparity, const StereoCameraModel &model, int decimation=1, float maxDepth=0.0f, float minDepth=0.0f, std::vector< int > *validIndices=0)
void callbackDisparity(const stereo_msgs::DisparityImageConstPtr &disparityMsg, const sensor_msgs::CameraInfoConstPtr &cameraInfo)
#define NODELET_ERROR(...)
void publish(const boost::shared_ptr< M > &message) const
message_filters::Synchronizer< MyExactSyncDepthPolicy > * exactSyncDepth_
std::string resolveName(const std::string &name, bool remap=true) const
double noiseFilterRadius_
pcl::PointCloud< pcl::PointXYZ >::Ptr RTABMAP_EXP removeNaNFromPointCloud(const pcl::PointCloud< pcl::PointXYZ >::Ptr &cloud)
image_transport::SubscriberFilter imageDepthSub_
message_filters::sync_policies::ApproximateTime< stereo_msgs::DisparityImage, sensor_msgs::CameraInfo > MyApproxSyncDisparityPolicy
message_filters::Synchronizer< MyApproxSyncDisparityPolicy > * approxSyncDisparity_
message_filters::Subscriber< sensor_msgs::CameraInfo > disparityCameraInfoSub_
message_filters::Synchronizer< MyExactSyncDisparityPolicy > * exactSyncDisparity_
pcl::PointCloud< pcl::PointXYZ >::Ptr RTABMAP_EXP cloudFromDepth(const cv::Mat &imageDepth, const CameraModel &model, int decimation=1, float maxDepth=0.0f, float minDepth=0.0f, std::vector< int > *validIndices=0)
std::list< std::string > uSplit(const std::string &str, char separator= ' ')
ros::NodeHandle & getPrivateNodeHandle() const
message_filters::sync_policies::ExactTime< stereo_msgs::DisparityImage, sensor_msgs::CameraInfo > MyExactSyncDisparityPolicy
void processAndPublish(pcl::PointCloud< pcl::PointXYZ >::Ptr &pclCloud, pcl::IndicesPtr &indices, const std_msgs::Header &header)
message_filters::Subscriber< stereo_msgs::DisparityImage > disparitySub_
message_filters::Synchronizer< MyApproxSyncDepthPolicy > * approxSyncDepth_
bool fromCameraInfo(const sensor_msgs::CameraInfo &msg)
bool param(const std::string ¶m_name, T ¶m_val, const T &default_val) const
const std::string TYPE_32FC1
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)
message_filters::Subscriber< sensor_msgs::CameraInfo > cameraInfoSub_
const std::string TYPE_16UC1
cv::Mat RTABMAP_EXP computeNormals(const cv::Mat &laserScan, int searchK, float searchRadius)
Publisher advertise(const std::string &topic, uint32_t queue_size, bool latch=false)
ros::NodeHandle & getNodeHandle() const
void subscribe(ImageTransport &it, const std::string &base_topic, uint32_t queue_size, const TransportHints &transport_hints=TransportHints())
pcl::IndicesPtr RTABMAP_EXP radiusFiltering(const pcl::PointCloud< pcl::PointXYZ >::Ptr &cloud, float radiusSearch, int minNeighborsInRadius)
message_filters::sync_policies::ApproximateTime< sensor_msgs::Image, sensor_msgs::CameraInfo > MyApproxSyncDepthPolicy
#define NODELET_INFO(...)
uint32_t getNumSubscribers() const
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)
void toROSMsg(const sensor_msgs::PointCloud2 &cloud, sensor_msgs::Image &image)
float uStr2Float(const std::string &str)
void callback(const sensor_msgs::ImageConstPtr &depth, const sensor_msgs::CameraInfoConstPtr &cameraInfo)
PLUGINLIB_EXPORT_CLASS(rtabmap_ros::CoreWrapper, nodelet::Nodelet)
pcl::PointCloud< pcl::PointNormal >::Ptr RTABMAP_EXP removeNaNNormalsFromPointCloud(const pcl::PointCloud< pcl::PointNormal >::Ptr &cloud)
bool hasParam(const std::string &key) const
int noiseFilterMinNeighbors_
pcl::PointCloud< pcl::PointXYZ >::Ptr RTABMAP_EXP voxelize(const pcl::PointCloud< pcl::PointXYZ >::Ptr &cloud, const pcl::IndicesPtr &indices, float voxelSize)
#define NODELET_DEBUG(...)
message_filters::sync_policies::ExactTime< sensor_msgs::Image, sensor_msgs::CameraInfo > MyExactSyncDepthPolicy
const std::string TYPE_16SC1