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>
37 
38 #include <tf/transform_listener.h>
39 
40 #include <sensor_msgs/PointCloud2.h>
41 
43 
44 #include "rtabmap/utilite/UStl.h"
45 
46 namespace rtabmap_util
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_conversions 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  pnh.param("frame_id", frameId_, frameId_);
117  pnh.param("map_frame_id", mapFrameId_, mapFrameId_);
118  pnh.param("wait_for_transform", waitForTransform_, waitForTransform_);
119 
120  if(pnh.hasParam("optimize_for_close_objects"))
121  {
122  NODELET_ERROR("\"optimize_for_close_objects\" parameter doesn't exist "
123  "anymore. Use rtabmap_conversions/obstacles_detection_old nodelet to use "
124  "the old interface.");
125  }
126 
127  rtabmap::ParametersMap parameters;
128 
129  // Backward compatibility
130  for(std::map<std::string, std::pair<bool, std::string> >::const_iterator iter=rtabmap::Parameters::getRemovedParameters().begin();
132  ++iter)
133  {
134  std::string vStr;
135  bool vBool;
136  int vInt;
137  double vDouble;
138  std::string paramValue;
139  if(pnh.getParam(iter->first, vStr))
140  {
141  paramValue = vStr;
142  }
143  else if(pnh.getParam(iter->first, vBool))
144  {
145  paramValue = uBool2Str(vBool);
146  }
147  else if(pnh.getParam(iter->first, vDouble))
148  {
149  paramValue = uNumber2Str(vDouble);
150  }
151  else if(pnh.getParam(iter->first, vInt))
152  {
153  paramValue = uNumber2Str(vInt);
154  }
155  if(!paramValue.empty())
156  {
157  if(iter->second.first)
158  {
159  // can be migrated
160  uInsert(parameters, rtabmap::ParametersPair(iter->second.second, paramValue));
161  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.",
162  iter->first.c_str(), iter->second.second.c_str(), paramValue.c_str());
163  }
164  else
165  {
166  if(iter->second.second.empty())
167  {
168  NODELET_ERROR("obstacles_detection: Parameter \"%s\" doesn't exist anymore!",
169  iter->first.c_str());
170  }
171  else
172  {
173  NODELET_ERROR("obstacles_detection: Parameter \"%s\" doesn't exist anymore! You may look at this similar parameter: \"%s\"",
174  iter->first.c_str(), iter->second.second.c_str());
175  }
176  }
177  }
178  }
179 
182  for(rtabmap::ParametersMap::iterator iter=gridParameters.begin(); iter!=gridParameters.end(); ++iter)
183  {
184  std::string vStr;
185  bool vBool;
186  int vInt;
187  double vDouble;
188  if(pnh.getParam(iter->first, vStr))
189  {
190  NODELET_INFO("obstacles_detection: Setting parameter \"%s\"=\"%s\"", iter->first.c_str(), vStr.c_str());
191  iter->second = vStr;
192  }
193  else if(pnh.getParam(iter->first, vBool))
194  {
195  NODELET_INFO("obstacles_detection: Setting parameter \"%s\"=\"%s\"", iter->first.c_str(), uBool2Str(vBool).c_str());
196  iter->second = uBool2Str(vBool);
197  }
198  else if(pnh.getParam(iter->first, vDouble))
199  {
200  NODELET_INFO("obstacles_detection: Setting parameter \"%s\"=\"%s\"", iter->first.c_str(), uNumber2Str(vDouble).c_str());
201  iter->second = uNumber2Str(vDouble);
202  }
203  else if(pnh.getParam(iter->first, vInt))
204  {
205  NODELET_INFO("obstacles_detection: Setting parameter \"%s\"=\"%s\"", iter->first.c_str(), uNumber2Str(vInt).c_str());
206  iter->second = uNumber2Str(vInt);
207  }
208  }
209  uInsert(parameters, gridParameters);
210  parameterMoved(pnh, "proj_voxel_size", rtabmap::Parameters::kGridCellSize(), parameters);
211  parameterMoved(pnh, "ground_normal_angle", rtabmap::Parameters::kGridMaxGroundAngle(), parameters);
212  parameterMoved(pnh, "min_cluster_size", rtabmap::Parameters::kGridMinClusterSize(), parameters);
213  parameterMoved(pnh, "normal_estimation_radius", rtabmap::Parameters::kGridClusterRadius(), parameters);
214  parameterMoved(pnh, "cluster_radius", rtabmap::Parameters::kGridClusterRadius(), parameters);
215  parameterMoved(pnh, "max_obstacles_height", rtabmap::Parameters::kGridMaxObstacleHeight(), parameters);
216  parameterMoved(pnh, "max_ground_height", rtabmap::Parameters::kGridMaxGroundHeight(), parameters);
217  parameterMoved(pnh, "detect_flat_obstacles", rtabmap::Parameters::kGridFlatObstacleDetected(), parameters);
218  parameterMoved(pnh, "normal_k", rtabmap::Parameters::kGridNormalK(), parameters);
219 
220  UASSERT(uContains(parameters, rtabmap::Parameters::kGridMapFrameProjection()));
221  mapFrameProjection_ = uStr2Bool(parameters.at(rtabmap::Parameters::kGridMapFrameProjection()));
222  if(mapFrameProjection_ && mapFrameId_.empty())
223  {
224  NODELET_ERROR("obstacles_detection: Parameter \"%s\" is true but map_frame_id is not set!", rtabmap::Parameters::kGridMapFrameProjection().c_str());
225  }
226 
227  localMapMaker_.parseParameters(parameters);
228 
229  cloudSub_ = nh.subscribe("cloud", 1, &ObstaclesDetection::callback, this);
230 
231  groundPub_ = nh.advertise<sensor_msgs::PointCloud2>("ground", 1);
232  obstaclesPub_ = nh.advertise<sensor_msgs::PointCloud2>("obstacles", 1);
233  projObstaclesPub_ = nh.advertise<sensor_msgs::PointCloud2>("proj_obstacles", 1);
234  }
235 
236 
237 
238  void callback(const sensor_msgs::PointCloud2ConstPtr & cloudMsg)
239  {
241 
243  {
244  // no one wants the results
245  return;
246  }
247 
249  try
250  {
252  {
253  if(!tfListener_.waitForTransform(frameId_, cloudMsg->header.frame_id, cloudMsg->header.stamp, ros::Duration(1)))
254  {
255  NODELET_ERROR("Could not get transform from %s to %s after 1 second!", frameId_.c_str(), cloudMsg->header.frame_id.c_str());
256  return;
257  }
258  }
260  tfListener_.lookupTransform(frameId_, cloudMsg->header.frame_id, cloudMsg->header.stamp, tmp);
261  localTransform = rtabmap_conversions::transformFromTF(tmp);
262  }
263  catch(tf::TransformException & ex)
264  {
265  NODELET_ERROR("%s",ex.what());
266  return;
267  }
268 
270  if(!mapFrameId_.empty())
271  {
272  try
273  {
275  {
276  if(!tfListener_.waitForTransform(mapFrameId_, frameId_, cloudMsg->header.stamp, ros::Duration(1)))
277  {
278  NODELET_ERROR("Could not get transform from %s to %s after 1 second!", mapFrameId_.c_str(), frameId_.c_str());
279  return;
280  }
281  }
283  tfListener_.lookupTransform(mapFrameId_, frameId_, cloudMsg->header.stamp, tmp);
285  }
286  catch(tf::TransformException & ex)
287  {
288  NODELET_ERROR("%s",ex.what());
289  return;
290  }
291  }
292 
293  UASSERT_MSG(cloudMsg->data.size() == cloudMsg->row_step*cloudMsg->height,
294  uFormat("data=%d row_step=%d height=%d", cloudMsg->data.size(), cloudMsg->row_step, cloudMsg->height).c_str());
295 
296  pcl::PointCloud<pcl::PointXYZ>::Ptr inputCloud(new pcl::PointCloud<pcl::PointXYZ>);
297  pcl::fromROSMsg(*cloudMsg, *inputCloud);
298  if(inputCloud->isOrganized())
299  {
300  std::vector<int> indices;
301  pcl::removeNaNFromPointCloud(*inputCloud, *inputCloud, indices);
302  }
303  else if(!inputCloud->is_dense && inputCloud->height == 1)
304  {
305  if(!warned_)
306  {
307  NODELET_WARN("Detected possible wrong format of point cloud \"%s\", it is "
308  "indicated that it is not dense, but there is only one row. "
309  "Assuming it is dense... This message will only appear once.", cloudSub_.getTopic().c_str());
310  warned_ = true;
311  }
312  inputCloud->is_dense = true;
313  }
314 
315  //Common variables for all strategies
316  pcl::IndicesPtr ground, obstacles;
317  pcl::PointCloud<pcl::PointXYZ>::Ptr obstaclesCloud(new pcl::PointCloud<pcl::PointXYZ>);
318  pcl::PointCloud<pcl::PointXYZ>::Ptr groundCloud(new pcl::PointCloud<pcl::PointXYZ>);
319  pcl::PointCloud<pcl::PointXYZ>::Ptr obstaclesCloudWithoutFlatSurfaces(new pcl::PointCloud<pcl::PointXYZ>);
320 
321  if(inputCloud->size())
322  {
323  inputCloud = rtabmap::util3d::transformPointCloud(inputCloud, localTransform);
324 
325  pcl::IndicesPtr flatObstacles(new std::vector<int>);
326  pcl::PointCloud<pcl::PointXYZ>::Ptr cloud = localMapMaker_.segmentCloud<pcl::PointXYZ>(
327  inputCloud,
328  pcl::IndicesPtr(new std::vector<int>),
329  pose,
330  cv::Point3f(localTransform.x(), localTransform.y(), localTransform.z()),
331  ground,
332  obstacles,
333  &flatObstacles);
334 
335  if(cloud->size() && ((ground.get() && ground->size()) || (obstacles.get() && obstacles->size())))
336  {
338  ground.get() && ground->size())
339  {
340  pcl::copyPointCloud(*cloud, *ground, *groundCloud);
341  }
342 
344  obstacles.get() && obstacles->size())
345  {
346  // remove flat obstacles from obstacles
347  std::set<int> flatObstaclesSet;
349  {
350  flatObstaclesSet.insert(flatObstacles->begin(), flatObstacles->end());
351  }
352 
353  obstaclesCloud->resize(obstacles->size());
354  obstaclesCloudWithoutFlatSurfaces->resize(obstacles->size());
355 
356  int oi=0;
357  for(unsigned int i=0; i<obstacles->size(); ++i)
358  {
359  obstaclesCloud->points[i] = cloud->at(obstacles->at(i));
360  if(flatObstaclesSet.size() == 0 ||
361  flatObstaclesSet.find(obstacles->at(i))==flatObstaclesSet.end())
362  {
363  obstaclesCloudWithoutFlatSurfaces->points[oi] = obstaclesCloud->points[i];
364  obstaclesCloudWithoutFlatSurfaces->points[oi].z = 0;
365  ++oi;
366  }
367 
368  }
369 
370  obstaclesCloudWithoutFlatSurfaces->resize(oi);
371  }
372 
373  if(!localTransform.isIdentity() || !pose.isIdentity())
374  {
375  //transform back in topic frame for 3d clouds and base frame for 2d clouds
376 
377  float roll, pitch, yaw;
378  pose.getEulerAngles(roll, pitch, yaw);
380 
381  if(obstaclesCloudWithoutFlatSurfaces->size() && !pose.isIdentity())
382  {
383  obstaclesCloudWithoutFlatSurfaces = rtabmap::util3d::transformPointCloud(obstaclesCloudWithoutFlatSurfaces, t.inverse());
384  }
385 
386  t = (t*localTransform).inverse();
387  if(groundCloud->size())
388  {
389  groundCloud = rtabmap::util3d::transformPointCloud(groundCloud, t);
390  }
391  if(obstaclesCloud->size())
392  {
393  obstaclesCloud = rtabmap::util3d::transformPointCloud(obstaclesCloud, t);
394  }
395  }
396  }
397  }
398  else
399  {
400  ROS_WARN("obstacles_detection: Input cloud is empty! (%d x %d, is_dense=%d)", cloudMsg->width, cloudMsg->height, cloudMsg->is_dense?1:0);
401  }
402 
404  {
405  sensor_msgs::PointCloud2 rosCloud;
406  pcl::toROSMsg(*groundCloud, rosCloud);
407  rosCloud.header = cloudMsg->header;
408 
409  //publish the message
410  groundPub_.publish(rosCloud);
411  }
412 
414  {
415  sensor_msgs::PointCloud2 rosCloud;
416  pcl::toROSMsg(*obstaclesCloud, rosCloud);
417  rosCloud.header = cloudMsg->header;
418 
419  //publish the message
420  obstaclesPub_.publish(rosCloud);
421  }
422 
424  {
425  sensor_msgs::PointCloud2 rosCloud;
426  pcl::toROSMsg(*obstaclesCloudWithoutFlatSurfaces, rosCloud);
427  rosCloud.header.stamp = cloudMsg->header.stamp;
428  rosCloud.header.frame_id = frameId_;
429 
430  //publish the message
431  projObstaclesPub_.publish(rosCloud);
432  }
433 
434  NODELET_DEBUG("Obstacles segmentation time = %f s", (ros::WallTime::now() - time).toSec());
435  }
436 
437 private:
438  std::string frameId_;
439  std::string mapFrameId_;
441 
444  bool warned_;
445 
447 
451 
453 };
454 
456 }
457 
458 
rtabmap::ParametersPair
std::pair< std::string, std::string > ParametersPair
NODELET_ERROR
#define NODELET_ERROR(...)
ros::Publisher
nodelet::Nodelet::getNodeHandle
ros::NodeHandle & getNodeHandle() const
yaw
GLM_FUNC_DECL T yaw(detail::tquat< T, P > const &x)
rtabmap_util::ObstaclesDetection::ObstaclesDetection
ObstaclesDetection()
Definition: obstacles_detection.cpp:52
rtabmap_util::ObstaclesDetection::callback
void callback(const sensor_msgs::PointCloud2ConstPtr &cloudMsg)
Definition: obstacles_detection.cpp:238
rtabmap_util::ObstaclesDetection::groundPub_
ros::Publisher groundPub_
Definition: obstacles_detection.cpp:448
ros::NodeHandle::getParam
bool getParam(const std::string &key, bool &b) const
uFormat
std::string uFormat(const char *fmt,...)
ULogger::kTypeConsole
kTypeConsole
ros.h
rtabmap::Transform::getIdentity
static Transform getIdentity()
Parameters
PM::Parameters Parameters
ULogger::setLevel
static void setLevel(ULogger::Level level)
rtabmap_util::ObstaclesDetection::mapFrameProjection_
bool mapFrameProjection_
Definition: obstacles_detection.cpp:443
ros::Subscriber::getTopic
std::string getTopic() const
rtabmap_util::ObstaclesDetection::onInit
virtual void onInit()
Definition: obstacles_detection.cpp:107
type
UStl.h
NODELET_WARN
#define NODELET_WARN(...)
rtabmap::ParametersMap
std::map< std::string, std::string > ParametersMap
tf::StampedTransform
pcl::fromROSMsg
void fromROSMsg(const sensor_msgs::PointCloud2 &cloud, pcl::PointCloud< T > &pcl_cloud)
uNumber2Str
std::string uNumber2Str(double number, int precision, bool fixed)
rtabmap_util
Definition: MapsManager.h:49
nodelet::Nodelet::getPrivateNodeHandle
ros::NodeHandle & getPrivateNodeHandle() const
ros::Publisher::publish
void publish(const boost::shared_ptr< M > &message) const
ros::NodeHandle::advertise
Publisher advertise(AdvertiseOptions &ops)
indices
indices
rtabmap_util::ObstaclesDetection
Definition: obstacles_detection.cpp:49
rtabmap::Transform::y
float & y()
rtabmap_util::ObstaclesDetection::~ObstaclesDetection
virtual ~ObstaclesDetection()
Definition: obstacles_detection.cpp:59
rtabmap::Parameters::getDefaultParameters
static const ParametersMap & getDefaultParameters()
uContains
bool uContains(const std::list< V > &list, const V &value)
rtabmap::Transform::z
float & z()
uBool2Str
std::string uBool2Str(bool boolean)
uInsert
void uInsert(std::map< K, V > &map, const std::map< K, V > &items)
rtabmap_util::ObstaclesDetection::obstaclesPub_
ros::Publisher obstaclesPub_
Definition: obstacles_detection.cpp:449
rtabmap_util::ObstaclesDetection::parameterMoved
void parameterMoved(ros::NodeHandle &nh, const std::string &rosName, const std::string &parameterName, rtabmap::ParametersMap &parameters)
Definition: obstacles_detection.cpp:64
rtabmap::LocalGridMaker
ROS_DEBUG
#define ROS_DEBUG(...)
ros::WallTime::now
static WallTime now()
rtabmap::Transform::x
float & x()
ULogger::kWarning
kWarning
rtabmap_util::ObstaclesDetection::waitForTransform_
bool waitForTransform_
Definition: obstacles_detection.cpp:440
rtabmap::Parameters::getRemovedParameters
static const std::map< std::string, std::pair< bool, std::string > > & getRemovedParameters()
rtabmap_util::ObstaclesDetection::mapFrameId_
std::string mapFrameId_
Definition: obstacles_detection.cpp:439
rtabmap_util::ObstaclesDetection::cloudSub_
ros::Subscriber cloudSub_
Definition: obstacles_detection.cpp:452
ros::NodeHandle::hasParam
bool hasParam(const std::string &key) const
UASSERT
#define UASSERT(condition)
ROS_WARN
#define ROS_WARN(...)
ULogger::setType
static void setType(Type type, const std::string &fileName=kDefaultLogFileName, bool append=true)
ros::NodeHandle::subscribe
Subscriber subscribe(const std::string &topic, uint32_t queue_size, const boost::function< void(C)> &callback, const VoidConstPtr &tracked_object=VoidConstPtr(), const TransportHints &transport_hints=TransportHints())
tf::Transformer::waitForTransform
bool waitForTransform(const std::string &target_frame, const ros::Time &target_time, const std::string &source_frame, const ros::Time &source_time, const std::string &fixed_frame, const ros::Duration &timeout, const ros::Duration &polling_sleep_duration=ros::Duration(0.01), std::string *error_msg=NULL) const
time
#define time
LocalGridMaker.h
ros::WallTime
pitch
GLM_FUNC_DECL T pitch(detail::tquat< T, P > const &x)
rtabmap::util3d::transformPointCloud
pcl::PointCloud< pcl::PointNormal >::Ptr RTABMAP_CORE_EXPORT transformPointCloud(const pcl::PointCloud< pcl::PointNormal >::Ptr &cloud, const pcl::IndicesPtr &indices, const Transform &transform)
UASSERT_MSG
#define UASSERT_MSG(condition, msg_str)
uStr2Int
int uStr2Int(const std::string &str)
rtabmap::LocalGridMaker::parseParameters
virtual void parseParameters(const ParametersMap &parameters)
NODELET_INFO
#define NODELET_INFO(...)
transform_listener.h
rtabmap::Transform
rtabmap::LocalGridMaker::segmentCloud
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
rtabmap_util::ObstaclesDetection::localMapMaker_
rtabmap::LocalGridMaker localMapMaker_
Definition: obstacles_detection.cpp:442
rtabmap_util::PLUGINLIB_EXPORT_CLASS
PLUGINLIB_EXPORT_CLASS(rtabmap_util::DisparityToDepth, nodelet::Nodelet)
nodelet::Nodelet
rtabmap_conversions::transformFromTF
rtabmap::Transform transformFromTF(const tf::Transform &transform)
rtabmap_util::ObstaclesDetection::warned_
bool warned_
Definition: obstacles_detection.cpp:444
iter
iterator iter(handle obj)
nodelet.h
rtabmap::Transform::isIdentity
bool isIdentity() const
c_str
const char * c_str(Args &&...args)
uStr2Bool
bool uStr2Bool(const char *str)
rtabmap_util::ObstaclesDetection::tfListener_
tf::TransformListener tfListener_
Definition: obstacles_detection.cpp:446
v
Array< int, Dynamic, 1 > v
class_list_macros.hpp
tf::TransformListener
rtabmap::Parameters::getType
static std::string getType(const std::string &paramKey)
ros::NodeHandle::param
T param(const std::string &param_name, const T &default_val) const
pcl::toROSMsg
void toROSMsg(const pcl::PointCloud< T > &cloud, sensor_msgs::Image &msg)
rtabmap_util::ObstaclesDetection::projObstaclesPub_
ros::Publisher projObstaclesPub_
Definition: obstacles_detection.cpp:450
rtabmap_util::ObstaclesDetection::frameId_
std::string frameId_
Definition: obstacles_detection.cpp:438
false
#define false
ros::Publisher::getNumSubscribers
uint32_t getNumSubscribers() const
tf::Transformer::lookupTransform
void lookupTransform(const std::string &target_frame, const ros::Time &target_time, const std::string &source_frame, const ros::Time &source_time, const std::string &fixed_frame, StampedTransform &transform) const
tf2::TransformException
t
Point2 t(10, 10)
MsgConversion.h
rtabmap
ros::Duration
uStr2Double
double uStr2Double(const std::string &str)
inverse
GLM_FUNC_DECL matType< T, P > inverse(matType< T, P > const &m)
i
int i
roll
GLM_FUNC_DECL T roll(detail::tquat< T, P > const &x)
ros::NodeHandle
ros::Subscriber
NODELET_DEBUG
#define NODELET_DEBUG(...)
pcl_conversions.h


rtabmap_util
Author(s): Mathieu Labbe
autogenerated on Mon Apr 28 2025 02:40:50