32 #include <pcl/point_cloud.h> 33 #include <pcl/point_types.h> 35 #include <pcl/filters/filter.h> 39 #include <sensor_msgs/PointCloud2.h> 66 const std::string & rosName,
67 const std::string & parameterName,
73 rtabmap::ParametersMap::const_iterator iter =gridParameters.find(parameterName);
74 if(iter != gridParameters.end())
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.",
81 parameterName.c_str());
83 if(type.compare(
"float") || type.compare(
"double"))
89 else if(type.compare(
"int") || type.compare(
"unsigned int"))
97 NODELET_ERROR(
"Not handled type \"%s\" for parameter \"%s\"", type.c_str(), parameterName.c_str());
102 NODELET_ERROR(
"Parameter \"%s\" not found in default parameters.", parameterName.c_str());
117 pnh.
param(
"queue_size", queueSize, queueSize);
122 if(pnh.
hasParam(
"optimize_for_close_objects"))
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.");
140 std::string paramValue;
145 else if(pnh.
getParam(iter->first, vBool))
149 else if(pnh.
getParam(iter->first, vDouble))
153 else if(pnh.
getParam(iter->first, vInt))
157 if(!paramValue.empty())
159 if(iter->second.first)
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());
168 if(iter->second.second.empty())
170 NODELET_ERROR(
"obstacles_detection: Parameter \"%s\" doesn't exist anymore!",
171 iter->first.c_str());
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());
184 for(rtabmap::ParametersMap::iterator iter=gridParameters.begin(); iter!=gridParameters.end(); ++iter)
192 NODELET_INFO(
"obstacles_detection: Setting parameter \"%s\"=\"%s\"", iter->first.c_str(), vStr.c_str());
195 else if(pnh.
getParam(iter->first, vBool))
197 NODELET_INFO(
"obstacles_detection: Setting parameter \"%s\"=\"%s\"", iter->first.c_str(),
uBool2Str(vBool).c_str());
200 else if(pnh.
getParam(iter->first, vDouble))
202 NODELET_INFO(
"obstacles_detection: Setting parameter \"%s\"=\"%s\"", iter->first.c_str(),
uNumber2Str(vDouble).c_str());
205 else if(pnh.
getParam(iter->first, vInt))
207 NODELET_INFO(
"obstacles_detection: Setting parameter \"%s\"=\"%s\"", iter->first.c_str(),
uNumber2Str(vInt).c_str());
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);
222 UASSERT(
uContains(parameters, rtabmap::Parameters::kGridMapFrameProjection()));
226 NODELET_ERROR(
"obstacles_detection: Parameter \"%s\" is true but map_frame_id is not set!", rtabmap::Parameters::kGridMapFrameProjection().c_str());
240 void callback(
const sensor_msgs::PointCloud2ConstPtr & cloudMsg)
257 NODELET_ERROR(
"Could not get transform from %s to %s after 1 second!",
frameId_.c_str(), cloudMsg->header.frame_id.c_str());
295 pcl::PointCloud<pcl::PointXYZ>::Ptr inputCloud(
new pcl::PointCloud<pcl::PointXYZ>);
297 if(inputCloud->isOrganized())
299 std::vector<int> indices;
300 pcl::removeNaNFromPointCloud(*inputCloud, *inputCloud, indices);
302 else if(!inputCloud->is_dense && inputCloud->height == 1)
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());
311 inputCloud->is_dense =
true;
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>);
320 if(inputCloud->size())
324 pcl::IndicesPtr flatObstacles(
new std::vector<int>);
327 pcl::IndicesPtr(
new std::vector<int>),
329 cv::Point3f(localTransform.
x(), localTransform.
y(), localTransform.
z()),
334 if(cloud->size() && ((ground.get() && ground->size()) || (obstacles.get() && obstacles->size())))
337 ground.get() && ground->size())
339 pcl::copyPointCloud(*cloud, *ground, *groundCloud);
343 obstacles.get() && obstacles->size())
346 std::set<int> flatObstaclesSet;
349 flatObstaclesSet.insert(flatObstacles->begin(), flatObstacles->end());
352 obstaclesCloud->resize(obstacles->size());
353 obstaclesCloudWithoutFlatSurfaces->resize(obstacles->size());
356 for(
unsigned int i=0; i<obstacles->size(); ++i)
358 obstaclesCloud->points[i] = cloud->at(obstacles->at(i));
359 if(flatObstaclesSet.size() == 0 ||
360 flatObstaclesSet.find(obstacles->at(i))==flatObstaclesSet.end())
362 obstaclesCloudWithoutFlatSurfaces->points[oi] = obstaclesCloud->points[i];
363 obstaclesCloudWithoutFlatSurfaces->points[oi].z = 0;
369 obstaclesCloudWithoutFlatSurfaces->resize(oi);
372 if(!localTransform.
isIdentity() || !pose.isIdentity())
377 pose.getEulerAngles(roll, pitch, yaw);
380 if(obstaclesCloudWithoutFlatSurfaces->size() && !pose.isIdentity())
385 t = (t*localTransform).
inverse();
386 if(groundCloud->size())
390 if(obstaclesCloud->size())
399 ROS_WARN(
"obstacles_detection: Input cloud is empty! (%d x %d, is_dense=%d)", cloudMsg->width, cloudMsg->height, cloudMsg->is_dense?1:0);
404 sensor_msgs::PointCloud2 rosCloud;
406 rosCloud.header = cloudMsg->header;
414 sensor_msgs::PointCloud2 rosCloud;
416 rosCloud.header = cloudMsg->header;
424 sensor_msgs::PointCloud2 rosCloud;
426 rosCloud.header.stamp = cloudMsg->header.stamp;
427 rosCloud.header.frame_id =
frameId_;
ros::Publisher obstaclesPub_
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 ¶meterName, rtabmap::ParametersMap ¶meters)
#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
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)
ros::Publisher groundPub_
GLM_FUNC_DECL T pitch(detail::tquat< T, P > const &x)
static void setLevel(ULogger::Level level)
geometry_msgs::TransformStamped t
std::string uBool2Str(bool boolean)
ros::NodeHandle & getPrivateNodeHandle() const
ros::Subscriber cloudSub_
#define UASSERT(condition)
int uStr2Int(const std::string &str)
ros::Publisher projObstaclesPub_
std::string uNumber2Str(unsigned int number)
bool param(const std::string ¶m_name, T ¶m_val, const T &default_val) const
static void setType(Type type, const std::string &fileName=kDefaultLogFileName, bool append=true)
tf::TransformListener tfListener_
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
virtual ~ObstaclesDetection()
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)
static std::string getType(const std::string ¶mKey)
static const ParametersMap & getDefaultParameters()
#define NODELET_INFO(...)
uint32_t getNumSubscribers() const
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)
rtabmap::OccupancyGrid grid_
void parseParameters(const ParametersMap ¶meters)
PLUGINLIB_EXPORT_CLASS(rtabmap_ros::CoreWrapper, nodelet::Nodelet)
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)
GLM_FUNC_DECL matType< T, P > inverse(matType< T, P > const &m)