#include <ros/ros.h>#include <pcl/point_types.h>#include <pcl_conversions/pcl_conversions.h>#include <pcl_ros/point_cloud.h>#include "pcl_ros/transforms.h"#include <sensor_msgs/PointCloud2.h>#include <tf/transform_listener.h>#include <octomap/octomap.h>#include <octomap_msgs/Octomap.h>#include <octomap_msgs/conversions.h>#include <geometry_msgs/Pose.h>#include <algorithm>

Go to the source code of this file.
Classes | |
| struct | sensorModel |
Typedefs | |
| typedef octomap::point3d | point3d |
| typedef pcl::PointCloud < pcl::PointXYZ > | PointCloud |
| typedef pcl::PointXYZ | PointType |
Functions | |
| double | calc_MI (const octomap::OcTree *octree, const point3d &sensor_orig, const octomap::Pointcloud &hits, const double before) |
| octomap::Pointcloud | castSensorRays (const octomap::OcTree *octree, const point3d &position, const point3d &sensor_orientation) |
| double | countFreeVolume (const octomap::OcTree *octree) |
| vector< pair< point3d, point3d > > | extractCandidateViewPoints (vector< vector< point3d >> frontier_groups, point3d sensor_orig, int n) |
| vector< vector< point3d > > | extractFrontierPoints (const octomap::OcTree *octree) |
| sensorModel | Kinect_360 (64, 48, 2 *PI *57/360, 2 *PI *43/360, 6) |
| void | kinectCallbacks (const sensor_msgs::PointCloud2ConstPtr &cloud2_msg) |
| vector< int > | sort_MIs (const vector< double > &v) |
Variables | |
| octomap::OcTree * | cur_tree |
| octomap::OcTree * | cur_tree_2d |
| ofstream | explo_log_file |
| point3d | kinect_orig |
| octomap_msgs::Octomap | msg_octomap |
| const int | num_of_bay = 3 |
| const int | num_of_samples = 12 |
| const int | num_of_samples_eva = 15 |
| const double | octo_reso = 0.1 |
| std::string | octomap_name_2d |
| std::string | octomap_name_3d |
| const double | PI = 3.1415926 |
| tf::TransformListener * | tf_listener |
| typedef octomap::point3d point3d |
Definition at line 21 of file exploration.h.
| typedef pcl::PointCloud<pcl::PointXYZ> PointCloud |
Definition at line 23 of file exploration.h.
| typedef pcl::PointXYZ PointType |
Definition at line 22 of file exploration.h.
| double calc_MI | ( | const octomap::OcTree * | octree, |
| const point3d & | sensor_orig, | ||
| const octomap::Pointcloud & | hits, | ||
| const double | before | ||
| ) |
Definition at line 257 of file exploration.h.
| octomap::Pointcloud castSensorRays | ( | const octomap::OcTree * | octree, |
| const point3d & | position, | ||
| const point3d & | sensor_orientation | ||
| ) |
Definition at line 90 of file exploration.h.
| double countFreeVolume | ( | const octomap::OcTree * | octree | ) |
Definition at line 80 of file exploration.h.
| vector<pair<point3d, point3d> > extractCandidateViewPoints | ( | vector< vector< point3d >> | frontier_groups, |
| point3d | sensor_orig, | ||
| int | n | ||
| ) |
Definition at line 188 of file exploration.h.
| vector<vector<point3d> > extractFrontierPoints | ( | const octomap::OcTree * | octree | ) |
Definition at line 112 of file exploration.h.
| sensorModel Kinect_360 | ( | 64 | , |
| 48 | , | ||
| 2 *PI *57/ | 360, | ||
| 2 *PI *43/ | 360, | ||
| 6 | |||
| ) |
| void kinectCallbacks | ( | const sensor_msgs::PointCloud2ConstPtr & | cloud2_msg | ) |
Definition at line 267 of file exploration.h.
Definition at line 42 of file exploration.h.
Definition at line 31 of file exploration.h.
Definition at line 32 of file exploration.h.
| ofstream explo_log_file |
Definition at line 39 of file exploration.h.
Definition at line 37 of file exploration.h.
| octomap_msgs::Octomap msg_octomap |
Definition at line 33 of file exploration.h.
| const int num_of_bay = 3 |
Definition at line 28 of file exploration.h.
| const int num_of_samples = 12 |
Definition at line 26 of file exploration.h.
| const int num_of_samples_eva = 15 |
Definition at line 27 of file exploration.h.
| const double octo_reso = 0.1 |
Definition at line 25 of file exploration.h.
Definition at line 40 of file exploration.h.
Definition at line 40 of file exploration.h.
| const double PI = 3.1415926 |
Definition at line 24 of file exploration.h.
Definition at line 35 of file exploration.h.