Definition at line 115 of file next_best_view.cpp.
Definition at line 249 of file next_best_view.cpp.
Definition at line 254 of file next_best_view.cpp.
void autonomous_mapping::NextBestView::castRayAndLabel | ( | pcl::PointCloud< pcl::PointXYZ > & | cloud, |
octomap::pose6d | origin | ||
) | [protected] |
Definition at line 1307 of file next_best_view.cpp.
void autonomous_mapping::NextBestView::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 774 of file next_best_view.cpp.
static bool autonomous_mapping::NextBestView::compareClusters | ( | pcl::PointIndices | c1, |
pcl::PointIndices | c2 | ||
) | [inline, static, protected] |
Definition at line 207 of file next_best_view.cpp.
double autonomous_mapping::NextBestView::compute_overlap_score | ( | double | x, |
double | y, | ||
double | theta, | ||
int | reward | ||
) | [protected] |
Definition at line 595 of file next_best_view.cpp.
void autonomous_mapping::NextBestView::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 1129 of file next_best_view.cpp.
std::vector< std::vector< std::vector< int > > > autonomous_mapping::NextBestView::create_costmap | ( | double | x_dim, |
double | y_dim, | ||
int | nr_dirs, | ||
pcl::PointCloud< pcl::PointXYZ > | border_cloud, | ||
geometry_msgs::Point & | min, | ||
geometry_msgs::Point & | max | ||
) | [protected] |
Definition at line 415 of file next_best_view.cpp.
std::vector< std::vector< std::vector< int > > > autonomous_mapping::NextBestView::create_empty_costmap | ( | double | x_dim, |
double | y_dim, | ||
int | nr_dirs | ||
) | [protected] |
Definition at line 401 of file next_best_view.cpp.
void autonomous_mapping::NextBestView::create_kernels | ( | ) | [protected] |
Definition at line 740 of file next_best_view.cpp.
void autonomous_mapping::NextBestView::createOctree | ( | pcl::PointCloud< pcl::PointXYZ > & | pointcloud2_pcl, |
octomap::pose6d | laser_pose | ||
) | [protected] |
creating an octree from pcl data
Definition at line 1427 of file next_best_view.cpp.
void autonomous_mapping::NextBestView::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] |
geometry_msgs::Pose autonomous_mapping::NextBestView::find_best_pose | ( | int | best_i, |
int | best_j, | ||
int | best_k, | ||
int | max_reward, | ||
geometry_msgs::Point & | min, | ||
geometry_msgs::Point & | max | ||
) | [protected] |
Definition at line 457 of file next_best_view.cpp.
void autonomous_mapping::NextBestView::find_max_indices | ( | int & | best_i, |
int & | best_j, | ||
int & | best_k, | ||
int | nr_dirs, | ||
int | x_dim, | ||
int | y_dim, | ||
int & | max_reward, | ||
std::vector< std::vector< std::vector< int > > > | costmap | ||
) | [protected] |
Definition at line 338 of file next_best_view.cpp.
void autonomous_mapping::NextBestView::find_min_max | ( | pcl::PointCloud< pcl::PointXYZ > | border_cloud, |
geometry_msgs::Point & | min, | ||
geometry_msgs::Point & | max | ||
) | [protected] |
Definition at line 390 of file next_best_view.cpp.
void autonomous_mapping::NextBestView::findBorderPoints | ( | pcl::PointCloud< pcl::PointXYZ > & | border_cloud, |
std::string | frame_id | ||
) | [protected] |
Definition at line 1368 of file next_best_view.cpp.
void autonomous_mapping::NextBestView::findOccupiedPoints | ( | pcl::PointCloud< pcl::PointXYZ > & | occupied_cloud, |
std::string | frame_id | ||
) | [protected] |
Definition at line 1347 of file next_best_view.cpp.
void autonomous_mapping::NextBestView::grid_cb | ( | const nav_msgs::OccupancyGridConstPtr & | grid_msg | ) | [protected] |
Definition at line 674 of file next_best_view.cpp.
void autonomous_mapping::NextBestView::onInit | ( | ) | [virtual] |
Reimplemented from pcl_ros::PCLNodelet.
Definition at line 262 of file next_best_view.cpp.
std::vector< std::vector< std::vector< int > > > autonomous_mapping::NextBestView::reduced_costmap | ( | std::vector< std::vector< std::vector< int > > > | costmap, |
int | best_j, | ||
int | best_k, | ||
geometry_msgs::Point & | min, | ||
geometry_msgs::Point & | max, | ||
double & | x_dim, | ||
double & | y_dim | ||
) | [protected] |
Definition at line 472 of file next_best_view.cpp.
geometry_msgs::Pose autonomous_mapping::NextBestView::sample_from_costmap | ( | std::vector< std::vector< std::vector< int > > > | costmap, |
int | max_reward, | ||
int | nr_dirs, | ||
int | x_dim, | ||
int | y_dim, | ||
geometry_msgs::Point | min, | ||
geometry_msgs::Point | max, | ||
int & | reward, | ||
double & | score | ||
) | [protected] |
Definition at line 566 of file next_best_view.cpp.
void autonomous_mapping::NextBestView::save_costmaps | ( | int | nr_dirs, |
std::vector< std::vector< std::vector< int > > > | costmap, | ||
std::string | file_prefix, | ||
ros::Time | stamp | ||
) | [protected] |
Definition at line 371 of file next_best_view.cpp.
void autonomous_mapping::NextBestView::visualizeOctree | ( | const sensor_msgs::PointCloud2ConstPtr & | pointcloud2_msg, |
geometry_msgs::Point | viewpoint | ||
) | [protected] |
Definition at line 1512 of file next_best_view.cpp.
Definition at line 197 of file next_best_view.cpp.
Definition at line 198 of file next_best_view.cpp.
double autonomous_mapping::NextBestView::boundary_angle_threshold_ [protected] |
Definition at line 142 of file next_best_view.cpp.
bool autonomous_mapping::NextBestView::check_centroids_ [protected] |
Definition at line 134 of file next_best_view.cpp.
sensor_msgs::PointCloud2 autonomous_mapping::NextBestView::cloud_in_ [protected] |
Definition at line 179 of file next_best_view.cpp.
Definition at line 186 of file next_best_view.cpp.
double autonomous_mapping::NextBestView::costmap_grid_cell_size_ [protected] |
Definition at line 151 of file next_best_view.cpp.
double autonomous_mapping::NextBestView::eps_angle_ [protected] |
Definition at line 140 of file next_best_view.cpp.
int autonomous_mapping::NextBestView::free_label_ [protected] |
Definition at line 133 of file next_best_view.cpp.
int autonomous_mapping::NextBestView::free_nr_ [protected] |
Definition at line 162 of file next_best_view.cpp.
int autonomous_mapping::NextBestView::fringe_label_ [protected] |
Definition at line 133 of file next_best_view.cpp.
int autonomous_mapping::NextBestView::fringe_nr_ [protected] |
Definition at line 162 of file next_best_view.cpp.
Definition at line 163 of file next_best_view.cpp.
Definition at line 187 of file next_best_view.cpp.
Definition at line 124 of file next_best_view.cpp.
double autonomous_mapping::NextBestView::kernel_degree_step_ [protected] |
Definition at line 148 of file next_best_view.cpp.
double autonomous_mapping::NextBestView::kernel_radial_step_ [protected] |
Definition at line 149 of file next_best_view.cpp.
Definition at line 127 of file next_best_view.cpp.
int autonomous_mapping::NextBestView::level_ [protected] |
Definition at line 133 of file next_best_view.cpp.
nav_msgs::OccupancyGrid autonomous_mapping::NextBestView::map_ [protected] |
Definition at line 184 of file next_best_view.cpp.
visualization_msgs::MarkerArray autonomous_mapping::NextBestView::marker [protected] |
Definition at line 181 of file next_best_view.cpp.
visualization_msgs::Marker autonomous_mapping::NextBestView::marker_bound_ [protected] |
Definition at line 182 of file next_best_view.cpp.
Definition at line 195 of file next_best_view.cpp.
visualization_msgs::Marker autonomous_mapping::NextBestView::marker_occ_ [protected] |
Definition at line 183 of file next_best_view.cpp.
Definition at line 196 of file next_best_view.cpp.
Definition at line 139 of file next_best_view.cpp.
geometry_msgs::PoseArray autonomous_mapping::NextBestView::nbv_pose_array_ [protected] |
Definition at line 180 of file next_best_view.cpp.
double autonomous_mapping::NextBestView::normal_search_radius_ [protected] |
Definition at line 138 of file next_best_view.cpp.
Definition at line 145 of file next_best_view.cpp.
double autonomous_mapping::NextBestView::nr_pose_samples_ [protected] |
Definition at line 159 of file next_best_view.cpp.
int autonomous_mapping::NextBestView::number [protected] |
Definition at line 161 of file next_best_view.cpp.
int autonomous_mapping::NextBestView::occupied_label_ [protected] |
Definition at line 133 of file next_best_view.cpp.
int autonomous_mapping::NextBestView::occupied_nr_ [protected] |
Definition at line 162 of file next_best_view.cpp.
octomap::ScanGraph* autonomous_mapping::NextBestView::octomap_graph_ [protected] |
Definition at line 175 of file next_best_view.cpp.
Definition at line 174 of file next_best_view.cpp.
visualization_msgs::MarkerArray autonomous_mapping::NextBestView::octree_marker_array_msg_ [protected] |
Definition at line 205 of file next_best_view.cpp.
Definition at line 200 of file next_best_view.cpp.
Definition at line 203 of file next_best_view.cpp.
double autonomous_mapping::NextBestView::octree_maxrange_ [protected] |
Definition at line 132 of file next_best_view.cpp.
Definition at line 188 of file next_best_view.cpp.
double autonomous_mapping::NextBestView::octree_res_ [protected] |
Definition at line 132 of file next_best_view.cpp.
Definition at line 194 of file next_best_view.cpp.
Definition at line 129 of file next_best_view.cpp.
Definition at line 128 of file next_best_view.cpp.
Definition at line 125 of file next_best_view.cpp.
Definition at line 126 of file next_best_view.cpp.
Definition at line 165 of file next_best_view.cpp.
Definition at line 192 of file next_best_view.cpp.
Definition at line 191 of file next_best_view.cpp.
Definition at line 191 of file next_best_view.cpp.
Definition at line 193 of file next_best_view.cpp.
Definition at line 190 of file next_best_view.cpp.
octomap::KeyRay autonomous_mapping::NextBestView::ray [protected] |
Definition at line 177 of file next_best_view.cpp.
bool autonomous_mapping::NextBestView::received_map_ [protected] |
Definition at line 160 of file next_best_view.cpp.
double autonomous_mapping::NextBestView::sensor_d_max_ [protected] |
Definition at line 147 of file next_best_view.cpp.
double autonomous_mapping::NextBestView::sensor_d_min_ [protected] |
Definition at line 146 of file next_best_view.cpp.
double autonomous_mapping::NextBestView::sensor_horizontal_angle_ [protected] |
Definition at line 152 of file next_best_view.cpp.
double autonomous_mapping::NextBestView::sensor_horizontal_resolution_ [protected] |
Definition at line 154 of file next_best_view.cpp.
double autonomous_mapping::NextBestView::sensor_opening_angle_ [protected] |
Definition at line 150 of file next_best_view.cpp.
double autonomous_mapping::NextBestView::sensor_preferred_d_max_ [protected] |
Definition at line 158 of file next_best_view.cpp.
double autonomous_mapping::NextBestView::sensor_preferred_d_min_ [protected] |
Definition at line 157 of file next_best_view.cpp.
double autonomous_mapping::NextBestView::sensor_preferred_opening_angle_ [protected] |
Definition at line 156 of file next_best_view.cpp.
double autonomous_mapping::NextBestView::sensor_vertical_angle_ [protected] |
Definition at line 153 of file next_best_view.cpp.
double autonomous_mapping::NextBestView::sensor_vertical_resolution_ [protected] |
Definition at line 155 of file next_best_view.cpp.
Reimplemented from pcl_ros::PCLNodelet.
Definition at line 171 of file next_best_view.cpp.
double autonomous_mapping::NextBestView::tolerance_ [protected] |
Definition at line 141 of file next_best_view.cpp.
int autonomous_mapping::NextBestView::unknown_label_ [protected] |
Definition at line 133 of file next_best_view.cpp.
std::vector<std::vector<point_2d> > autonomous_mapping::NextBestView::vis_kernel [protected] |
Definition at line 168 of file next_best_view.cpp.
bool autonomous_mapping::NextBestView::visualize_octree_ [protected] |
Definition at line 135 of file next_best_view.cpp.