Public Member Functions | |
| Nbv (ros::NodeHandle &anode) | |
| ~Nbv () | |
Protected Member Functions | |
| void | castRayAndLabel (pcl::PointCloud< pcl::PointXYZ > &cloud, octomap::pose6d origin) |
| void | cloud_cb (const sensor_msgs::PointCloud2ConstPtr &pointcloud2_msg) |
| cloud callback and the core filtering function at the same time | |
| void | computeBoundaryPoints (pcl::PointCloud< pcl::PointXYZ > &border_cloud, pcl::PointCloud< pcl::Normal > &border_normals, std::vector< pcl::PointIndices > &clusters, pcl::PointCloud< pcl::PointXYZ > *cluster_clouds) |
| void | createOctree (pcl::PointCloud< pcl::PointXYZ > &pointcloud2_pcl, octomap::pose6d laser_pose) |
| void | extractClusters (const pcl::PointCloud< pcl::PointXYZ > &cloud, const pcl::PointCloud< pcl::Normal > &normals, float tolerance, const boost::shared_ptr< pcl::KdTree< pcl::PointXYZ > > &tree, std::vector< pcl::PointIndices > &clusters, double eps_angle, unsigned int min_pts_per_cluster=1, unsigned int max_pts_per_cluster=std::numeric_limits< int >::max()) |
| void | findBorderPoints (pcl::PointCloud< pcl::PointXYZ > &border_cloud, std::string frame_id) |
| void | visualizeOctree (const sensor_msgs::PointCloud2ConstPtr &pointcloud2_msg, geometry_msgs::Point viewpoint) |
Static Protected Member Functions | |
| static bool | compareClusters (pcl::PointIndices c1, pcl::PointIndices c2) |
Protected Attributes | |
| pcl_ros::Publisher < pcl::PointNormal > | border_cloud_pub_ |
| double | boundary_angle_threshold_ |
| bool | check_centroids_ |
| sensor_msgs::PointCloud2 | cloud_in_ |
| ros::Subscriber | cloud_sub_ |
| pcl_ros::Publisher< pcl::PointXYZ > | cluster_cloud2_pub_ |
| pcl_ros::Publisher< pcl::PointXYZ > | cluster_cloud3_pub_ |
| pcl_ros::Publisher< pcl::PointXYZ > | cluster_cloud_pub_ |
| double | eps_angle_ |
| int | free_label_ |
| std::string | input_cloud_topic_ |
| std::string | laser_frame_ |
| int | level_ |
| int | min_pts_per_cluster_ |
| geometry_msgs::PoseArray | nbv_pose_array_ |
| ros::NodeHandle | nh_ |
| double | normal_search_radius_ |
| int | occupied_label_ |
| octomap::ScanGraph * | octomap_graph_ |
| octomap::OcTreePCL * | octree_ |
| visualization_msgs::MarkerArray | octree_marker_array_msg_ |
| ros::Publisher | octree_marker_array_publisher_ |
| ros::Publisher | octree_marker_publisher_ |
| double | octree_maxrange_ |
| ros::Publisher | octree_pub_ |
| double | octree_res_ |
| std::string | output_octree_topic_ |
| std::string | output_pose_topic_ |
| ros::Publisher | pose_pub_ |
| octomap::KeyRay | ray |
| tf::TransformListener | tf_listener_ |
| double | tolerance_ |
| int | unknown_label_ |
| bool | visualize_octree_ |
Definition at line 45 of file next_best_view.cpp.
| Nbv::Nbv | ( | ros::NodeHandle & | anode | ) |
Definition at line 119 of file next_best_view.cpp.
| Nbv::~Nbv | ( | ) |
Definition at line 154 of file next_best_view.cpp.
| void Nbv::castRayAndLabel | ( | pcl::PointCloud< pcl::PointXYZ > & | cloud, |
| octomap::pose6d | origin | ||
| ) | [protected] |
Definition at line 398 of file next_best_view.cpp.
| void Nbv::cloud_cb | ( | const sensor_msgs::PointCloud2ConstPtr & | pointcloud2_msg | ) | [protected] |
cloud callback and the core filtering function at the same time
| pointcloud2_msg | input point cloud to be processed |
Definition at line 166 of file next_best_view.cpp.
| static bool Nbv::compareClusters | ( | pcl::PointIndices | c1, |
| pcl::PointIndices | c2 | ||
| ) | [inline, static, protected] |
Definition at line 95 of file next_best_view.cpp.
| void Nbv::computeBoundaryPoints | ( | pcl::PointCloud< pcl::PointXYZ > & | border_cloud, |
| pcl::PointCloud< pcl::Normal > & | border_normals, | ||
| std::vector< pcl::PointIndices > & | clusters, | ||
| pcl::PointCloud< pcl::PointXYZ > * | cluster_clouds | ||
| ) | [protected] |
Definition at line 323 of file next_best_view.cpp.
| void Nbv::createOctree | ( | pcl::PointCloud< pcl::PointXYZ > & | pointcloud2_pcl, |
| octomap::pose6d | laser_pose | ||
| ) | [protected] |
creating an octree from pcl data
Definition at line 464 of file next_best_view.cpp.
| void Nbv::extractClusters | ( | const pcl::PointCloud< pcl::PointXYZ > & | cloud, |
| const pcl::PointCloud< pcl::Normal > & | normals, | ||
| float | tolerance, | ||
| const boost::shared_ptr< pcl::KdTree< pcl::PointXYZ > > & | tree, | ||
| std::vector< pcl::PointIndices > & | clusters, | ||
| double | eps_angle, | ||
| unsigned int | min_pts_per_cluster = 1, |
||
| unsigned int | max_pts_per_cluster = std::numeric_limits< int >::max() |
||
| ) | [protected] |
| void Nbv::findBorderPoints | ( | pcl::PointCloud< pcl::PointXYZ > & | border_cloud, |
| std::string | frame_id | ||
| ) | [protected] |
Definition at line 431 of file next_best_view.cpp.
| void Nbv::visualizeOctree | ( | const sensor_msgs::PointCloud2ConstPtr & | pointcloud2_msg, |
| geometry_msgs::Point | viewpoint | ||
| ) | [protected] |
Definition at line 555 of file next_best_view.cpp.
pcl_ros::Publisher<pcl::PointNormal> Nbv::border_cloud_pub_ [protected] |
Definition at line 81 of file next_best_view.cpp.
double Nbv::boundary_angle_threshold_ [protected] |
Definition at line 65 of file next_best_view.cpp.
bool Nbv::check_centroids_ [protected] |
Definition at line 58 of file next_best_view.cpp.
sensor_msgs::PointCloud2 Nbv::cloud_in_ [protected] |
Definition at line 76 of file next_best_view.cpp.
ros::Subscriber Nbv::cloud_sub_ [protected] |
Definition at line 79 of file next_best_view.cpp.
pcl_ros::Publisher<pcl::PointXYZ> Nbv::cluster_cloud2_pub_ [protected] |
Definition at line 83 of file next_best_view.cpp.
pcl_ros::Publisher<pcl::PointXYZ> Nbv::cluster_cloud3_pub_ [protected] |
Definition at line 84 of file next_best_view.cpp.
pcl_ros::Publisher<pcl::PointXYZ> Nbv::cluster_cloud_pub_ [protected] |
Definition at line 82 of file next_best_view.cpp.
double Nbv::eps_angle_ [protected] |
Definition at line 63 of file next_best_view.cpp.
int Nbv::free_label_ [protected] |
Definition at line 57 of file next_best_view.cpp.
std::string Nbv::input_cloud_topic_ [protected] |
Definition at line 51 of file next_best_view.cpp.
std::string Nbv::laser_frame_ [protected] |
Definition at line 54 of file next_best_view.cpp.
int Nbv::level_ [protected] |
Definition at line 57 of file next_best_view.cpp.
int Nbv::min_pts_per_cluster_ [protected] |
Definition at line 62 of file next_best_view.cpp.
geometry_msgs::PoseArray Nbv::nbv_pose_array_ [protected] |
Definition at line 77 of file next_best_view.cpp.
ros::NodeHandle Nbv::nh_ [protected] |
Definition at line 48 of file next_best_view.cpp.
double Nbv::normal_search_radius_ [protected] |
Definition at line 61 of file next_best_view.cpp.
int Nbv::occupied_label_ [protected] |
Definition at line 57 of file next_best_view.cpp.
octomap::ScanGraph* Nbv::octomap_graph_ [protected] |
Definition at line 72 of file next_best_view.cpp.
octomap::OcTreePCL* Nbv::octree_ [protected] |
Definition at line 71 of file next_best_view.cpp.
visualization_msgs::MarkerArray Nbv::octree_marker_array_msg_ [protected] |
Definition at line 93 of file next_best_view.cpp.
ros::Publisher Nbv::octree_marker_array_publisher_ [protected] |
Definition at line 88 of file next_best_view.cpp.
ros::Publisher Nbv::octree_marker_publisher_ [protected] |
Definition at line 91 of file next_best_view.cpp.
double Nbv::octree_maxrange_ [protected] |
Definition at line 56 of file next_best_view.cpp.
ros::Publisher Nbv::octree_pub_ [protected] |
Definition at line 80 of file next_best_view.cpp.
double Nbv::octree_res_ [protected] |
Definition at line 56 of file next_best_view.cpp.
std::string Nbv::output_octree_topic_ [protected] |
Definition at line 52 of file next_best_view.cpp.
std::string Nbv::output_pose_topic_ [protected] |
Definition at line 53 of file next_best_view.cpp.
ros::Publisher Nbv::pose_pub_ [protected] |
Definition at line 85 of file next_best_view.cpp.
octomap::KeyRay Nbv::ray [protected] |
Definition at line 74 of file next_best_view.cpp.
tf::TransformListener Nbv::tf_listener_ [protected] |
Definition at line 68 of file next_best_view.cpp.
double Nbv::tolerance_ [protected] |
Definition at line 64 of file next_best_view.cpp.
int Nbv::unknown_label_ [protected] |
Definition at line 57 of file next_best_view.cpp.
bool Nbv::visualize_octree_ [protected] |
Definition at line 59 of file next_best_view.cpp.