obstacles_detection.cpp
Go to the documentation of this file.
1 /*
2 Copyright (c) 2010-2016, Mathieu Labbe - IntRoLab - Universite de Sherbrooke
3 All rights reserved.
4 
5 Redistribution and use in source and binary forms, with or without
6 modification, are permitted provided that the following conditions are met:
7  * Redistributions of source code must retain the above copyright
8  notice, this list of conditions and the following disclaimer.
9  * Redistributions in binary form must reproduce the above copyright
10  notice, this list of conditions and the following disclaimer in the
11  documentation and/or other materials provided with the distribution.
12  * Neither the name of the Universite de Sherbrooke nor the
13  names of its contributors may be used to endorse or promote products
14  derived from this software without specific prior written permission.
15 
16 THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS" AND
17 ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE IMPLIED
18 WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE ARE
19 DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT HOLDER OR CONTRIBUTORS BE LIABLE FOR ANY
20 DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES
21 (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES;
22 LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED AND
23 ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT LIABILITY, OR TORT
24 (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY OUT OF THE USE OF THIS
25 SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE.
26 */
27 
28 #include <ros/ros.h>
30 #include <nodelet/nodelet.h>
31 
32 #include <pcl/point_cloud.h>
33 #include <pcl/point_types.h>
35 #include <pcl/filters/filter.h>
36 
37 #include <tf/transform_listener.h>
38 
39 #include <sensor_msgs/PointCloud2.h>
40 
42 
44 #include "rtabmap/utilite/UStl.h"
45 
46 namespace rtabmap_ros
47 {
48 
50 {
51 public:
53  frameId_("base_link"),
55  mapFrameProjection_(rtabmap::Parameters::defaultGridMapFrameProjection())
56  {}
57 
59  {}
60 
61 private:
62 
64  ros::NodeHandle & nh,
65  const std::string & rosName,
66  const std::string & parameterName,
67  rtabmap::ParametersMap & parameters)
68  {
69  if(nh.hasParam(rosName))
70  {
72  rtabmap::ParametersMap::const_iterator iter =gridParameters.find(parameterName);
73  if(iter != gridParameters.end())
74  {
75  NODELET_ERROR("obstacles_detection: Parameter \"%s\" has moved from "
76  "rtabmap_ros to rtabmap library. Use "
77  "parameter \"%s\" instead. The value is still "
78  "copied to new parameter name.",
79  rosName.c_str(),
80  parameterName.c_str());
81  std::string type = rtabmap::Parameters::getType(parameterName);
82  if(type.compare("float") || type.compare("double"))
83  {
84  double v = uStr2Double(iter->second);
85  nh.getParam(rosName, v);
86  parameters.insert(rtabmap::ParametersPair(parameterName, uNumber2Str(v)));
87  }
88  else if(type.compare("int") || type.compare("unsigned int"))
89  {
90  int v = uStr2Int(iter->second);
91  nh.getParam(rosName, v);
92  parameters.insert(rtabmap::ParametersPair(parameterName, uNumber2Str(v)));
93  }
94  else
95  {
96  NODELET_ERROR("Not handled type \"%s\" for parameter \"%s\"", type.c_str(), parameterName.c_str());
97  }
98  }
99  else
100  {
101  NODELET_ERROR("Parameter \"%s\" not found in default parameters.", parameterName.c_str());
102  }
103  }
104  }
105 
106  virtual void onInit()
107  {
108  ROS_DEBUG("_"); // not sure why, but all NODELET_*** log are not shown if a normal ROS_*** is not called!?
111 
112  int queueSize = 10;
113  pnh.param("queue_size", queueSize, queueSize);
114  pnh.param("frame_id", frameId_, frameId_);
115  pnh.param("map_frame_id", mapFrameId_, mapFrameId_);
116  pnh.param("wait_for_transform", waitForTransform_, waitForTransform_);
117 
118  if(pnh.hasParam("optimize_for_close_objects"))
119  {
120  NODELET_ERROR("\"optimize_for_close_objects\" parameter doesn't exist "
121  "anymore. Use rtabmap_ros/obstacles_detection_old nodelet to use "
122  "the old interface.");
123  }
124 
125  rtabmap::ParametersMap parameters;
126 
127  // Backward compatibility
128  for(std::map<std::string, std::pair<bool, std::string> >::const_iterator iter=rtabmap::Parameters::getRemovedParameters().begin();
130  ++iter)
131  {
132  std::string vStr;
133  bool vBool;
134  int vInt;
135  double vDouble;
136  std::string paramValue;
137  if(pnh.getParam(iter->first, vStr))
138  {
139  paramValue = vStr;
140  }
141  else if(pnh.getParam(iter->first, vBool))
142  {
143  paramValue = uBool2Str(vBool);
144  }
145  else if(pnh.getParam(iter->first, vDouble))
146  {
147  paramValue = uNumber2Str(vDouble);
148  }
149  else if(pnh.getParam(iter->first, vInt))
150  {
151  paramValue = uNumber2Str(vInt);
152  }
153  if(!paramValue.empty())
154  {
155  if(iter->second.first)
156  {
157  // can be migrated
158  uInsert(parameters, rtabmap::ParametersPair(iter->second.second, paramValue));
159  NODELET_ERROR("obstacles_detection: Parameter name changed: \"%s\" -> \"%s\". Please update your launch file accordingly. Value \"%s\" is still set to the new parameter name.",
160  iter->first.c_str(), iter->second.second.c_str(), paramValue.c_str());
161  }
162  else
163  {
164  if(iter->second.second.empty())
165  {
166  NODELET_ERROR("obstacles_detection: Parameter \"%s\" doesn't exist anymore!",
167  iter->first.c_str());
168  }
169  else
170  {
171  NODELET_ERROR("obstacles_detection: Parameter \"%s\" doesn't exist anymore! You may look at this similar parameter: \"%s\"",
172  iter->first.c_str(), iter->second.second.c_str());
173  }
174  }
175  }
176  }
177 
180  for(rtabmap::ParametersMap::iterator iter=gridParameters.begin(); iter!=gridParameters.end(); ++iter)
181  {
182  std::string vStr;
183  bool vBool;
184  int vInt;
185  double vDouble;
186  if(pnh.getParam(iter->first, vStr))
187  {
188  NODELET_INFO("obstacles_detection: Setting parameter \"%s\"=\"%s\"", iter->first.c_str(), vStr.c_str());
189  iter->second = vStr;
190  }
191  else if(pnh.getParam(iter->first, vBool))
192  {
193  NODELET_INFO("obstacles_detection: Setting parameter \"%s\"=\"%s\"", iter->first.c_str(), uBool2Str(vBool).c_str());
194  iter->second = uBool2Str(vBool);
195  }
196  else if(pnh.getParam(iter->first, vDouble))
197  {
198  NODELET_INFO("obstacles_detection: Setting parameter \"%s\"=\"%s\"", iter->first.c_str(), uNumber2Str(vDouble).c_str());
199  iter->second = uNumber2Str(vDouble);
200  }
201  else if(pnh.getParam(iter->first, vInt))
202  {
203  NODELET_INFO("obstacles_detection: Setting parameter \"%s\"=\"%s\"", iter->first.c_str(), uNumber2Str(vInt).c_str());
204  iter->second = uNumber2Str(vInt);
205  }
206  }
207  uInsert(parameters, gridParameters);
208  parameterMoved(pnh, "proj_voxel_size", rtabmap::Parameters::kGridCellSize(), parameters);
209  parameterMoved(pnh, "ground_normal_angle", rtabmap::Parameters::kGridMaxGroundAngle(), parameters);
210  parameterMoved(pnh, "min_cluster_size", rtabmap::Parameters::kGridMinClusterSize(), parameters);
211  parameterMoved(pnh, "normal_estimation_radius", rtabmap::Parameters::kGridClusterRadius(), parameters);
212  parameterMoved(pnh, "cluster_radius", rtabmap::Parameters::kGridClusterRadius(), parameters);
213  parameterMoved(pnh, "max_obstacles_height", rtabmap::Parameters::kGridMaxObstacleHeight(), parameters);
214  parameterMoved(pnh, "max_ground_height", rtabmap::Parameters::kGridMaxGroundHeight(), parameters);
215  parameterMoved(pnh, "detect_flat_obstacles", rtabmap::Parameters::kGridFlatObstacleDetected(), parameters);
216  parameterMoved(pnh, "normal_k", rtabmap::Parameters::kGridNormalK(), parameters);
217 
218  UASSERT(uContains(parameters, rtabmap::Parameters::kGridMapFrameProjection()));
219  mapFrameProjection_ = uStr2Bool(parameters.at(rtabmap::Parameters::kGridMapFrameProjection()));
220  if(mapFrameProjection_ && mapFrameId_.empty())
221  {
222  NODELET_ERROR("obstacles_detection: Parameter \"%s\" is true but map_frame_id is not set!", rtabmap::Parameters::kGridMapFrameProjection().c_str());
223  }
224 
225  grid_.parseParameters(parameters);
226 
227  cloudSub_ = nh.subscribe("cloud", 1, &ObstaclesDetection::callback, this);
228 
229  groundPub_ = nh.advertise<sensor_msgs::PointCloud2>("ground", 1);
230  obstaclesPub_ = nh.advertise<sensor_msgs::PointCloud2>("obstacles", 1);
231  projObstaclesPub_ = nh.advertise<sensor_msgs::PointCloud2>("proj_obstacles", 1);
232  }
233 
234 
235 
236  void callback(const sensor_msgs::PointCloud2ConstPtr & cloudMsg)
237  {
239 
241  {
242  // no one wants the results
243  return;
244  }
245 
247  try
248  {
250  {
251  if(!tfListener_.waitForTransform(frameId_, cloudMsg->header.frame_id, cloudMsg->header.stamp, ros::Duration(1)))
252  {
253  NODELET_ERROR("Could not get transform from %s to %s after 1 second!", frameId_.c_str(), cloudMsg->header.frame_id.c_str());
254  return;
255  }
256  }
258  tfListener_.lookupTransform(frameId_, cloudMsg->header.frame_id, cloudMsg->header.stamp, tmp);
259  localTransform = rtabmap_ros::transformFromTF(tmp);
260  }
261  catch(tf::TransformException & ex)
262  {
263  NODELET_ERROR("%s",ex.what());
264  return;
265  }
266 
268  if(!mapFrameId_.empty())
269  {
270  try
271  {
273  {
274  if(!tfListener_.waitForTransform(mapFrameId_, frameId_, cloudMsg->header.stamp, ros::Duration(1)))
275  {
276  NODELET_ERROR("Could not get transform from %s to %s after 1 second!", mapFrameId_.c_str(), frameId_.c_str());
277  return;
278  }
279  }
281  tfListener_.lookupTransform(mapFrameId_, frameId_, cloudMsg->header.stamp, tmp);
282  pose = rtabmap_ros::transformFromTF(tmp);
283  }
284  catch(tf::TransformException & ex)
285  {
286  NODELET_ERROR("%s",ex.what());
287  return;
288  }
289  }
290 
291  pcl::PointCloud<pcl::PointXYZ>::Ptr inputCloud(new pcl::PointCloud<pcl::PointXYZ>);
292  pcl::fromROSMsg(*cloudMsg, *inputCloud);
293  if(inputCloud->isOrganized())
294  {
295  std::vector<int> indices;
296  pcl::removeNaNFromPointCloud(*inputCloud, *inputCloud, indices);
297  }
298 
299  //Common variables for all strategies
300  pcl::IndicesPtr ground, obstacles;
301  pcl::PointCloud<pcl::PointXYZ>::Ptr obstaclesCloud(new pcl::PointCloud<pcl::PointXYZ>);
302  pcl::PointCloud<pcl::PointXYZ>::Ptr groundCloud(new pcl::PointCloud<pcl::PointXYZ>);
303  pcl::PointCloud<pcl::PointXYZ>::Ptr obstaclesCloudWithoutFlatSurfaces(new pcl::PointCloud<pcl::PointXYZ>);
304 
305  if(inputCloud->size())
306  {
307  inputCloud = rtabmap::util3d::transformPointCloud(inputCloud, localTransform);
308 
309  pcl::IndicesPtr flatObstacles(new std::vector<int>);
310  pcl::PointCloud<pcl::PointXYZ>::Ptr cloud = grid_.segmentCloud<pcl::PointXYZ>(
311  inputCloud,
312  pcl::IndicesPtr(new std::vector<int>),
313  pose,
314  cv::Point3f(localTransform.x(), localTransform.y(), localTransform.z()),
315  ground,
316  obstacles,
317  &flatObstacles);
318 
319  if(cloud->size() && (ground->size() || obstacles->size()))
320  {
322  ground.get() && ground->size())
323  {
324  pcl::copyPointCloud(*cloud, *ground, *groundCloud);
325  }
326 
328  obstacles.get() && obstacles->size())
329  {
330  // remove flat obstacles from obstacles
331  std::set<int> flatObstaclesSet;
333  {
334  flatObstaclesSet.insert(flatObstacles->begin(), flatObstacles->end());
335  }
336 
337  obstaclesCloud->resize(obstacles->size());
338  obstaclesCloudWithoutFlatSurfaces->resize(obstacles->size());
339 
340  int oi=0;
341  for(unsigned int i=0; i<obstacles->size(); ++i)
342  {
343  obstaclesCloud->points[i] = cloud->at(obstacles->at(i));
344  if(flatObstaclesSet.size() == 0 ||
345  flatObstaclesSet.find(obstacles->at(i))==flatObstaclesSet.end())
346  {
347  obstaclesCloudWithoutFlatSurfaces->points[oi] = obstaclesCloud->points[i];
348  obstaclesCloudWithoutFlatSurfaces->points[oi].z = 0;
349  ++oi;
350  }
351 
352  }
353 
354  obstaclesCloudWithoutFlatSurfaces->resize(oi);
355  }
356 
357  if(!localTransform.isIdentity() || !pose.isIdentity())
358  {
359  //transform back in topic frame for 3d clouds and base frame for 2d clouds
360 
361  float roll, pitch, yaw;
362  pose.getEulerAngles(roll, pitch, yaw);
364 
365  if(obstaclesCloudWithoutFlatSurfaces->size() && !pose.isIdentity())
366  {
367  obstaclesCloudWithoutFlatSurfaces = rtabmap::util3d::transformPointCloud(obstaclesCloudWithoutFlatSurfaces, t.inverse());
368  }
369 
370  t = (t*localTransform).inverse();
371  if(groundCloud->size())
372  {
373  groundCloud = rtabmap::util3d::transformPointCloud(groundCloud, t);
374  }
375  if(obstaclesCloud->size())
376  {
377  obstaclesCloud = rtabmap::util3d::transformPointCloud(obstaclesCloud, t);
378  }
379  }
380  }
381  }
382  else
383  {
384  ROS_WARN("obstacles_detection: Input cloud is empty! (%d x %d, is_dense=%d)", cloudMsg->width, cloudMsg->height, cloudMsg->is_dense?1:0);
385  }
386 
388  {
389  sensor_msgs::PointCloud2 rosCloud;
390  pcl::toROSMsg(*groundCloud, rosCloud);
391  rosCloud.header = cloudMsg->header;
392 
393  //publish the message
394  groundPub_.publish(rosCloud);
395  }
396 
398  {
399  sensor_msgs::PointCloud2 rosCloud;
400  pcl::toROSMsg(*obstaclesCloud, rosCloud);
401  rosCloud.header = cloudMsg->header;
402 
403  //publish the message
404  obstaclesPub_.publish(rosCloud);
405  }
406 
408  {
409  sensor_msgs::PointCloud2 rosCloud;
410  pcl::toROSMsg(*obstaclesCloudWithoutFlatSurfaces, rosCloud);
411  rosCloud.header.stamp = cloudMsg->header.stamp;
412  rosCloud.header.frame_id = frameId_;
413 
414  //publish the message
415  projObstaclesPub_.publish(rosCloud);
416  }
417 
418  NODELET_DEBUG("Obstacles segmentation time = %f s", (ros::WallTime::now() - time).toSec());
419  }
420 
421 private:
422  std::string frameId_;
423  std::string mapFrameId_;
425 
428 
430 
434 
436 };
437 
439 }
440 
441 
GLM_FUNC_DECL T roll(detail::tquat< T, P > const &x)
static const std::map< std::string, std::pair< bool, std::string > > & getRemovedParameters()
#define NODELET_ERROR(...)
void parameterMoved(ros::NodeHandle &nh, const std::string &rosName, const std::string &parameterName, rtabmap::ParametersMap &parameters)
void publish(const boost::shared_ptr< M > &message) const
pcl::PointCloud< pcl::PointXYZ >::Ptr RTABMAP_EXP transformPointCloud(const pcl::PointCloud< pcl::PointXYZ >::Ptr &cloud, const Transform &transform)
double uStr2Double(const std::string &str)
Subscriber subscribe(const std::string &topic, uint32_t queue_size, void(T::*fp)(M), T *obj, const TransportHints &transport_hints=TransportHints())
std::pair< std::string, std::string > ParametersPair
static Transform getIdentity()
void callback(const sensor_msgs::PointCloud2ConstPtr &cloudMsg)
std::map< std::string, std::string > ParametersMap
void fromROSMsg(const sensor_msgs::PointCloud2 &cloud, pcl::PointCloud< T > &pcl_cloud)
GLM_FUNC_DECL T pitch(detail::tquat< T, P > const &x)
#define ROS_WARN(...)
std::string uBool2Str(bool boolean)
bool isIdentity() const
ros::NodeHandle & getPrivateNodeHandle() const
bool waitForTransform(const std::string &target_frame, const std::string &source_frame, const ros::Time &time, const ros::Duration &timeout, const ros::Duration &polling_sleep_duration=ros::Duration(0.01), std::string *error_msg=NULL) const
#define UASSERT(condition)
int uStr2Int(const std::string &str)
std::string uNumber2Str(unsigned int number)
bool param(const std::string &param_name, T &param_val, const T &default_val) const
pcl::PointCloud< PointT >::Ptr segmentCloud(const typename pcl::PointCloud< PointT >::Ptr &cloud, const pcl::IndicesPtr &indices, const Transform &pose, const cv::Point3f &viewPoint, pcl::IndicesPtr &groundIndices, pcl::IndicesPtr &obstaclesIndices, pcl::IndicesPtr *flatObstacles=0) const
Publisher advertise(const std::string &topic, uint32_t queue_size, bool latch=false)
bool uStr2Bool(const char *str)
ros::NodeHandle & getNodeHandle() const
bool uContains(const std::list< V > &list, const V &value)
void lookupTransform(const std::string &target_frame, const std::string &source_frame, const ros::Time &time, StampedTransform &transform) const
static std::string getType(const std::string &paramKey)
#define false
static const ParametersMap & getDefaultParameters()
#define NODELET_INFO(...)
uint32_t getNumSubscribers() const
static WallTime now()
bool getParam(const std::string &key, std::string &s) const
void toROSMsg(const sensor_msgs::PointCloud2 &cloud, sensor_msgs::Image &image)
GLM_FUNC_DECL T yaw(detail::tquat< T, P > const &x)
void parseParameters(const ParametersMap &parameters)
PLUGINLIB_EXPORT_CLASS(rtabmap_ros::CoreWrapper, nodelet::Nodelet)
Transform inverse() const
bool hasParam(const std::string &key) const
#define NODELET_DEBUG(...)
rtabmap::Transform transformFromTF(const tf::Transform &transform)
void uInsert(std::map< K, V > &map, const std::pair< K, V > &pair)
#define ROS_DEBUG(...)
GLM_FUNC_DECL matType< T, P > inverse(matType< T, P > const &m)


rtabmap_ros
Author(s): Mathieu Labbe
autogenerated on Fri Jun 7 2019 21:55:04