Public Member Functions | Public Attributes | Protected Types | Protected Member Functions | Protected Attributes | Private Member Functions | Private Attributes | List of all members
multi_robot_router::Router Class Reference

#include <router.h>

Inheritance diagram for multi_robot_router::Router:
Inheritance graph
[legend]

Public Member Functions

uint32_t getDuration_ms () const
 getter More...
 
float getLongestPathLength () const
 getter More...
 
float getOverallPathLength () const
 getter More...
 
uint32_t getPriorityScheduleAttemps () const
 getter More...
 
const std::vector< Checkpoint > & getRoute (const uint32_t _robot) const
 returns the found Routing Table More...
 
uint32_t getSpeedScheduleAttemps () const
 getter More...
 
bool 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] More...
 
void resize (const uint32_t _nr_robots)
 resizes the planner to a different nr of _nr_robots More...
 
 Router (const uint32_t _nr_robots)
 
 Router ()
 
void setCollisionResolutionType (const SegmentExpander::CollisionResolverType _cr)
 sets the CollisionResolverType used More...
 

Public Attributes

std::shared_ptr< float > potential_
 

Protected Types

enum  goalMode { goalMode::use_segment_goal, goalMode::use_voronoi_goal, goalMode::use_map_goal }
 
enum  graphType { graphType::voronoi, graphType::random }
 
enum  routerType { routerType::singleThread, routerType::multiThreadSrr }
 

Protected Member Functions

void setPlannerType (routerType _type, uint32_t _nr_threads)
 

Protected Attributes

bool collisionResolver_ = true
 
goalMode goalMode_ = goalMode::use_voronoi_goal
 
graphType graphMode_ = graphType::voronoi
 
bool priorityRescheduling_ = true
 
float routerTimeLimit_s_ = 10.0
 
bool segmentOptimizations_ = false
 
bool speedRescheduling_ = true
 

Private Member Functions

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
 

Private Attributes

uint32_t duration_
 
std::vector< Eigen::Vector3d > goals_
 
std::vector< uint32_t > goalSegments_
 
float longestPatLength_
 
MultiRobotRouter mrr_
 
MultiRobotRouterThreadedSrr mrrTs_
 
MultiRobotRoutermultiRobotRouter_
 
float overallPathLength_
 
PointExpander pointExpander_
 with the robot id one can access the robot name More...
 
std::vector< Eigen::Vector2d > realGoals_
 
std::vector< Eigen::Vector2d > realStart_
 
std::vector< std::string > robot_names_
 
uint32_t robot_nr_
 
std::vector< std::vector< Checkpoint > > routingTable_
 
std::vector< Eigen::Vector3d > starts_
 
std::vector< uint32_t > startSegments_
 
std::vector< Eigen::Vector2d > voronoiGoals_
 
std::vector< Eigen::Vector2d > voronoiStart_
 

Detailed Description

Definition at line 41 of file router.h.

Member Enumeration Documentation

Enumerator
use_segment_goal 
use_voronoi_goal 
use_map_goal 

Definition at line 137 of file router.h.

Enumerator
voronoi 
random 

Definition at line 143 of file router.h.

Enumerator
singleThread 
multiThreadSrr 

Definition at line 148 of file router.h.

Constructor & Destructor Documentation

multi_robot_router::Router::Router ( const uint32_t  _nr_robots)

Definition at line 44 of file router.cpp.

multi_robot_router::Router::Router ( )

Definition at line 40 of file router.cpp.

Member Function Documentation

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

Definition at line 192 of file router.cpp.

float multi_robot_router::Router::distanceToSegment ( const Segment _s,
const Eigen::Vector2d &  _p 
) const
private

Definition at line 257 of file router.cpp.

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
_robotthe 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

Definition at line 237 of file router.cpp.

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
_startsthe start positions of all robots
_goalsthe goal positions fo all robots
_radiusa vector of the robots radius'
_mapthe grid_map used to find the start and goal segments of the path
_graphthe full graph of the map used for planning the path
_robot_namesrobot names

Definition at line 328 of file router.cpp.

void multi_robot_router::Router::optimizePaths ( const std::vector< Segment > &  _graph)
private

Definition at line 414 of file router.cpp.

void multi_robot_router::Router::postprocessRoutingTable ( )
private

Definition at line 426 of file router.cpp.

bool multi_robot_router::Router::preprocessEndpoints ( const std::vector< float > &  _radius,
const float &  resolution,
const Eigen::Vector2d &  origin,
const std::vector< Segment > &  _graph 
)
private

Definition at line 83 of file router.cpp.

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

Definition at line 110 of file router.cpp.

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

Definition at line 280 of file router.cpp.

void multi_robot_router::Router::setCollisionResolutionType ( const SegmentExpander::CollisionResolverType  _cr)

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

Definition at line 59 of file router.cpp.

Member Data Documentation

bool multi_robot_router::Router::collisionResolver_ = true
protected

Definition at line 159 of file router.h.

uint32_t multi_robot_router::Router::duration_
private

Definition at line 134 of file router.h.

goalMode multi_robot_router::Router::goalMode_ = goalMode::use_voronoi_goal
protected

Definition at line 154 of file router.h.

std::vector<Eigen::Vector3d> multi_robot_router::Router::goals_
private

Definition at line 118 of file router.h.

std::vector<uint32_t> multi_robot_router::Router::goalSegments_
private

Definition at line 124 of file router.h.

graphType multi_robot_router::Router::graphMode_ = graphType::voronoi
protected

Definition at line 153 of file router.h.

float multi_robot_router::Router::longestPatLength_
private

Definition at line 133 of file router.h.

MultiRobotRouter multi_robot_router::Router::mrr_
private

Definition at line 129 of file router.h.

MultiRobotRouterThreadedSrr multi_robot_router::Router::mrrTs_
private

Definition at line 130 of file router.h.

MultiRobotRouter* multi_robot_router::Router::multiRobotRouter_
private

Definition at line 128 of file router.h.

float multi_robot_router::Router::overallPathLength_
private

Definition at line 132 of file router.h.

PointExpander multi_robot_router::Router::pointExpander_
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_

Definition at line 96 of file router.h.

bool multi_robot_router::Router::priorityRescheduling_ = true
protected

Definition at line 158 of file router.h.

std::vector<Eigen::Vector2d> multi_robot_router::Router::realGoals_
private

Definition at line 119 of file router.h.

std::vector<Eigen::Vector2d> multi_robot_router::Router::realStart_
private

Definition at line 120 of file router.h.

std::vector<std::string> multi_robot_router::Router::robot_names_
private

Definition at line 125 of file router.h.

uint32_t multi_robot_router::Router::robot_nr_
private

Definition at line 116 of file router.h.

float multi_robot_router::Router::routerTimeLimit_s_ = 10.0
protected

Definition at line 155 of file router.h.

std::vector<std::vector<Checkpoint> > multi_robot_router::Router::routingTable_
private

Definition at line 131 of file router.h.

bool multi_robot_router::Router::segmentOptimizations_ = false
protected

Definition at line 156 of file router.h.

bool multi_robot_router::Router::speedRescheduling_ = true
protected

Definition at line 157 of file router.h.

std::vector<Eigen::Vector3d> multi_robot_router::Router::starts_
private

Definition at line 117 of file router.h.

std::vector<uint32_t> multi_robot_router::Router::startSegments_
private

Definition at line 123 of file router.h.

std::vector<Eigen::Vector2d> multi_robot_router::Router::voronoiGoals_
private

Definition at line 121 of file router.h.

std::vector<Eigen::Vector2d> multi_robot_router::Router::voronoiStart_
private

Definition at line 122 of file router.h.


The documentation for this class was generated from the following files:


tuw_multi_robot_router
Author(s): Benjamin Binder
autogenerated on Mon Jun 10 2019 15:42:49