#include <navigation.h>
| Public Member Functions | |
| bool | checkViewRayValidness (cv::Point source, cv::Point target) | 
| std::vector< NextBestView > | compute_frontier_tasks (Polygon_2 boundary, std::vector< Polygon_2 > holes) | 
| bool | compute_robot_move_nodes (std::vector< double > &distances) | 
| bool | compute_sync_move_paths (std::vector< double > distances) | 
| cv::Mat | computeLoationMap () | 
| void | correct_boundary_holes (Polygon_2 &boundary, std::vector< Polygon_2 > &holes) | 
| Pwh_list_2 | differenceCGALExactKernel (Polygon_with_holes_2 domain, Polygon_2 hole) | 
| std::vector< NextBestView > | extractQualityTaskViews (Polygon_2 boundary, std::vector< Polygon_2 > holes) | 
| bool | extractTasks (Polygon_2 boundary, std::vector< Polygon_2 > holes, std::vector< ScanningTask > &tasks) | 
| bool | generateMoveDomainCDT (Polygon_2 boundary, std::vector< Polygon_2 > holes, std::vector< Polygon_2 > origin_holes, std::vector< ScanningTask > tasks, CDT &cdt) | 
| std::vector< NextBestView > | generateViewsFrontiers (bool enableSampling=false, double sampleRate=0.5) | 
| vector< cv::Point > | get_frustum_contuor (iro::SE2 pose) | 
| Polygon_2 | load_and_check_boundary () | 
| std::vector< Point_2 > | load_and_check_frontiers (Polygon_2 &boundary, std::vector< Polygon_2 > &holes) | 
| std::vector< Polygon_2 > | load_and_check_holes (Polygon_2 boundary, std::vector< Polygon_2 > &origin_holes) | 
| void | moveRobotsAndScan () | 
| Navigation (DataEngine &de, int paramK=6) | |
| void | OMT_TSP () | 
| bool | path_occlusion_check (cv::Mat background, cv::Point beg, cv::Point end) | 
| bool | points_equal (Point_2 p1, Point_2 p2) | 
| std::vector< int > | preprocess_frontiers (Polygon_2 outer, std::vector< Polygon_2 > iner) | 
| void | processCurrentScene () | 
| bool | robotMoveDomainProcess (Polygon_2 &boundary, std::vector< Polygon_2 > &holes, std::vector< Polygon_2 > &origin_holes) | 
| void | scanFinished () | 
| bool | se2_equal (iro::SE2 p1, iro::SE2 p2) | 
| bool | simplifyPolygon (Polygon_2 &poly, const double colinearThresh, bool addNoise) | 
| void | Trajectory_Optimization () | 
| void | trajectoryInterpolation (std::vector< iro::SE2 > &path, double dAngle=PI/12) | 
| std::vector< int > | TSP_path (std::vector< Point_2 > points, std::vector< vector< double >> weights) | 
| std::vector< iro::SE2 > | uniformSampleWithNBVInfo (const int robot_id, const double step, const double length) | 
| bool | visualizeScan (std::vector< iro::SE2 > current_views, int vid) | 
| Public Attributes | |
| std::vector< cv::Point > | m_boundary | 
| std::vector< FrontierElement > | m_frontierList | 
| std::vector< cv::Point > | m_frontiers | 
| std::vector< Point_2 > | m_frontiers_p2 | 
| std::vector< std::vector< cv::Point > > | m_holes | 
| int | m_max_task_num = 30 | 
| DistanceMetric | m_metric | 
| DataEngine * | m_p_de | 
| std::vector< std::vector< iro::SE2 > > | m_robot_move_nodes | 
| std::vector< std::vector< bool > > | m_robot_move_nodes_nbv_sign | 
| std::vector< std::vector< iro::SE2 > > | m_robot_move_views | 
| std::vector< Point_2 > | m_robot_sites | 
| std::vector< std::vector< iro::SE2 > > | m_sync_move_paths | 
| std::vector< int > | m_task_index_in_valid_object_nbvs | 
| std::vector< NextBestView > | m_valid_object_nbvs | 
| int | rbt_num | 
| std::set< Point_2 > | task_maybe_invalid | 
Definition at line 152 of file navigation.h.
| 
 | inline | 
Definition at line 182 of file navigation.h.
| bool Navigation::checkViewRayValidness | ( | cv::Point | source, | 
| cv::Point | target | ||
| ) | 
Definition at line 1211 of file navigation.cpp.
| vector< NextBestView > Navigation::compute_frontier_tasks | ( | Polygon_2 | boundary, | 
| std::vector< Polygon_2 > | holes | ||
| ) | 
Definition at line 1523 of file navigation.cpp.
| bool Navigation::compute_robot_move_nodes | ( | std::vector< double > & | distances | ) | 
Definition at line 2319 of file navigation.cpp.
| bool Navigation::compute_sync_move_paths | ( | std::vector< double > | distances | ) | 
Definition at line 2631 of file navigation.cpp.
| cv::Mat Navigation::computeLoationMap | ( | ) | 
Definition at line 1181 of file navigation.cpp.
Definition at line 562 of file navigation.cpp.
| Pwh_list_2 Navigation::differenceCGALExactKernel | ( | Polygon_with_holes_2 | domain, | 
| Polygon_2 | hole | ||
| ) | 
Definition at line 381 of file navigation.cpp.
| vector< NextBestView > Navigation::extractQualityTaskViews | ( | Polygon_2 | boundary, | 
| std::vector< Polygon_2 > | holes | ||
| ) | 
Definition at line 1579 of file navigation.cpp.
| bool Navigation::extractTasks | ( | Polygon_2 | boundary, | 
| std::vector< Polygon_2 > | holes, | ||
| std::vector< ScanningTask > & | tasks | ||
| ) | 
Definition at line 1670 of file navigation.cpp.
| bool Navigation::generateMoveDomainCDT | ( | Polygon_2 | boundary, | 
| std::vector< Polygon_2 > | holes, | ||
| std::vector< Polygon_2 > | origin_holes, | ||
| std::vector< ScanningTask > | tasks, | ||
| CDT & | cdt | ||
| ) | 
Definition at line 878 of file navigation.cpp.
| vector< NextBestView > Navigation::generateViewsFrontiers | ( | bool | enableSampling = false, | 
| double | sampleRate = 0.5 | ||
| ) | 
Definition at line 1343 of file navigation.cpp.
| vector< cv::Point > Navigation::get_frustum_contuor | ( | iro::SE2 | pose | ) | 
Definition at line 1286 of file navigation.cpp.
| Polygon_2 Navigation::load_and_check_boundary | ( | ) | 
Definition at line 447 of file navigation.cpp.
| vector< Point_2 > Navigation::load_and_check_frontiers | ( | Polygon_2 & | boundary, | 
| std::vector< Polygon_2 > & | holes | ||
| ) | 
Definition at line 1006 of file navigation.cpp.
| vector< Polygon_2 > Navigation::load_and_check_holes | ( | Polygon_2 | boundary, | 
| std::vector< Polygon_2 > & | origin_holes | ||
| ) | 
Definition at line 491 of file navigation.cpp.
| void Navigation::moveRobotsAndScan | ( | ) | 
Definition at line 3041 of file navigation.cpp.
| void Navigation::OMT_TSP | ( | ) | 
Definition at line 1963 of file navigation.cpp.
| bool Navigation::path_occlusion_check | ( | cv::Mat | background, | 
| cv::Point | beg, | ||
| cv::Point | end | ||
| ) | 
Definition at line 2243 of file navigation.cpp.
Definition at line 2508 of file navigation.cpp.
Definition at line 1016 of file navigation.cpp.
| void Navigation::processCurrentScene | ( | ) | 
Definition at line 8 of file navigation.cpp.
| bool Navigation::robotMoveDomainProcess | ( | Polygon_2 & | boundary, | 
| std::vector< Polygon_2 > & | holes, | ||
| std::vector< Polygon_2 > & | origin_holes | ||
| ) | 
Definition at line 659 of file navigation.cpp.
| void Navigation::scanFinished | ( | ) | 
Definition at line 1803 of file navigation.cpp.
Definition at line 2518 of file navigation.cpp.
| bool Navigation::simplifyPolygon | ( | Polygon_2 & | poly, | 
| const double | colinearThresh, | ||
| bool | addNoise | ||
| ) | 
Definition at line 327 of file navigation.cpp.
| void Navigation::Trajectory_Optimization | ( | ) | 
Definition at line 2878 of file navigation.cpp.
| void Navigation::trajectoryInterpolation | ( | std::vector< iro::SE2 > & | path, | 
| double | dAngle = PI / 12 | ||
| ) | 
Definition at line 2831 of file navigation.cpp.
| vector< int > Navigation::TSP_path | ( | std::vector< Point_2 > | points, | 
| std::vector< vector< double >> | weights | ||
| ) | 
Definition at line 1812 of file navigation.cpp.
| vector< iro::SE2 > Navigation::uniformSampleWithNBVInfo | ( | const int | robot_id, | 
| const double | step, | ||
| const double | length | ||
| ) | 
Definition at line 2528 of file navigation.cpp.
| bool Navigation::visualizeScan | ( | std::vector< iro::SE2 > | current_views, | 
| int | vid | ||
| ) | 
Definition at line 3313 of file navigation.cpp.
| std::vector<cv::Point> Navigation::m_boundary | 
Definition at line 158 of file navigation.h.
| std::vector<FrontierElement> Navigation::m_frontierList | 
Definition at line 171 of file navigation.h.
| std::vector<cv::Point> Navigation::m_frontiers | 
Definition at line 159 of file navigation.h.
| std::vector<Point_2> Navigation::m_frontiers_p2 | 
Definition at line 160 of file navigation.h.
| std::vector<std::vector<cv::Point> > Navigation::m_holes | 
Definition at line 161 of file navigation.h.
| int Navigation::m_max_task_num = 30 | 
Definition at line 156 of file navigation.h.
| DistanceMetric Navigation::m_metric | 
Definition at line 168 of file navigation.h.
| DataEngine* Navigation::m_p_de | 
Definition at line 166 of file navigation.h.
| std::vector<std::vector<iro::SE2> > Navigation::m_robot_move_nodes | 
Definition at line 177 of file navigation.h.
| std::vector<std::vector<bool> > Navigation::m_robot_move_nodes_nbv_sign | 
Definition at line 178 of file navigation.h.
| std::vector<std::vector<iro::SE2> > Navigation::m_robot_move_views | 
Definition at line 176 of file navigation.h.
| std::vector<Point_2> Navigation::m_robot_sites | 
Definition at line 163 of file navigation.h.
| std::vector<std::vector<iro::SE2> > Navigation::m_sync_move_paths | 
Definition at line 179 of file navigation.h.
| std::vector<int> Navigation::m_task_index_in_valid_object_nbvs | 
Definition at line 174 of file navigation.h.
| std::vector<NextBestView> Navigation::m_valid_object_nbvs | 
Definition at line 173 of file navigation.h.
| int Navigation::rbt_num | 
Definition at line 162 of file navigation.h.
Definition at line 172 of file navigation.h.