
Public Types | |
| typedef pcl::PointXYZRGB | Point |
Public Member Functions | |
| void | dynReconfCallback (cob_3d_segmentation::plane_extraction_nodeletConfig &config, uint32_t level) |
| void | extractPlane (const pcl::PointCloud< Point >::Ptr &pc_in, std::vector< pcl::PointCloud< Point >, Eigen::aligned_allocator< pcl::PointCloud< Point > > > &v_cloud_hull, std::vector< std::vector< pcl::Vertices > > &v_hull_polygons, std::vector< pcl::ModelCoefficients > &v_coefficients_plane) |
| extracts planes from a point cloud | |
| void | onInit () |
| initializes parameters | |
| PlaneExtractionNodelet () | |
| void | pointCloudSubCallback (const pcl::PointCloud< Point >::Ptr &pc_in) |
| extracts planes from a point cloud | |
| void | publishMarker (pcl::PointCloud< Point > &cloud_hull, std_msgs::Header header, float r, float g, float b) |
| publish markers | |
| void | publishShapeArray (std::vector< pcl::PointCloud< Point >, Eigen::aligned_allocator< pcl::PointCloud< Point > > > &v_cloud_hull, std::vector< std::vector< pcl::Vertices > > &v_hull_polygons, std::vector< pcl::ModelCoefficients > &v_coefficients_plane, std_msgs::Header header) |
| creates polygon from parameters and publish it | |
| bool | srvCallback (cob_3d_mapping_msgs::GetPlane::Request &req, cob_3d_mapping_msgs::GetPlane::Response &res) |
| extracts planes from a point cloud and saves coefficients of nearest table | |
| virtual | ~PlaneExtractionNodelet () |
Public Attributes | |
| ros::NodeHandle | n_ |
Protected Attributes | |
| std::string | action_name_ |
| actionlib::SimpleActionServer < cob_3d_mapping_msgs::PlaneExtractionAction > * | as_ |
| boost::shared_ptr < dynamic_reconfigure::Server < cob_3d_segmentation::plane_extraction_nodeletConfig > > | config_server_ |
| int | ctr_ |
| cob_3d_mapping_msgs::PlaneExtractionFeedback | feedback_ |
| ros::ServiceServer | get_plane_ |
| pcl::PointCloud< Point > | hull_ |
| point cloud for plane | |
| bool | mode_action_ |
| counter for published planes, also used as id | |
| boost::mutex | mutex_ |
| double | passthrough_max_z_ |
| double | passthrough_min_z_ |
| voxel filter leaf size | |
| pcl::PointCloud< Point > | pc_cur_ |
| class for actual calculation | |
| pcl::PointCloud< Point > | pc_plane_ |
| point cloud | |
| PlaneExtraction | pe |
| pcl::ModelCoefficients | plane_coeffs_ |
| hull | |
| ros::Subscriber | point_cloud_sub_ |
| cob_3d_mapping_msgs::PlaneExtractionResult | result_ |
| ros::Publisher | shape_array_pub_ |
| std::string | target_frame_ |
| TransformListener | tf_listener_ |
| coefficients | |
| ros::Publisher | viz_marker_pub_ |
| double | vox_leaf_size_ |
Definition at line 134 of file plane_extraction_nodelet.cpp.
| typedef pcl::PointXYZRGB PlaneExtractionNodelet::Point |
Definition at line 137 of file plane_extraction_nodelet.cpp.
| PlaneExtractionNodelet::PlaneExtractionNodelet | ( | ) | [inline] |
Definition at line 139 of file plane_extraction_nodelet.cpp.
| virtual PlaneExtractionNodelet::~PlaneExtractionNodelet | ( | ) | [inline, virtual] |
Definition at line 153 of file plane_extraction_nodelet.cpp.
| void PlaneExtractionNodelet::dynReconfCallback | ( | cob_3d_segmentation::plane_extraction_nodeletConfig & | config, |
| uint32_t | level | ||
| ) | [inline] |
Definition at line 158 of file plane_extraction_nodelet.cpp.
| void PlaneExtractionNodelet::extractPlane | ( | const pcl::PointCloud< Point >::Ptr & | pc_in, |
| std::vector< pcl::PointCloud< Point >, Eigen::aligned_allocator< pcl::PointCloud< Point > > > & | v_cloud_hull, | ||
| std::vector< std::vector< pcl::Vertices > > & | v_hull_polygons, | ||
| std::vector< pcl::ModelCoefficients > & | v_coefficients_plane | ||
| ) | [inline] |
extracts planes from a point cloud
extracts planes from a point cloud
| pc_in | input point cloud |
| v_cloud_hull | output point cloud with points lying inside the plane |
| v_hull_polygons | output polygons which describes the plane |
| v_coefficients_plane | coefficients of the plane calculated by the segmentation of the inliers |
Definition at line 216 of file plane_extraction_nodelet.cpp.
| void PlaneExtractionNodelet::onInit | ( | ) | [inline, virtual] |
initializes parameters
initializes parameters
Implements nodelet::Nodelet.
Definition at line 186 of file plane_extraction_nodelet.cpp.
| void PlaneExtractionNodelet::pointCloudSubCallback | ( | const pcl::PointCloud< Point >::Ptr & | pc_in | ) | [inline] |
extracts planes from a point cloud
point cloud will be transformed and then extracted if mode_action is false
| pc_in | input point cloud, should be in a coordinate system with z pointing upwards |
Definition at line 234 of file plane_extraction_nodelet.cpp.
| void PlaneExtractionNodelet::publishMarker | ( | pcl::PointCloud< Point > & | cloud_hull, |
| std_msgs::Header | header, | ||
| float | r, | ||
| float | g, | ||
| float | b | ||
| ) | [inline] |
publish markers
publish markers
| cloud_hull | point cloud |
| header | header of published polygons |
| r | red |
| g | green |
| b | blue |
Definition at line 487 of file plane_extraction_nodelet.cpp.
| void PlaneExtractionNodelet::publishShapeArray | ( | std::vector< pcl::PointCloud< Point >, Eigen::aligned_allocator< pcl::PointCloud< Point > > > & | v_cloud_hull, |
| std::vector< std::vector< pcl::Vertices > > & | v_hull_polygons, | ||
| std::vector< pcl::ModelCoefficients > & | v_coefficients_plane, | ||
| std_msgs::Header | header | ||
| ) | [inline] |
creates polygon from parameters and publish it
creates polygon from parameters and publish it
| cloud_hull | point cloud |
| hull_polygons | polygons |
| coefficients_plane | coefficients |
| header | header of published polygons |
Definition at line 383 of file plane_extraction_nodelet.cpp.
| bool PlaneExtractionNodelet::srvCallback | ( | cob_3d_mapping_msgs::GetPlane::Request & | req, |
| cob_3d_mapping_msgs::GetPlane::Response & | res | ||
| ) | [inline] |
extracts planes from a point cloud and saves coefficients of nearest table
extracts planes from a point cloud and saves coefficients of nearest table
| goal | unused |
publishes nearest table
| req | unused |
| res | result with coefficients |
Definition at line 353 of file plane_extraction_nodelet.cpp.
std::string PlaneExtractionNodelet::action_name_ [protected] |
Definition at line 544 of file plane_extraction_nodelet.cpp.
actionlib::SimpleActionServer<cob_3d_mapping_msgs::PlaneExtractionAction>* PlaneExtractionNodelet::as_ [protected] |
Definition at line 543 of file plane_extraction_nodelet.cpp.
boost::shared_ptr<dynamic_reconfigure::Server<cob_3d_segmentation::plane_extraction_nodeletConfig> > PlaneExtractionNodelet::config_server_ [protected] |
Definition at line 539 of file plane_extraction_nodelet.cpp.
int PlaneExtractionNodelet::ctr_ [protected] |
Definition at line 557 of file plane_extraction_nodelet.cpp.
cob_3d_mapping_msgs::PlaneExtractionFeedback PlaneExtractionNodelet::feedback_ [protected] |
Definition at line 546 of file plane_extraction_nodelet.cpp.
ros::ServiceServer PlaneExtractionNodelet::get_plane_ [protected] |
Definition at line 541 of file plane_extraction_nodelet.cpp.
pcl::PointCloud<Point> PlaneExtractionNodelet::hull_ [protected] |
point cloud for plane
Definition at line 553 of file plane_extraction_nodelet.cpp.
bool PlaneExtractionNodelet::mode_action_ [protected] |
counter for published planes, also used as id
Definition at line 561 of file plane_extraction_nodelet.cpp.
boost::mutex PlaneExtractionNodelet::mutex_ [protected] |
Definition at line 548 of file plane_extraction_nodelet.cpp.
Definition at line 532 of file plane_extraction_nodelet.cpp.
double PlaneExtractionNodelet::passthrough_max_z_ [protected] |
Definition at line 567 of file plane_extraction_nodelet.cpp.
double PlaneExtractionNodelet::passthrough_min_z_ [protected] |
voxel filter leaf size
Definition at line 566 of file plane_extraction_nodelet.cpp.
pcl::PointCloud<Point> PlaneExtractionNodelet::pc_cur_ [protected] |
class for actual calculation
Definition at line 551 of file plane_extraction_nodelet.cpp.
pcl::PointCloud<Point> PlaneExtractionNodelet::pc_plane_ [protected] |
point cloud
Definition at line 552 of file plane_extraction_nodelet.cpp.
PlaneExtraction PlaneExtractionNodelet::pe [protected] |
Definition at line 550 of file plane_extraction_nodelet.cpp.
pcl::ModelCoefficients PlaneExtractionNodelet::plane_coeffs_ [protected] |
hull
Definition at line 554 of file plane_extraction_nodelet.cpp.
Definition at line 536 of file plane_extraction_nodelet.cpp.
cob_3d_mapping_msgs::PlaneExtractionResult PlaneExtractionNodelet::result_ [protected] |
Definition at line 547 of file plane_extraction_nodelet.cpp.
Definition at line 538 of file plane_extraction_nodelet.cpp.
std::string PlaneExtractionNodelet::target_frame_ [protected] |
Definition at line 563 of file plane_extraction_nodelet.cpp.
coefficients
Definition at line 556 of file plane_extraction_nodelet.cpp.
Definition at line 537 of file plane_extraction_nodelet.cpp.
double PlaneExtractionNodelet::vox_leaf_size_ [protected] |
Definition at line 565 of file plane_extraction_nodelet.cpp.