#include <point_expander.h>
|
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...
|
|
|
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) |
|
Definition at line 43 of file point_expander.h.
void multi_robot_router::PointExpander::addPotentialExpansionCandidate |
( |
PointExpander::Index |
_current, |
|
|
int32_t |
_next_x, |
|
|
int32_t |
_next_y, |
|
|
float * |
_potential, |
|
|
uint32_t |
_distToObstacle |
|
) |
| |
|
private |
template<class T , class S , class C >
void multi_robot_router::PointExpander::clearpq |
( |
std::priority_queue< T, S, C > & |
q | ) |
|
|
inlineprivate |
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 |
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
-
_start | the start point on the map |
_cycles | the maximum number of cycles used to compute a goal |
_potential | the potential map to assign the weights |
_goals | a map containing goal points mapped to an index |
_optimizationSteps | the _optimizationSteps' goal node is taken to optimize paths |
_foundPoint | the found goal point |
_segIdx | the found index |
_radius | the 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
-
vec | the 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
-
_map | a 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 |
cv::Mat multi_robot_router::PointExpander::distance_field_ |
|
private |
float multi_robot_router::PointExpander::neutral_cost_ = 1 |
|
private |
int multi_robot_router::PointExpander::ns_ |
|
private |
int multi_robot_router::PointExpander::nx_ |
|
private |
int multi_robot_router::PointExpander::ny_ |
|
private |
std::priority_queue<Index, std::vector<Index>, greater1> multi_robot_router::PointExpander::queue_ |
|
private |
The documentation for this class was generated from the following files: