32 #include <pcl/point_cloud.h> 33 #include <pcl/point_types.h> 35 #include <pcl/filters/filter.h> 39 #include <sensor_msgs/PointCloud2.h> 65 const std::string & rosName,
66 const std::string & parameterName,
72 rtabmap::ParametersMap::const_iterator iter =gridParameters.find(parameterName);
73 if(iter != gridParameters.end())
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.",
80 parameterName.c_str());
82 if(type.compare(
"float") || type.compare(
"double"))
88 else if(type.compare(
"int") || type.compare(
"unsigned int"))
96 NODELET_ERROR(
"Not handled type \"%s\" for parameter \"%s\"", type.c_str(), parameterName.c_str());
101 NODELET_ERROR(
"Parameter \"%s\" not found in default parameters.", parameterName.c_str());
113 pnh.
param(
"queue_size", queueSize, queueSize);
118 if(pnh.
hasParam(
"optimize_for_close_objects"))
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.");
136 std::string paramValue;
141 else if(pnh.
getParam(iter->first, vBool))
145 else if(pnh.
getParam(iter->first, vDouble))
149 else if(pnh.
getParam(iter->first, vInt))
153 if(!paramValue.empty())
155 if(iter->second.first)
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());
164 if(iter->second.second.empty())
166 NODELET_ERROR(
"obstacles_detection: Parameter \"%s\" doesn't exist anymore!",
167 iter->first.c_str());
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());
180 for(rtabmap::ParametersMap::iterator iter=gridParameters.begin(); iter!=gridParameters.end(); ++iter)
188 NODELET_INFO(
"obstacles_detection: Setting parameter \"%s\"=\"%s\"", iter->first.c_str(), vStr.c_str());
191 else if(pnh.
getParam(iter->first, vBool))
193 NODELET_INFO(
"obstacles_detection: Setting parameter \"%s\"=\"%s\"", iter->first.c_str(),
uBool2Str(vBool).c_str());
196 else if(pnh.
getParam(iter->first, vDouble))
198 NODELET_INFO(
"obstacles_detection: Setting parameter \"%s\"=\"%s\"", iter->first.c_str(),
uNumber2Str(vDouble).c_str());
201 else if(pnh.
getParam(iter->first, vInt))
203 NODELET_INFO(
"obstacles_detection: Setting parameter \"%s\"=\"%s\"", iter->first.c_str(),
uNumber2Str(vInt).c_str());
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);
218 UASSERT(
uContains(parameters, rtabmap::Parameters::kGridMapFrameProjection()));
222 NODELET_ERROR(
"obstacles_detection: Parameter \"%s\" is true but map_frame_id is not set!", rtabmap::Parameters::kGridMapFrameProjection().c_str());
236 void callback(
const sensor_msgs::PointCloud2ConstPtr & cloudMsg)
253 NODELET_ERROR(
"Could not get transform from %s to %s after 1 second!",
frameId_.c_str(), cloudMsg->header.frame_id.c_str());
291 pcl::PointCloud<pcl::PointXYZ>::Ptr inputCloud(
new pcl::PointCloud<pcl::PointXYZ>);
293 if(inputCloud->isOrganized())
295 std::vector<int> indices;
296 pcl::removeNaNFromPointCloud(*inputCloud, *inputCloud, indices);
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>);
305 if(inputCloud->size())
309 pcl::IndicesPtr flatObstacles(
new std::vector<int>);
312 pcl::IndicesPtr(
new std::vector<int>),
314 cv::Point3f(localTransform.
x(), localTransform.
y(), localTransform.
z()),
319 if(cloud->size() && (ground->size() || obstacles->size()))
322 ground.get() && ground->size())
324 pcl::copyPointCloud(*cloud, *ground, *groundCloud);
328 obstacles.get() && obstacles->size())
331 std::set<int> flatObstaclesSet;
334 flatObstaclesSet.insert(flatObstacles->begin(), flatObstacles->end());
337 obstaclesCloud->resize(obstacles->size());
338 obstaclesCloudWithoutFlatSurfaces->resize(obstacles->size());
341 for(
unsigned int i=0; i<obstacles->size(); ++i)
343 obstaclesCloud->points[i] = cloud->at(obstacles->at(i));
344 if(flatObstaclesSet.size() == 0 ||
345 flatObstaclesSet.find(obstacles->at(i))==flatObstaclesSet.end())
347 obstaclesCloudWithoutFlatSurfaces->points[oi] = obstaclesCloud->points[i];
348 obstaclesCloudWithoutFlatSurfaces->points[oi].z = 0;
354 obstaclesCloudWithoutFlatSurfaces->resize(oi);
357 if(!localTransform.
isIdentity() || !pose.isIdentity())
362 pose.getEulerAngles(roll, pitch, yaw);
365 if(obstaclesCloudWithoutFlatSurfaces->size() && !pose.isIdentity())
370 t = (t*localTransform).
inverse();
371 if(groundCloud->size())
375 if(obstaclesCloud->size())
384 ROS_WARN(
"obstacles_detection: Input cloud is empty! (%d x %d, is_dense=%d)", cloudMsg->width, cloudMsg->height, cloudMsg->is_dense?1:0);
389 sensor_msgs::PointCloud2 rosCloud;
391 rosCloud.header = cloudMsg->header;
399 sensor_msgs::PointCloud2 rosCloud;
401 rosCloud.header = cloudMsg->header;
409 sensor_msgs::PointCloud2 rosCloud;
411 rosCloud.header.stamp = cloudMsg->header.stamp;
412 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)
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)
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
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
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)