#include <router.h>
 | 
| bool  | calculateStartPoints (const std::vector< float > &_radius, const cv::Mat &_map, const float &resolution, const Eigen::Vector2d &origin, const std::vector< Segment > &_graph) | 
|   | 
| float  | distanceToSegment (const Segment &_s, const Eigen::Vector2d &_p) const  | 
|   | 
| int32_t  | getSegment (const std::vector< Segment > &_graph, const Eigen::Vector2d &_pose) const  | 
|   | 
| void  | optimizePaths (const std::vector< Segment > &_graph) | 
|   | 
| void  | postprocessRoutingTable () | 
|   | 
| bool  | preprocessEndpoints (const std::vector< float > &_radius, const float &resolution, const Eigen::Vector2d &origin, const std::vector< Segment > &_graph) | 
|   | 
| bool  | processEndpointsExpander (const cv::Mat &_map, const std::vector< Segment > &_graph, const Eigen::Vector2d &_realStart, const Eigen::Vector2d &_realGoal, Eigen::Vector2d &_voronoiStart, Eigen::Vector2d &_voronoiGoal, uint32_t &_segmentStart, uint32_t &_segmentGoal, const uint32_t _diameter, const uint32_t _index) const  | 
|   | 
| bool  | resolveSegment (const std::vector< Segment > &_graph, const uint32_t &_segId, const Eigen::Vector2d &_originPoint, const float &_radius, uint32_t &_foundSeg) const  | 
|   | 
Definition at line 41 of file router.h.
 
| Enumerator | 
|---|
| use_segment_goal  | 
 | 
| use_voronoi_goal  | 
 | 
| use_map_goal  | 
 | 
Definition at line 137 of file router.h.
 
 
| Enumerator | 
|---|
| singleThread  | 
 | 
| multiThreadSrr  | 
 | 
Definition at line 148 of file router.h.
 
 
      
        
          | multi_robot_router::Router::Router  | 
          ( | 
          const uint32_t  | 
          _nr_robots | ) | 
           | 
        
      
 
 
      
        
          | multi_robot_router::Router::Router  | 
          ( | 
           | ) | 
           | 
        
      
 
 
  
  
      
        
          | bool multi_robot_router::Router::calculateStartPoints  | 
          ( | 
          const std::vector< float > &  | 
          _radius,  | 
         
        
           | 
           | 
          const cv::Mat &  | 
          _map,  | 
         
        
           | 
           | 
          const float &  | 
          resolution,  | 
         
        
           | 
           | 
          const Eigen::Vector2d &  | 
          origin,  | 
         
        
           | 
           | 
          const std::vector< Segment > &  | 
          _graph  | 
         
        
           | 
          ) | 
           |  | 
         
       
   | 
  
private   | 
  
 
 
  
  
      
        
          | float multi_robot_router::Router::distanceToSegment  | 
          ( | 
          const Segment &  | 
          _s,  | 
         
        
           | 
           | 
          const Eigen::Vector2d &  | 
          _p  | 
         
        
           | 
          ) | 
           |  const | 
         
       
   | 
  
private   | 
  
 
 
      
        
          | uint32_t multi_robot_router::Router::getDuration_ms  | 
          ( | 
           | ) | 
           const | 
        
      
 
getter 
- Returns
 - the duration of the planning attempt 
 
Definition at line 464 of file router.cpp.
 
 
      
        
          | float multi_robot_router::Router::getLongestPathLength  | 
          ( | 
           | ) | 
           const | 
        
      
 
getter 
- Returns
 - the longest Path length of the planning attempt 
 
Definition at line 469 of file router.cpp.
 
 
      
        
          | float multi_robot_router::Router::getOverallPathLength  | 
          ( | 
           | ) | 
           const | 
        
      
 
getter 
- Returns
 - the Overall path length of the planning attempt 
 
Definition at line 474 of file router.cpp.
 
 
      
        
          | uint32_t multi_robot_router::Router::getPriorityScheduleAttemps  | 
          ( | 
           | ) | 
           const | 
        
      
 
getter 
- Returns
 - the priority reschedule attempts 
 
Definition at line 479 of file router.cpp.
 
 
      
        
          | const std::vector< Checkpoint > & multi_robot_router::Router::getRoute  | 
          ( | 
          const uint32_t  | 
          _robot | ) | 
           const | 
        
      
 
returns the found Routing Table 
- Parameters
 - 
  
    | _robot | the robot to whom the routing table belongs to  | 
  
   
Definition at line 459 of file router.cpp.
 
 
  
  
      
        
          | int32_t multi_robot_router::Router::getSegment  | 
          ( | 
          const std::vector< Segment > &  | 
          _graph,  | 
         
        
           | 
           | 
          const Eigen::Vector2d &  | 
          _pose  | 
         
        
           | 
          ) | 
           |  const | 
         
       
   | 
  
private   | 
  
 
 
      
        
          | uint32_t multi_robot_router::Router::getSpeedScheduleAttemps  | 
          ( | 
           | ) | 
           const | 
        
      
 
getter 
- Returns
 - the speed reschedule attempts 
 
Definition at line 484 of file router.cpp.
 
 
      
        
          | bool multi_robot_router::Router::makePlan  | 
          ( | 
          const std::vector< Eigen::Vector3d > &  | 
          _starts,  | 
        
        
           | 
           | 
          const std::vector< Eigen::Vector3d > &  | 
          _goals,  | 
        
        
           | 
           | 
          const std::vector< float > &  | 
          _radius,  | 
        
        
           | 
           | 
          const cv::Mat &  | 
          _map,  | 
        
        
           | 
           | 
          const float &  | 
          _resolution,  | 
        
        
           | 
           | 
          const Eigen::Vector2d &  | 
          _origin,  | 
        
        
           | 
           | 
          const std::vector< Segment > &  | 
          _graph,  | 
        
        
           | 
           | 
          const std::vector< std::string > &  | 
          _robot_names  | 
        
        
           | 
          ) | 
           |  | 
        
      
 
generates the plan from (Vertex[odom robotPose] to Vertex[_goals] 
- Parameters
 - 
  
    | _starts | the start positions of all robots  | 
    | _goals | the goal positions fo all robots  | 
    | _radius | a vector of the robots radius'  | 
    | _map | the grid_map used to find the start and goal segments of the path  | 
    | _graph | the full graph of the map used for planning the path  | 
    | _robot_names | robot names  | 
  
   
Definition at line 328 of file router.cpp.
 
 
  
  
      
        
          | void multi_robot_router::Router::optimizePaths  | 
          ( | 
          const std::vector< Segment > &  | 
          _graph | ) | 
           | 
         
       
   | 
  
private   | 
  
 
 
  
  
      
        
          | void multi_robot_router::Router::postprocessRoutingTable  | 
          ( | 
           | ) | 
           | 
         
       
   | 
  
private   | 
  
 
 
  
  
      
        
          | bool multi_robot_router::Router::preprocessEndpoints  | 
          ( | 
          const std::vector< float > &  | 
          _radius,  | 
         
        
           | 
           | 
          const float &  | 
          resolution,  | 
         
        
           | 
           | 
          const Eigen::Vector2d &  | 
          origin,  | 
         
        
           | 
           | 
          const std::vector< Segment > &  | 
          _graph  | 
         
        
           | 
          ) | 
           |  | 
         
       
   | 
  
private   | 
  
 
 
  
  
      
        
          | bool multi_robot_router::Router::processEndpointsExpander  | 
          ( | 
          const cv::Mat &  | 
          _map,  | 
         
        
           | 
           | 
          const std::vector< Segment > &  | 
          _graph,  | 
         
        
           | 
           | 
          const Eigen::Vector2d &  | 
          _realStart,  | 
         
        
           | 
           | 
          const Eigen::Vector2d &  | 
          _realGoal,  | 
         
        
           | 
           | 
          Eigen::Vector2d &  | 
          _voronoiStart,  | 
         
        
           | 
           | 
          Eigen::Vector2d &  | 
          _voronoiGoal,  | 
         
        
           | 
           | 
          uint32_t &  | 
          _segmentStart,  | 
         
        
           | 
           | 
          uint32_t &  | 
          _segmentGoal,  | 
         
        
           | 
           | 
          const uint32_t  | 
          _diameter,  | 
         
        
           | 
           | 
          const uint32_t  | 
          _index  | 
         
        
           | 
          ) | 
           |  const | 
         
       
   | 
  
private   | 
  
 
 
      
        
          | void multi_robot_router::Router::resize  | 
          ( | 
          const uint32_t  | 
          _nr_robots | ) | 
           | 
        
      
 
resizes the planner to a different nr of _nr_robots 
Definition at line 67 of file router.cpp.
 
 
  
  
      
        
          | bool multi_robot_router::Router::resolveSegment  | 
          ( | 
          const std::vector< Segment > &  | 
          _graph,  | 
         
        
           | 
           | 
          const uint32_t &  | 
          _segId,  | 
         
        
           | 
           | 
          const Eigen::Vector2d &  | 
          _originPoint,  | 
         
        
           | 
           | 
          const float &  | 
          _radius,  | 
         
        
           | 
           | 
          uint32_t &  | 
          _foundSeg  | 
         
        
           | 
          ) | 
           |  const | 
         
       
   | 
  
private   | 
  
 
 
sets the CollisionResolverType used 
Definition at line 54 of file router.cpp.
 
 
  
  
      
        
          | void multi_robot_router::Router::setPlannerType  | 
          ( | 
          Router::routerType  | 
          _type,  | 
         
        
           | 
           | 
          uint32_t  | 
          _nr_threads  | 
         
        
           | 
          ) | 
           |  | 
         
       
   | 
  
protected   | 
  
 
 
  
  
      
        
          | bool multi_robot_router::Router::collisionResolver_ = true | 
         
       
   | 
  
protected   | 
  
 
 
  
  
      
        
          | uint32_t multi_robot_router::Router::duration_ | 
         
       
   | 
  
private   | 
  
 
 
  
  
      
        
          | std::vector<Eigen::Vector3d> multi_robot_router::Router::goals_ | 
         
       
   | 
  
private   | 
  
 
 
  
  
      
        
          | std::vector<uint32_t> multi_robot_router::Router::goalSegments_ | 
         
       
   | 
  
private   | 
  
 
 
  
  
      
        
          | float multi_robot_router::Router::longestPatLength_ | 
         
       
   | 
  
private   | 
  
 
 
  
  
      
        
          | float multi_robot_router::Router::overallPathLength_ | 
         
       
   | 
  
private   | 
  
 
 
with the robot id one can access the robot name 
Definition at line 127 of file router.h.
 
 
      
        
          | std::shared_ptr<float> multi_robot_router::Router::potential_ | 
        
      
 
 
  
  
      
        
          | bool multi_robot_router::Router::priorityRescheduling_ = true | 
         
       
   | 
  
protected   | 
  
 
 
  
  
      
        
          | std::vector<Eigen::Vector2d> multi_robot_router::Router::realGoals_ | 
         
       
   | 
  
private   | 
  
 
 
  
  
      
        
          | std::vector<Eigen::Vector2d> multi_robot_router::Router::realStart_ | 
         
       
   | 
  
private   | 
  
 
 
  
  
      
        
          | std::vector<std::string> multi_robot_router::Router::robot_names_ | 
         
       
   | 
  
private   | 
  
 
 
  
  
      
        
          | uint32_t multi_robot_router::Router::robot_nr_ | 
         
       
   | 
  
private   | 
  
 
 
  
  
      
        
          | float multi_robot_router::Router::routerTimeLimit_s_ = 10.0 | 
         
       
   | 
  
protected   | 
  
 
 
  
  
      
        
          | std::vector<std::vector<Checkpoint> > multi_robot_router::Router::routingTable_ | 
         
       
   | 
  
private   | 
  
 
 
  
  
      
        
          | bool multi_robot_router::Router::segmentOptimizations_ = false | 
         
       
   | 
  
protected   | 
  
 
 
  
  
      
        
          | bool multi_robot_router::Router::speedRescheduling_ = true | 
         
       
   | 
  
protected   | 
  
 
 
  
  
      
        
          | std::vector<Eigen::Vector3d> multi_robot_router::Router::starts_ | 
         
       
   | 
  
private   | 
  
 
 
  
  
      
        
          | std::vector<uint32_t> multi_robot_router::Router::startSegments_ | 
         
       
   | 
  
private   | 
  
 
 
  
  
      
        
          | std::vector<Eigen::Vector2d> multi_robot_router::Router::voronoiGoals_ | 
         
       
   | 
  
private   | 
  
 
 
  
  
      
        
          | std::vector<Eigen::Vector2d> multi_robot_router::Router::voronoiStart_ | 
         
       
   | 
  
private   | 
  
 
 
The documentation for this class was generated from the following files: