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

#include <point_expander.h>

Classes

struct  greater1
 
class  Index
 

Public Member Functions

bool findGoalOnMap (const Eigen::Vector2d &_start, const uint32_t &_cycles, float *_potential, const std::map< uint32_t, Eigen::Vector2d > &_goals, const uint32_t &_optimizationSteps, Eigen::Vector2d &_foundPoint, int32_t &_segIdx, const uint32_t &_radius)
 searches the first occurence of a point in the goals_ list and returns the index More...
 
float getDistanceToObstacle (const Eigen::Vector2d &vec)
 returns the distance to the closest obstacle for a point More...
 
void initialize (const cv::Mat &_map)
 initializes the point expander with a distance map More...
 

Private Member Functions

void addPotentialExpansionCandidate (Index _current, int32_t _next_x, int32_t _next_y, float *_potential, uint32_t _distToObstacle)
 
template<class T , class S , class C >
void clearpq (std::priority_queue< T, S, C > &q)
 
Index findGoal (const Index &_start, const uint32_t &_cycles, float *_potential, const std::map< uint32_t, Index > &_goals, const uint32_t &_optimizationSteps, int32_t &segIdx, const uint32_t &_radius)
 
bool isGoal (Index _p, const std::map< uint32_t, Index > &_goals, int32_t &segIdx)
 

Private Attributes

cv::Mat distance_field_
 
float neutral_cost_ = 1
 
int ns_
 
int nx_
 
int ny_
 
std::priority_queue< Index, std::vector< Index >, greater1queue_
 

Detailed Description

Definition at line 43 of file point_expander.h.

Member Function Documentation

void multi_robot_router::PointExpander::addPotentialExpansionCandidate ( PointExpander::Index  _current,
int32_t  _next_x,
int32_t  _next_y,
float *  _potential,
uint32_t  _distToObstacle 
)
private

Definition at line 44 of file point_expander.cpp.

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

Definition at line 73 of file point_expander.h.

PointExpander::Index multi_robot_router::PointExpander::findGoal ( const Index _start,
const uint32_t &  _cycles,
float *  _potential,
const std::map< uint32_t, Index > &  _goals,
const uint32_t &  _optimizationSteps,
int32_t &  segIdx,
const uint32_t &  _radius 
)
private

Definition at line 69 of file point_expander.cpp.

bool multi_robot_router::PointExpander::findGoalOnMap ( const Eigen::Vector2d &  _start,
const uint32_t &  _cycles,
float *  _potential,
const std::map< uint32_t, Eigen::Vector2d > &  _goals,
const uint32_t &  _optimizationSteps,
Eigen::Vector2d &  _foundPoint,
int32_t &  _segIdx,
const uint32_t &  _radius 
)

searches the first occurence of a point in the goals_ list and returns the index

used to find the closes segment to the start point. The goals are usually the centerpoints of the considered segments with the segment id. If a path is allready found the expander can be started again to find the nth furthest segment to optimize the path.

Parameters
_startthe start point on the map
_cyclesthe maximum number of cycles used to compute a goal
_potentialthe potential map to assign the weights
_goalsa map containing goal points mapped to an index
_optimizationStepsthe _optimizationSteps' goal node is taken to optimize paths
_foundPointthe found goal point
_segIdxthe found index
_radiusthe robot _radius
Returns
true if a point was found

Definition at line 148 of file point_expander.cpp.

float multi_robot_router::PointExpander::getDistanceToObstacle ( const Eigen::Vector2d &  vec)

returns the distance to the closest obstacle for a point

Parameters
vecthe point which is used to calculate the distance to the closest obstacle

Definition at line 173 of file point_expander.cpp.

void multi_robot_router::PointExpander::initialize ( const cv::Mat &  _map)

initializes the point expander with a distance map

Parameters
_mapa cv::Mat containing a distance_transformed map (e.g. opencv disttransform)

Definition at line 35 of file point_expander.cpp.

bool multi_robot_router::PointExpander::isGoal ( Index  _p,
const std::map< uint32_t, Index > &  _goals,
int32_t &  segIdx 
)
private

Definition at line 132 of file point_expander.cpp.

Member Data Documentation

cv::Mat multi_robot_router::PointExpander::distance_field_
private

Definition at line 145 of file point_expander.h.

float multi_robot_router::PointExpander::neutral_cost_ = 1
private

Definition at line 146 of file point_expander.h.

int multi_robot_router::PointExpander::ns_
private

Definition at line 140 of file point_expander.h.

int multi_robot_router::PointExpander::nx_
private

Definition at line 140 of file point_expander.h.

int multi_robot_router::PointExpander::ny_
private

Definition at line 140 of file point_expander.h.

std::priority_queue<Index, std::vector<Index>, greater1> multi_robot_router::PointExpander::queue_
private

Definition at line 139 of file point_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