32 #include <pcl/point_cloud.h> 33 #include <pcl/point_types.h> 38 #include <sensor_msgs/PointCloud2.h> 77 pnh.
param(
"queue_size", queueSize, queueSize);
81 if(pnh.
hasParam(
"normal_estimation_radius") && !pnh.
hasParam(
"cluster_radius"))
83 NODELET_WARN(
"Parameter \"normal_estimation_radius\" has been renamed " 84 "to \"cluster_radius\"! Your value is still copied to " 85 "corresponding parameter. Instead of normal radius, nearest neighbors count " 86 "\"normal_k\" is used instead (default 20).");
110 void callback(
const sensor_msgs::PointCloud2ConstPtr & cloudMsg)
127 NODELET_ERROR(
"Could not get transform from %s to %s after 1 second!",
frameId_.c_str(), cloudMsg->header.frame_id.c_str());
141 pcl::PointCloud<pcl::PointXYZ>::Ptr originalCloud(
new pcl::PointCloud<pcl::PointXYZ>);
145 pcl::IndicesPtr ground, obstacles;
146 pcl::PointCloud<pcl::PointXYZ>::Ptr obstaclesCloud(
new pcl::PointCloud<pcl::PointXYZ>);
147 pcl::PointCloud<pcl::PointXYZ>::Ptr groundCloud(
new pcl::PointCloud<pcl::PointXYZ>);
148 pcl::PointCloud<pcl::PointXYZ>::Ptr obstaclesCloudWithoutFlatSurfaces(
new pcl::PointCloud<pcl::PointXYZ>);
150 if(originalCloud->size())
159 if(originalCloud->size())
164 pcl::IndicesPtr flatObstacles(
new std::vector<int>);
165 rtabmap::util3d::segmentObstaclesFromGround<pcl::PointXYZ>(
178 ground.get() && ground->size())
180 pcl::copyPointCloud(*originalCloud, *ground, *groundCloud);
184 obstacles.get() && obstacles->size())
187 std::set<int> flatObstaclesSet;
190 flatObstaclesSet.insert(flatObstacles->begin(), flatObstacles->end());
193 obstaclesCloud->resize(obstacles->size());
194 obstaclesCloudWithoutFlatSurfaces->resize(obstacles->size());
197 for(
unsigned int i=0; i<obstacles->size(); ++i)
199 obstaclesCloud->points[i] = originalCloud->at(obstacles->at(i));
200 if(flatObstaclesSet.size() == 0 ||
201 flatObstaclesSet.find(obstacles->at(i))==flatObstaclesSet.end())
203 obstaclesCloudWithoutFlatSurfaces->points[oi] = obstaclesCloud->points[i];
204 obstaclesCloudWithoutFlatSurfaces->points[oi].z = 0;
210 obstaclesCloudWithoutFlatSurfaces->resize(oi);
211 if(obstaclesCloudWithoutFlatSurfaces->size() &&
projVoxelSize_ > 0.0)
231 rtabmap::util3d::segmentObstaclesFromGround<pcl::PointXYZ>(
244 pcl::copyPointCloud(*originalCloud_near, *ground, *groundCloud);
250 pcl::copyPointCloud(*originalCloud_near, *obstacles, *obstaclesCloud);
255 rtabmap::util3d::segmentObstaclesFromGround<pcl::PointXYZ>(
268 pcl::PointCloud<pcl::PointXYZ>::Ptr groundCloud2 (
new pcl::PointCloud<pcl::PointXYZ>);
269 pcl::copyPointCloud(*originalCloud_far, *ground, *groundCloud2);
270 *groundCloud += *groundCloud2;
276 pcl::PointCloud<pcl::PointXYZ>::Ptr obstacles2(
new pcl::PointCloud<pcl::PointXYZ>);
277 pcl::copyPointCloud(*originalCloud_far, *obstacles, *obstacles2);
278 *obstaclesCloud += *obstacles2;
286 if(groundCloud->size())
290 if(obstaclesCloud->size())
300 sensor_msgs::PointCloud2 rosCloud;
302 rosCloud.header = cloudMsg->header;
310 sensor_msgs::PointCloud2 rosCloud;
312 rosCloud.header = cloudMsg->header;
320 sensor_msgs::PointCloud2 rosCloud;
322 rosCloud.header.stamp = cloudMsg->header.stamp;
323 rosCloud.header.frame_id =
frameId_;
double maxObstaclesHeight_
#define NODELET_ERROR(...)
GLM_FUNC_DECL genType min(genType const &x, genType const &y)
ros::Publisher groundPub_
#define NODELET_WARN(...)
virtual ~ObstaclesDetectionOld()
void callback(const sensor_msgs::PointCloud2ConstPtr &cloudMsg)
pcl::PointCloud< pcl::PointXYZ >::Ptr RTABMAP_EXP transformPointCloud(const pcl::PointCloud< pcl::PointXYZ >::Ptr &cloud, const Transform &transform)
pcl::IndicesPtr RTABMAP_EXP passThrough(const pcl::PointCloud< pcl::PointXYZ >::Ptr &cloud, const pcl::IndicesPtr &indices, const std::string &axis, float min, float max, bool negative=false)
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
void fromROSMsg(const sensor_msgs::PointCloud2 &cloud, pcl::PointCloud< T > &pcl_cloud)
ros::NodeHandle & getPrivateNodeHandle() const
bool optimizeForCloseObjects_
double groundNormalAngle_
bool param(const std::string ¶m_name, T ¶m_val, const T &default_val) const
void publish(const boost::shared_ptr< M > &message) const
ros::Publisher projObstaclesPub_
bool segmentFlatObstacles_
tf::TransformListener tfListener_
Publisher advertise(const std::string &topic, uint32_t queue_size, bool latch=false)
bool hasParam(const std::string &key) const
ros::Publisher obstaclesPub_
ros::Subscriber cloudSub_
GLM_FUNC_DECL genType max(genType const &x, genType const &y)
void toROSMsg(const sensor_msgs::PointCloud2 &cloud, sensor_msgs::Image &image)
PLUGINLIB_EXPORT_CLASS(rtabmap_ros::CoreWrapper, nodelet::Nodelet)
uint32_t getNumSubscribers() const
pcl::PointCloud< pcl::PointXYZ >::Ptr RTABMAP_EXP voxelize(const pcl::PointCloud< pcl::PointXYZ >::Ptr &cloud, const pcl::IndicesPtr &indices, float voxelSize)
#define NODELET_DEBUG(...)
rtabmap::Transform transformFromTF(const tf::Transform &transform)