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  warned_(false)
57  {}
58 
60  {}
61 
62 private:
63 
65  ros::NodeHandle & nh,
66  const std::string & rosName,
67  const std::string & parameterName,
68  rtabmap::ParametersMap & parameters)
69  {
70  if(nh.hasParam(rosName))
71  {
73  rtabmap::ParametersMap::const_iterator iter =gridParameters.find(parameterName);
74  if(iter != gridParameters.end())
75  {
76  NODELET_ERROR("obstacles_detection: Parameter \"%s\" has moved from "
77  "rtabmap_ros to rtabmap library. Use "
78  "parameter \"%s\" instead. The value is still "
79  "copied to new parameter name.",
80  rosName.c_str(),
81  parameterName.c_str());
82  std::string type = rtabmap::Parameters::getType(parameterName);
83  if(type.compare("float") || type.compare("double"))
84  {
85  double v = uStr2Double(iter->second);
86  nh.getParam(rosName, v);
87  parameters.insert(rtabmap::ParametersPair(parameterName, uNumber2Str(v)));
88  }
89  else if(type.compare("int") || type.compare("unsigned int"))
90  {
91  int v = uStr2Int(iter->second);
92  nh.getParam(rosName, v);
93  parameters.insert(rtabmap::ParametersPair(parameterName, uNumber2Str(v)));
94  }
95  else
96  {
97  NODELET_ERROR("Not handled type \"%s\" for parameter \"%s\"", type.c_str(), parameterName.c_str());
98  }
99  }
100  else
101  {
102  NODELET_ERROR("Parameter \"%s\" not found in default parameters.", parameterName.c_str());
103  }
104  }
105  }
106 
107  virtual void onInit()
108  {
109  ROS_DEBUG("_"); // not sure why, but all NODELET_*** log are not shown if a normal ROS_*** is not called!?
112 
115 
116  int queueSize = 10;
117  pnh.param("queue_size", queueSize, queueSize);
118  pnh.param("frame_id", frameId_, frameId_);
119  pnh.param("map_frame_id", mapFrameId_, mapFrameId_);
120  pnh.param("wait_for_transform", waitForTransform_, waitForTransform_);
121 
122  if(pnh.hasParam("optimize_for_close_objects"))
123  {
124  NODELET_ERROR("\"optimize_for_close_objects\" parameter doesn't exist "
125  "anymore. Use rtabmap_ros/obstacles_detection_old nodelet to use "
126  "the old interface.");
127  }
128 
129  rtabmap::ParametersMap parameters;
130 
131  // Backward compatibility
132  for(std::map<std::string, std::pair<bool, std::string> >::const_iterator iter=rtabmap::Parameters::getRemovedParameters().begin();
134  ++iter)
135  {
136  std::string vStr;
137  bool vBool;
138  int vInt;
139  double vDouble;
140  std::string paramValue;
141  if(pnh.getParam(iter->first, vStr))
142  {
143  paramValue = vStr;
144  }
145  else if(pnh.getParam(iter->first, vBool))
146  {
147  paramValue = uBool2Str(vBool);
148  }
149  else if(pnh.getParam(iter->first, vDouble))
150  {
151  paramValue = uNumber2Str(vDouble);
152  }
153  else if(pnh.getParam(iter->first, vInt))
154  {
155  paramValue = uNumber2Str(vInt);
156  }
157  if(!paramValue.empty())
158  {
159  if(iter->second.first)
160  {
161  // can be migrated
162  uInsert(parameters, rtabmap::ParametersPair(iter->second.second, paramValue));
163  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.",
164  iter->first.c_str(), iter->second.second.c_str(), paramValue.c_str());
165  }
166  else
167  {
168  if(iter->second.second.empty())
169  {
170  NODELET_ERROR("obstacles_detection: Parameter \"%s\" doesn't exist anymore!",
171  iter->first.c_str());
172  }
173  else
174  {
175  NODELET_ERROR("obstacles_detection: Parameter \"%s\" doesn't exist anymore! You may look at this similar parameter: \"%s\"",
176  iter->first.c_str(), iter->second.second.c_str());
177  }
178  }
179  }
180  }
181 
184  for(rtabmap::ParametersMap::iterator iter=gridParameters.begin(); iter!=gridParameters.end(); ++iter)
185  {
186  std::string vStr;
187  bool vBool;
188  int vInt;
189  double vDouble;
190  if(pnh.getParam(iter->first, vStr))
191  {
192  NODELET_INFO("obstacles_detection: Setting parameter \"%s\"=\"%s\"", iter->first.c_str(), vStr.c_str());
193  iter->second = vStr;
194  }
195  else if(pnh.getParam(iter->first, vBool))
196  {
197  NODELET_INFO("obstacles_detection: Setting parameter \"%s\"=\"%s\"", iter->first.c_str(), uBool2Str(vBool).c_str());
198  iter->second = uBool2Str(vBool);
199  }
200  else if(pnh.getParam(iter->first, vDouble))
201  {
202  NODELET_INFO("obstacles_detection: Setting parameter \"%s\"=\"%s\"", iter->first.c_str(), uNumber2Str(vDouble).c_str());
203  iter->second = uNumber2Str(vDouble);
204  }
205  else if(pnh.getParam(iter->first, vInt))
206  {
207  NODELET_INFO("obstacles_detection: Setting parameter \"%s\"=\"%s\"", iter->first.c_str(), uNumber2Str(vInt).c_str());
208  iter->second = uNumber2Str(vInt);
209  }
210  }
211  uInsert(parameters, gridParameters);
212  parameterMoved(pnh, "proj_voxel_size", rtabmap::Parameters::kGridCellSize(), parameters);
213  parameterMoved(pnh, "ground_normal_angle", rtabmap::Parameters::kGridMaxGroundAngle(), parameters);
214  parameterMoved(pnh, "min_cluster_size", rtabmap::Parameters::kGridMinClusterSize(), parameters);
215  parameterMoved(pnh, "normal_estimation_radius", rtabmap::Parameters::kGridClusterRadius(), parameters);
216  parameterMoved(pnh, "cluster_radius", rtabmap::Parameters::kGridClusterRadius(), parameters);
217  parameterMoved(pnh, "max_obstacles_height", rtabmap::Parameters::kGridMaxObstacleHeight(), parameters);
218  parameterMoved(pnh, "max_ground_height", rtabmap::Parameters::kGridMaxGroundHeight(), parameters);
219  parameterMoved(pnh, "detect_flat_obstacles", rtabmap::Parameters::kGridFlatObstacleDetected(), parameters);
220  parameterMoved(pnh, "normal_k", rtabmap::Parameters::kGridNormalK(), parameters);
221 
222  UASSERT(uContains(parameters, rtabmap::Parameters::kGridMapFrameProjection()));
223  mapFrameProjection_ = uStr2Bool(parameters.at(rtabmap::Parameters::kGridMapFrameProjection()));
224  if(mapFrameProjection_ && mapFrameId_.empty())
225  {
226  NODELET_ERROR("obstacles_detection: Parameter \"%s\" is true but map_frame_id is not set!", rtabmap::Parameters::kGridMapFrameProjection().c_str());
227  }
228 
229  grid_.parseParameters(parameters);
230 
231  cloudSub_ = nh.subscribe("cloud", 1, &ObstaclesDetection::callback, this);
232 
233  groundPub_ = nh.advertise<sensor_msgs::PointCloud2>("ground", 1);
234  obstaclesPub_ = nh.advertise<sensor_msgs::PointCloud2>("obstacles", 1);
235  projObstaclesPub_ = nh.advertise<sensor_msgs::PointCloud2>("proj_obstacles", 1);
236  }
237 
238 
239 
240  void callback(const sensor_msgs::PointCloud2ConstPtr & cloudMsg)
241  {
243 
245  {
246  // no one wants the results
247  return;
248  }
249 
251  try
252  {
254  {
255  if(!tfListener_.waitForTransform(frameId_, cloudMsg->header.frame_id, cloudMsg->header.stamp, ros::Duration(1)))
256  {
257  NODELET_ERROR("Could not get transform from %s to %s after 1 second!", frameId_.c_str(), cloudMsg->header.frame_id.c_str());
258  return;
259  }
260  }
262  tfListener_.lookupTransform(frameId_, cloudMsg->header.frame_id, cloudMsg->header.stamp, tmp);
263  localTransform = rtabmap_ros::transformFromTF(tmp);
264  }
265  catch(tf::TransformException & ex)
266  {
267  NODELET_ERROR("%s",ex.what());
268  return;
269  }
270 
272  if(!mapFrameId_.empty())
273  {
274  try
275  {
277  {
278  if(!tfListener_.waitForTransform(mapFrameId_, frameId_, cloudMsg->header.stamp, ros::Duration(1)))
279  {
280  NODELET_ERROR("Could not get transform from %s to %s after 1 second!", mapFrameId_.c_str(), frameId_.c_str());
281  return;
282  }
283  }
285  tfListener_.lookupTransform(mapFrameId_, frameId_, cloudMsg->header.stamp, tmp);
286  pose = rtabmap_ros::transformFromTF(tmp);
287  }
288  catch(tf::TransformException & ex)
289  {
290  NODELET_ERROR("%s",ex.what());
291  return;
292  }
293  }
294 
295  pcl::PointCloud<pcl::PointXYZ>::Ptr inputCloud(new pcl::PointCloud<pcl::PointXYZ>);
296  pcl::fromROSMsg(*cloudMsg, *inputCloud);
297  if(inputCloud->isOrganized())
298  {
299  std::vector<int> indices;
300  pcl::removeNaNFromPointCloud(*inputCloud, *inputCloud, indices);
301  }
302  else if(!inputCloud->is_dense && inputCloud->height == 1)
303  {
304  if(!warned_)
305  {
306  NODELET_WARN("Detected possible wrong format of point cloud \"%s\", it is "
307  "indicated that it is not dense, but there is only one row. "
308  "Assuming it is dense... This message will only appear once.", cloudSub_.getTopic().c_str());
309  warned_ = true;
310  }
311  inputCloud->is_dense = true;
312  }
313 
314  //Common variables for all strategies
315  pcl::IndicesPtr ground, obstacles;
316  pcl::PointCloud<pcl::PointXYZ>::Ptr obstaclesCloud(new pcl::PointCloud<pcl::PointXYZ>);
317  pcl::PointCloud<pcl::PointXYZ>::Ptr groundCloud(new pcl::PointCloud<pcl::PointXYZ>);
318  pcl::PointCloud<pcl::PointXYZ>::Ptr obstaclesCloudWithoutFlatSurfaces(new pcl::PointCloud<pcl::PointXYZ>);
319 
320  if(inputCloud->size())
321  {
322  inputCloud = rtabmap::util3d::transformPointCloud(inputCloud, localTransform);
323 
324  pcl::IndicesPtr flatObstacles(new std::vector<int>);
325  pcl::PointCloud<pcl::PointXYZ>::Ptr cloud = grid_.segmentCloud<pcl::PointXYZ>(
326  inputCloud,
327  pcl::IndicesPtr(new std::vector<int>),
328  pose,
329  cv::Point3f(localTransform.x(), localTransform.y(), localTransform.z()),
330  ground,
331  obstacles,
332  &flatObstacles);
333 
334  if(cloud->size() && ((ground.get() && ground->size()) || (obstacles.get() && obstacles->size())))
335  {
337  ground.get() && ground->size())
338  {
339  pcl::copyPointCloud(*cloud, *ground, *groundCloud);
340  }
341 
343  obstacles.get() && obstacles->size())
344  {
345  // remove flat obstacles from obstacles
346  std::set<int> flatObstaclesSet;
348  {
349  flatObstaclesSet.insert(flatObstacles->begin(), flatObstacles->end());
350  }
351 
352  obstaclesCloud->resize(obstacles->size());
353  obstaclesCloudWithoutFlatSurfaces->resize(obstacles->size());
354 
355  int oi=0;
356  for(unsigned int i=0; i<obstacles->size(); ++i)
357  {
358  obstaclesCloud->points[i] = cloud->at(obstacles->at(i));
359  if(flatObstaclesSet.size() == 0 ||
360  flatObstaclesSet.find(obstacles->at(i))==flatObstaclesSet.end())
361  {
362  obstaclesCloudWithoutFlatSurfaces->points[oi] = obstaclesCloud->points[i];
363  obstaclesCloudWithoutFlatSurfaces->points[oi].z = 0;
364  ++oi;
365  }
366 
367  }
368 
369  obstaclesCloudWithoutFlatSurfaces->resize(oi);
370  }
371 
372  if(!localTransform.isIdentity() || !pose.isIdentity())
373  {
374  //transform back in topic frame for 3d clouds and base frame for 2d clouds
375 
376  float roll, pitch, yaw;
377  pose.getEulerAngles(roll, pitch, yaw);
379 
380  if(obstaclesCloudWithoutFlatSurfaces->size() && !pose.isIdentity())
381  {
382  obstaclesCloudWithoutFlatSurfaces = rtabmap::util3d::transformPointCloud(obstaclesCloudWithoutFlatSurfaces, t.inverse());
383  }
384 
385  t = (t*localTransform).inverse();
386  if(groundCloud->size())
387  {
388  groundCloud = rtabmap::util3d::transformPointCloud(groundCloud, t);
389  }
390  if(obstaclesCloud->size())
391  {
392  obstaclesCloud = rtabmap::util3d::transformPointCloud(obstaclesCloud, t);
393  }
394  }
395  }
396  }
397  else
398  {
399  ROS_WARN("obstacles_detection: Input cloud is empty! (%d x %d, is_dense=%d)", cloudMsg->width, cloudMsg->height, cloudMsg->is_dense?1:0);
400  }
401 
403  {
404  sensor_msgs::PointCloud2 rosCloud;
405  pcl::toROSMsg(*groundCloud, rosCloud);
406  rosCloud.header = cloudMsg->header;
407 
408  //publish the message
409  groundPub_.publish(rosCloud);
410  }
411 
413  {
414  sensor_msgs::PointCloud2 rosCloud;
415  pcl::toROSMsg(*obstaclesCloud, rosCloud);
416  rosCloud.header = cloudMsg->header;
417 
418  //publish the message
419  obstaclesPub_.publish(rosCloud);
420  }
421 
423  {
424  sensor_msgs::PointCloud2 rosCloud;
425  pcl::toROSMsg(*obstaclesCloudWithoutFlatSurfaces, rosCloud);
426  rosCloud.header.stamp = cloudMsg->header.stamp;
427  rosCloud.header.frame_id = frameId_;
428 
429  //publish the message
430  projObstaclesPub_.publish(rosCloud);
431  }
432 
433  NODELET_DEBUG("Obstacles segmentation time = %f s", (ros::WallTime::now() - time).toSec());
434  }
435 
436 private:
437  std::string frameId_;
438  std::string mapFrameId_;
440 
443  bool warned_;
444 
446 
450 
452 };
453 
455 }
456 
457 
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)
#define NODELET_WARN(...)
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)
static void setLevel(ULogger::Level level)
#define ROS_WARN(...)
geometry_msgs::TransformStamped t
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
static void setType(Type type, const std::string &fileName=kDefaultLogFileName, bool append=true)
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
std::string getTopic() 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 Mon Dec 14 2020 03:42:19