|
UAV Coverage Path Planner
|
Utility for computational geometry. More...
#include <cgutil.hpp>#include <array>#include <string>#include <unordered_map>#include <boost/range/adaptor/indexed.hpp>#include <boost/range/adaptor/reversed.hpp>#include <std_msgs/Float64.h>#include <geometry_msgs/Point32.h>#include <geometry_msgs/Polygon.h>#include "cpp_uav/Torres16.h"

Go to the source code of this file.
Classes | |
| struct | Direction |
| Storage for line sweep direction. More... | |
Functions | |
| bool | isClockWise (const PointVector &path) |
| Checks if given path is clockwise (the first turn made to the left) or not. More... | |
| Direction | identifyOptimalSweepDir (const PointVector &polygon) |
| Calculates line sweep direction for given polygon. More... | |
| PointVector | reshapePath (const PointVector &path, double padding) |
| Reshape given path. More... | |
| bool | computeConvexCoverage (const PointVector &polygon, double footprintWidth, double horizontalOverwrap, const Direction &sweepDirection, PointVector &path) |
| Compute coverage path for convex polygon. More... | |
| bool | computeConvexCoverage (const PointVector &polygon, double footprintWidth, double horizontalOverwrap, PointVector &path) |
| Compute coverage path for convex polygon. More... | |
| double | calculatePathLength (const PointVector &path) |
| Calculates length of path. More... | |
| PointVector | computeCCWPath (PointVector path) |
| Return counter clock wise-ed path of given path. More... | |
| PointVector | computeOppositePath (const PointVector &path) |
| Return opposite path of given path. More... | |
| PointVector | identifyOptimalAlternative (const PointVector &polygon, const PointVector &path, const geometry_msgs::Point &start, const geometry_msgs::Point &end) |
| Identify optimal path from 4 coverage alternatives. More... | |
| PointVector | identifyOptimalAlternative (const PointVector &polygon, const PointVector &path, const geometry_msgs::Point &start) |
| Identify optimal path from 4 coverage alternatives. More... | |
| bool | findSecondOptimalPath (const PointVector &polygon, double footprintWidth, double horizontalOverwrap, PointVector &path) |
| Find second optimal path. More... | |
| bool | isAdjacent (const PointVector &polygon1, const PointVector &polygon2) |
| Check if given two polygons are adjacent. More... | |
| PointVector | computeMultiplePolygonCoverage (std::vector< PointVector > subPolygons, double footprintWidth, double horizontalOverwrap, int adjacencyCriteria=1) |
| Compute coverage path for multiple convex polygons. More... | |
Utility for computational geometry.
Header file for torres_etal_2016.cpp.
Definition in file torres_etal_2016.hpp.
| double calculatePathLength | ( | const PointVector & | path | ) |
Calculates length of path.
| path |
Definition at line 380 of file torres_etal_2016.hpp.
| PointVector computeCCWPath | ( | PointVector | path | ) |
Return counter clock wise-ed path of given path.
| path | Clockwise path |
Definition at line 400 of file torres_etal_2016.hpp.
| bool computeConvexCoverage | ( | const PointVector & | polygon, |
| double | footprintWidth, | ||
| double | horizontalOverwrap, | ||
| const Direction & | sweepDirection, | ||
| PointVector & | path | ||
| ) |
Compute coverage path for convex polygon.
| polygon | Coverage path is calculated on this region |
| footprintWidth | Width of the area taken by one sweep |
| horizontalOverwrap | Horizontal overwrap of each sweep |
| sweepDirection | |
| path | Path of coverage path |
Definition at line 260 of file torres_etal_2016.hpp.
| bool computeConvexCoverage | ( | const PointVector & | polygon, |
| double | footprintWidth, | ||
| double | horizontalOverwrap, | ||
| PointVector & | path | ||
| ) |
Compute coverage path for convex polygon.
| polygon | Coverage path is calculated on this region |
| footprintWidth | Width of the area taken by one sweep |
| horizontalOverwrap | Horizontal overwrap of each sweep |
| path | Path of coverage path |
Definition at line 368 of file torres_etal_2016.hpp.
| PointVector computeMultiplePolygonCoverage | ( | std::vector< PointVector > | subPolygons, |
| double | footprintWidth, | ||
| double | horizontalOverwrap, | ||
| int | adjacencyCriteria = 1 |
||
| ) |
Compute coverage path for multiple convex polygons.
| subPolygons | |
| footprintWidth | |
| horizontalOverwrap | |
| adjacencyCriteria | Ignore paths which have less adjacent polygons than this number |
See section 6.2 of torres et al. 2016 for the detail
Definition at line 634 of file torres_etal_2016.hpp.
| PointVector computeOppositePath | ( | const PointVector & | path | ) |
Return opposite path of given path.
| path |
Definition at line 425 of file torres_etal_2016.hpp.
| bool findSecondOptimalPath | ( | const PointVector & | polygon, |
| double | footprintWidth, | ||
| double | horizontalOverwrap, | ||
| PointVector & | path | ||
| ) |
Find second optimal path.
| polygon | |
| footprintWidth | |
| horizontalOverwrap | |
| path |
Definition at line 547 of file torres_etal_2016.hpp.
| PointVector identifyOptimalAlternative | ( | const PointVector & | polygon, |
| const PointVector & | path, | ||
| const geometry_msgs::Point & | start, | ||
| const geometry_msgs::Point & | end | ||
| ) |
Identify optimal path from 4 coverage alternatives.
| polygon | |
| path | |
| start | Start point |
| end | End point |
The naming of the following variable follows torres et al. 2016
Definition at line 447 of file torres_etal_2016.hpp.
| PointVector identifyOptimalAlternative | ( | const PointVector & | polygon, |
| const PointVector & | path, | ||
| const geometry_msgs::Point & | start | ||
| ) |
Identify optimal path from 4 coverage alternatives.
| polygon | |
| path | |
| start | Start point |
The naming of the following variable follows torres et al. 2016
Definition at line 533 of file torres_etal_2016.hpp.
| Direction identifyOptimalSweepDir | ( | const PointVector & | polygon | ) |
Calculates line sweep direction for given polygon.
| polygon | Line sweep direction is calculated on this region |
Definition at line 65 of file torres_etal_2016.hpp.
| bool isAdjacent | ( | const PointVector & | polygon1, |
| const PointVector & | polygon2 | ||
| ) |
Check if given two polygons are adjacent.
| polygon1 | |
| polygon2 |
Definition at line 609 of file torres_etal_2016.hpp.
|
inline |
Checks if given path is clockwise (the first turn made to the left) or not.
| path |
the definition of "clockwise" is based on Fig.8 in Torres et al. 2016
Definition at line 55 of file torres_etal_2016.hpp.
| PointVector reshapePath | ( | const PointVector & | path, |
| double | padding | ||
| ) |
Reshape given path.
| path | The sweep lines of path should be horizontal about x axis |
| padding |
Reshape given path so that generated path becomes the sequence of "C" shapes and add padding
Definition at line 134 of file torres_etal_2016.hpp.
1.8.11