UAV Coverage Path Planner
Classes | Functions
torres_etal_2016.hpp File Reference

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"
Include dependency graph for torres_etal_2016.hpp:
This graph shows which files directly or indirectly include this file:

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

Detailed Description

Utility for computational geometry.

Header file for torres_etal_2016.cpp.

Author
Takaki Ueno

Definition in file torres_etal_2016.hpp.

Function Documentation

double calculatePathLength ( const PointVector path)

Calculates length of path.

Parameters
path
Returns
double Length of path

Definition at line 380 of file torres_etal_2016.hpp.

PointVector computeCCWPath ( PointVector  path)

Return counter clock wise-ed path of given path.

Parameters
pathClockwise path
Returns
PointVector Counter clock wise version of given 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.

Parameters
polygonCoverage path is calculated on this region
footprintWidthWidth of the area taken by one sweep
horizontalOverwrapHorizontal overwrap of each sweep
sweepDirection
pathPath of coverage path
Returns
bool True if path does not intersect with polygon

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.

Parameters
polygonCoverage path is calculated on this region
footprintWidthWidth of the area taken by one sweep
horizontalOverwrapHorizontal overwrap of each sweep
pathPath of coverage path
Returns
bool True if path does not intersect with polygon

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.

Parameters
subPolygons
footprintWidth
horizontalOverwrap
adjacencyCriteriaIgnore paths which have less adjacent polygons than this number
Returns
PointVector Computed Path

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.

Parameters
path
Returns
PointVector Path with points of reversed order of given 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.

Parameters
polygon
footprintWidth
horizontalOverwrap
path
Returns
bool True if second optimal path exists

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.

Parameters
polygon
path
startStart point
endEnd point
Returns
PointVector Optimal path that minimizes the length of path

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.

Parameters
polygon
path
startStart point
Returns
PointVector Optimal path that minimizes the length of path

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.

Parameters
polygonLine sweep direction is calculated on this region
Returns
direction Struct containing edge and vertex

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.

Parameters
polygon1
polygon2
Returns
True if given two polygons are adjacent

Definition at line 609 of file torres_etal_2016.hpp.

bool isClockWise ( const PointVector path)
inline

Checks if given path is clockwise (the first turn made to the left) or not.

Parameters
path
Returns
bool True if path is clockwise

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.

Parameters
pathThe sweep lines of path should be horizontal about x axis
padding
Returns
PointVector

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.