-
Raphael Memmesheimer authored
This reverts commit 38523a92.
Raphael Memmesheimer authoredThis reverts commit 38523a92.
Explorer.h 12.80 KiB
#ifndef EXPLORER_H
#define EXPLORER_H
#include <vector>
#include <geometry_msgs/Pose.h>
#include "GridMap.h"
#include "tools/tools.h"
namespace ExplorerConstants
{
static int8_t UNKNOWN;
static const int8_t NOT_SEEN_YET = -1;
static const double MAX_DISTANCE = DBL_MAX;
static const double MAX_COST = DBL_MAX;
static const int OBSTACLE = INT_MAX;
}
/**
* @class Explorer
* @author Malte Knauf, Stephan Wirth, David Gossow (RX)
* @brief Path planning & exploration class
*
* Usage:
*
* - Call setOccupancyMap() to set the base map for path finding.
* - Set a start point by calling setStart()
*
* - For path planning:
* +Choose a target by calling setTarget()
* +To correct a target to the nearest approachable position,
* call getNearestAccessibleTarget
* +Call getPathTransformPath()
*
* -For exploration:
* +Call resetExploration()
* +Call getExplorationTransformPath()
* +The calculated target is the last element in the returned path
*
* - Call sampleWaypointsFromPath() to extract waypoints from a calculated path
*
* This class uses a couple of "maps" for computation and storing data:
*
* - m_OccupancyMap stores the occupancy probabilities in double values. A value of 100 means
* totally occupied, 0 totally free.
* - m_ObstacleDistanceMap stores in each cell the distance (one unit = one cell) to the nearest obstacle.
* This map is computed by an eucledian distance transformation from m_OccupancyMap.
* - m_FrontierMap is a bool map which has 1 in frontier cells and 0 in all others. A frontier
* is defined as a free cell that has one of its four direct neighbours in unknown space and is "safe" for
* the robot (m_ObstacleDistanceMap is used for that).
* - m_DrivingDistanceMap is a double map that stores for each cell the distance to m_Start. It is computed
* by a flood-fill (seed-fill) algorithm. The values are therefor only an approximation and not exact.
* m_DrivingDistanceMap is used to search the nearest frontier when requesting an auto target.
* - m_TargetMap is a double map that stores for each cell the distance to m_Target. It is computed
* like m_DrivingDistanceMap. This map is used as heuristic for the A*-Pathfinding algorithm.
* - m_NavigationMap is used to mark the cells that are touched by the A*-Pathfinding algorithm.
*
*
* The coordinate system and units that are used in this class are based on map cells.
* @see GridMap
*
*/
class Explorer
{
public:
/**
* @brief Default constructor.
* @param minAllowedObstacleDistance,maxAllowedObstacleDistance Range of allowed distances to next obstacle [Pixels]