#include <string>
#include <ros/ros.h>
#include <sensor_msgs/PointCloud.h>
#include <sensor_msgs/PointCloud2.h>
#include <sensor_msgs/point_cloud_conversion.h>
#include <visualization_msgs/Marker.h>
#include <tf/transform_listener.h>
#include "tf/tf.h"
#include "tf/tfMessage.h"
#include <pcl/point_cloud.h>
#include <pcl/point_types.h>
#include <pcl/io/io.h>
#include "pcl/filters/filter.h"
#include <map>
#include <boost/mpl/size.hpp>
#include <boost/fusion/sequence/intrinsic/at_key.hpp>
#include <pcl/filters/passthrough.h>
#include <pcl/filters/extract_indices.h>
#include <pcl/features/feature.h>
#include <pcl/kdtree/kdtree_flann.h>
#include <pcl/sample_consensus/model_types.h>
#include "pcl/pcl_base.h"
#include "pcl/PointIndices.h"
#include <vector>
#include <ostream>
#include "ros/serialization.h"
#include "ros/builtin_message_traits.h"
#include "ros/message_operations.h"
#include "ros/message.h"
#include "ros/time.h"
#include "std_msgs/Header.h"
#include "pcl/sample_consensus/sac.h"
#include "pcl/sample_consensus/sac_model.h"
#include "pcl/ModelCoefficients.h"
#include <cminpack.h>
#include <boost/thread/mutex.hpp>
#include <cfloat>
#include <pcl/common/eigen.h>
#include <pcl/features/normal_3d.h>
#include <pcl/sample_consensus/sac_model_plane.h>
#include <pcl/common/common.h>
#include <pcl/sample_consensus/sac_model_perpendicular_plane.h>
#include <pcl/sample_consensus/sac_model_line.h>
#include <math.h>
#include <stdio.h>
#include <stdlib.h>
#include "qhull/qhull.h"
#include "qhull/mem.h"
#include "qhull/qset.h"
#include "qhull/geom.h"
#include "qhull/merge.h"
#include "qhull/poly.h"
#include "qhull/io.h"
#include "qhull/stat.h"
#include <pcl/segmentation/extract_clusters.h>
#include "tabletop_object_detector/marker_generator.h"
#include "tabletop_object_detector/TabletopSegmentation.h"
Go to the source code of this file.
Classes | |
class | tabletop_object_detector::TabletopSegmentor |
Namespaces | |
namespace | tabletop_object_detector |
Functions | |
template<typename PointT > | |
void | tabletop_object_detector::getClustersFromPointCloud2 (const pcl::PointCloud< PointT > &cloud_objects, const std::vector< pcl::PointIndices > &clusters2, std::vector< sensor_msgs::PointCloud > &clusters) |
template<typename PointT > | |
bool | tabletop_object_detector::getPlanePoints (const pcl::PointCloud< PointT > &table, const tf::Transform &table_plane_trans, sensor_msgs::PointCloud &table_points) |
tf::Transform | tabletop_object_detector::getPlaneTransform (pcl::ModelCoefficients coeffs, double up_direction) |
int | main (int argc, char **argv) |
int main | ( | int | argc, | |
char ** | argv | |||
) |
Definition at line 584 of file tabletop_segmentation.cpp.