Classes | Public Types | Public Member Functions | Private Member Functions | Private Attributes | List of all members
multi_robot_router::SegmentExpander Class Reference

#include <segment_expander.h>

Classes

struct  greaterSegmentWrapper
 

Public Types

enum  CollisionResolverType { CollisionResolverType::none, CollisionResolverType::backtracking, CollisionResolverType::avoidance }
 

Public Member Functions

bool calculatePotentials (const RouteCoordinatorWrapper *_p, Vertex &_start, Vertex &_end, const uint32_t _maxIterations, const uint32_t _radius)
 assigns all Vertices in the Search graph with a potential according to the distance to the start More...
 
CollisionResolverType getCollisionResolver () const
 gets the currently used collision resolver More...
 
const std::vector< uint32_t > & getRobotCollisions () const
 returns the found robotCollisions while planning More...
 
void reset ()
 resets the session More...
 
 SegmentExpander (const CollisionResolverType _cRes)
 constructor More...
 
void setCollisionResolver (const CollisionResolverType cRes)
 sets the desired collision resolver More...
 
void setSpeed (const float &_speed)
 Sets the multiplier to reduce a robots speed (pCalc...) More...
 

Private Member Functions

void addExpansoionCandidate (Vertex &_current, Vertex &_next, Vertex &_end)
 
void addStartExpansionCandidate (Vertex &_start, Vertex &_current, Vertex &_next, Vertex &_end)
 
template<class T , class S , class C >
void clearpq (std::priority_queue< T, S, C > &q)
 
bool containsVertex (const Vertex &_v, const std::vector< std::reference_wrapper< Vertex >> &_list) const
 
VertexexpandVoronoi (Vertex &_start, Vertex &_end, const uint32_t _cycles)
 
void resolveStartCollision (Vertex &_start, Vertex &_end)
 

Private Attributes

AvoidanceResolution avr_
 
BacktrackingResolution btr_
 
CollisionResolutioncollision_resolution_
 
std::vector< uint32_t > collisions_robots_
 
CollisionResolverType crType_
 
uint32_t diameter_
 
EmptyResolution er_
 
Heuristic hx_
 
uint32_t neutral_cost_ = 1
 
PotentialCalculator pCalc_
 
const RouteCoordinatorWrapperroute_querry_
 
std::priority_queue< Vertex *, std::vector< Vertex * >, greaterSegmentWrapperseg_queue_
 
std::vector< std::unique_ptr< Vertex > > startSegments_
 

Detailed Description

Definition at line 45 of file segment_expander.h.

Member Enumeration Documentation

Enumerator
none 
backtracking 
avoidance 

Definition at line 48 of file segment_expander.h.

Constructor & Destructor Documentation

multi_robot_router::SegmentExpander::SegmentExpander ( const CollisionResolverType  _cRes)

constructor

Parameters
_hthe heuristic used (A-Star, Dijkstra, ...)
_pCalcthe used Potential Calculator for the expander
_cResthe used collision resolution strategy

Definition at line 36 of file segment_expander.cpp.

Member Function Documentation

void multi_robot_router::SegmentExpander::addExpansoionCandidate ( Vertex _current,
Vertex _next,
Vertex _end 
)
private

Definition at line 95 of file segment_expander.cpp.

void multi_robot_router::SegmentExpander::addStartExpansionCandidate ( Vertex _start,
Vertex _current,
Vertex _next,
Vertex _end 
)
private

Definition at line 69 of file segment_expander.cpp.

bool multi_robot_router::SegmentExpander::calculatePotentials ( const RouteCoordinatorWrapper _p,
Vertex _start,
Vertex _end,
const uint32_t  _maxIterations,
const uint32_t  _radius 
)

assigns all Vertices in the Search graph with a potential according to the distance to the start

Parameters
_pthe route coordinator to coordinate the route with other robots
_startthe start Vertex
_endthe end Vertex
Returns
if the goal was found

Definition at line 144 of file segment_expander.cpp.

template<class T , class S , class C >
void multi_robot_router::SegmentExpander::clearpq ( std::priority_queue< T, S, C > &  q)
inlineprivate

Definition at line 92 of file segment_expander.h.

bool multi_robot_router::SegmentExpander::containsVertex ( const Vertex _v,
const std::vector< std::reference_wrapper< Vertex >> &  _list 
) const
private

Definition at line 228 of file segment_expander.cpp.

Vertex * multi_robot_router::SegmentExpander::expandVoronoi ( Vertex _start,
Vertex _end,
const uint32_t  _cycles 
)
private

Definition at line 244 of file segment_expander.cpp.

SegmentExpander::CollisionResolverType multi_robot_router::SegmentExpander::getCollisionResolver ( ) const

gets the currently used collision resolver

Definition at line 58 of file segment_expander.cpp.

const std::vector< uint32_t > & multi_robot_router::SegmentExpander::getRobotCollisions ( ) const

returns the found robotCollisions while planning

Definition at line 298 of file segment_expander.cpp.

void multi_robot_router::SegmentExpander::reset ( )

resets the session

Definition at line 63 of file segment_expander.cpp.

void multi_robot_router::SegmentExpander::resolveStartCollision ( Vertex _start,
Vertex _end 
)
private

Definition at line 164 of file segment_expander.cpp.

void multi_robot_router::SegmentExpander::setCollisionResolver ( const CollisionResolverType  cRes)

sets the desired collision resolver

Definition at line 41 of file segment_expander.cpp.

void multi_robot_router::SegmentExpander::setSpeed ( const float &  _speed)

Sets the multiplier to reduce a robots speed (pCalc...)

Definition at line 239 of file segment_expander.cpp.

Member Data Documentation

AvoidanceResolution multi_robot_router::SegmentExpander::avr_
private

Definition at line 123 of file segment_expander.h.

BacktrackingResolution multi_robot_router::SegmentExpander::btr_
private

Definition at line 124 of file segment_expander.h.

CollisionResolution* multi_robot_router::SegmentExpander::collision_resolution_
private

Definition at line 122 of file segment_expander.h.

std::vector<uint32_t> multi_robot_router::SegmentExpander::collisions_robots_
private

Definition at line 128 of file segment_expander.h.

CollisionResolverType multi_robot_router::SegmentExpander::crType_
private

Definition at line 130 of file segment_expander.h.

uint32_t multi_robot_router::SegmentExpander::diameter_
private

Definition at line 118 of file segment_expander.h.

EmptyResolution multi_robot_router::SegmentExpander::er_
private

Definition at line 125 of file segment_expander.h.

Heuristic multi_robot_router::SegmentExpander::hx_
private

Definition at line 120 of file segment_expander.h.

uint32_t multi_robot_router::SegmentExpander::neutral_cost_ = 1
private

Definition at line 117 of file segment_expander.h.

PotentialCalculator multi_robot_router::SegmentExpander::pCalc_
private

Definition at line 121 of file segment_expander.h.

const RouteCoordinatorWrapper* multi_robot_router::SegmentExpander::route_querry_
private

Definition at line 127 of file segment_expander.h.

std::priority_queue<Vertex *, std::vector<Vertex *>, greaterSegmentWrapper> multi_robot_router::SegmentExpander::seg_queue_
private

Definition at line 116 of file segment_expander.h.

std::vector<std::unique_ptr<Vertex> > multi_robot_router::SegmentExpander::startSegments_
private

Definition at line 129 of file segment_expander.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