aboutsummaryrefslogtreecommitdiff
path: root/src/pathfinder.cpp
diff options
context:
space:
mode:
Diffstat (limited to 'src/pathfinder.cpp')
-rw-r--r--src/pathfinder.cpp720
1 files changed, 349 insertions, 371 deletions
diff --git a/src/pathfinder.cpp b/src/pathfinder.cpp
index 3f0b98c10..ec418c45d 100644
--- a/src/pathfinder.cpp
+++ b/src/pathfinder.cpp
@@ -30,13 +30,13 @@ with this program; if not, write to the Free Software Foundation, Inc.,
//#define PATHFINDER_CALC_TIME
#ifdef PATHFINDER_DEBUG
- #include <string>
+#include <string>
#endif
#ifdef PATHFINDER_DEBUG
- #include <iomanip>
+#include <iomanip>
#endif
#ifdef PATHFINDER_CALC_TIME
- #include <sys/time.h>
+#include <sys/time.h>
#endif
/******************************************************************************/
@@ -46,15 +46,15 @@ with this program; if not, write to the Free Software Foundation, Inc.,
#define LVL "(" << level << ")" <<
#ifdef PATHFINDER_DEBUG
-#define DEBUG_OUT(a) std::cout << a
-#define INFO_TARGET std::cout
-#define VERBOSE_TARGET std::cout
-#define ERROR_TARGET std::cout
+#define DEBUG_OUT(a) std::cout << a
+#define INFO_TARGET std::cout
+#define VERBOSE_TARGET std::cout
+#define ERROR_TARGET std::cout
#else
-#define DEBUG_OUT(a) while(0)
-#define INFO_TARGET infostream << "Pathfinder: "
-#define VERBOSE_TARGET verbosestream << "Pathfinder: "
-#define ERROR_TARGET warningstream << "Pathfinder: "
+#define DEBUG_OUT(a) while (0)
+#define INFO_TARGET infostream << "Pathfinder: "
+#define VERBOSE_TARGET verbosestream << "Pathfinder: "
+#define ERROR_TARGET warningstream << "Pathfinder: "
#endif
#define PATHFINDER_MAX_WAYPOINTS 700
@@ -63,11 +63,10 @@ with this program; if not, write to the Free Software Foundation, Inc.,
/* Class definitions */
/******************************************************************************/
-
/** representation of cost in specific direction */
-class PathCost {
+class PathCost
+{
public:
-
/** default constructor */
PathCost() = default;
@@ -75,18 +74,17 @@ public:
PathCost(const PathCost &b);
/** assignment operator */
- PathCost &operator= (const PathCost &b);
-
- bool valid = false; /**< movement is possible */
- int value = 0; /**< cost of movement */
- int y_change = 0; /**< change of y position of movement */
- bool updated = false; /**< this cost has ben calculated */
+ PathCost &operator=(const PathCost &b);
+ bool valid = false; /**< movement is possible */
+ int value = 0; /**< cost of movement */
+ int y_change = 0; /**< change of y position of movement */
+ bool updated = false; /**< this cost has ben calculated */
};
-
/** representation of a mapnode to be used for pathfinding */
-class PathGridnode {
+class PathGridnode
+{
public:
/** default constructor */
@@ -99,7 +97,7 @@ public:
* assignment operator
* @param b node to copy
*/
- PathGridnode &operator= (const PathGridnode &b);
+ PathGridnode &operator=(const PathGridnode &b);
/**
* read cost in a specific direction
@@ -112,37 +110,38 @@ public:
* @param dir direction to set cost for
* @cost cost to set
*/
- void setCost(v3s16 dir, const PathCost &cost);
-
- bool valid = false; /**< node is on surface */
- bool target = false; /**< node is target position */
- bool source = false; /**< node is stating position */
- int totalcost = -1; /**< cost to move here from starting point */
- int estimated_cost = -1; /**< totalcost + heuristic cost to end */
- v3s16 sourcedir; /**< origin of movement for current cost */
- v3s16 pos; /**< real position of node */
- PathCost directions[4]; /**< cost in different directions */
- bool is_closed = false; /**< for A* search: if true, is in closed list */
- bool is_open = false; /**< for A* search: if true, is in open list */
+ void setCost(v3s16 dir, const PathCost &cost);
+
+ bool valid = false; /**< node is on surface */
+ bool target = false; /**< node is target position */
+ bool source = false; /**< node is stating position */
+ int totalcost = -1; /**< cost to move here from starting point */
+ int estimated_cost = -1; /**< totalcost + heuristic cost to end */
+ v3s16 sourcedir; /**< origin of movement for current cost */
+ v3s16 pos; /**< real position of node */
+ PathCost directions[4]; /**< cost in different directions */
+ bool is_closed = false; /**< for A* search: if true, is in closed list */
+ bool is_open = false; /**< for A* search: if true, is in open list */
/* debug values */
- bool is_element = false; /**< node is element of path detected */
- char type = 'u'; /**< Type of pathfinding node.
- * u = unknown
- * i = invalid
- * s = surface (walkable node)
- * - = non-walkable node (e.g. air) above surface
- * g = other non-walkable node
- */
+ bool is_element = false; /**< node is element of path detected */
+ char type = 'u'; /**< Type of pathfinding node.
+ * u = unknown
+ * i = invalid
+ * s = surface (walkable node)
+ * - = non-walkable node (e.g. air) above surface
+ * g = other non-walkable node
+ */
};
class Pathfinder;
class PathfinderCompareHeuristic;
/** Abstract class to manage the map data */
-class GridNodeContainer {
+class GridNodeContainer
+{
public:
- virtual PathGridnode &access(v3s16 p)=0;
+ virtual PathGridnode &access(v3s16 p) = 0;
virtual ~GridNodeContainer() = default;
protected:
@@ -151,12 +150,14 @@ protected:
void initNode(v3s16 ipos, PathGridnode *p_node);
};
-class ArrayGridNodeContainer : public GridNodeContainer {
+class ArrayGridNodeContainer : public GridNodeContainer
+{
public:
virtual ~ArrayGridNodeContainer() = default;
ArrayGridNodeContainer(Pathfinder *pathf, v3s16 dimensions);
virtual PathGridnode &access(v3s16 p);
+
private:
v3s16 m_dimensions;
@@ -165,18 +166,21 @@ private:
std::vector<PathGridnode> m_nodes_array;
};
-class MapGridNodeContainer : public GridNodeContainer {
+class MapGridNodeContainer : public GridNodeContainer
+{
public:
virtual ~MapGridNodeContainer() = default;
MapGridNodeContainer(Pathfinder *pathf);
virtual PathGridnode &access(v3s16 p);
+
private:
std::map<v3s16, PathGridnode> m_nodes;
};
/** class doing pathfinding */
-class Pathfinder {
+class Pathfinder
+{
public:
Pathfinder() = delete;
@@ -194,12 +198,9 @@ public:
* @param max_drop maximum number of blocks a path may drop
* @param algo Algorithm to use for finding a path
*/
- std::vector<v3s16> getPath(v3s16 source,
- v3s16 destination,
- unsigned int searchdistance,
- unsigned int max_jump,
- unsigned int max_drop,
- PathAlgorithm algo);
+ std::vector<v3s16> getPath(v3s16 source, v3s16 destination,
+ unsigned int searchdistance, unsigned int max_jump,
+ unsigned int max_drop, PathAlgorithm algo);
private:
/* helper functions */
@@ -209,14 +210,14 @@ private:
* @param ipos a index position
* @return map position
*/
- v3s16 getRealPos(v3s16 ipos);
+ v3s16 getRealPos(v3s16 ipos);
/**
* transform mappos to index pos
* @param pos a real pos
* @return index position
*/
- v3s16 getIndexPos(v3s16 pos);
+ v3s16 getIndexPos(v3s16 pos);
/**
* get gridnode at a specific index position
@@ -236,15 +237,14 @@ private:
* @param pos 3D position
* @return pos *-1
*/
- v3s16 invert(v3s16 pos);
+ v3s16 invert(v3s16 pos);
/**
* check if a index is within current search area
* @param index position to validate
* @return true/false
*/
- bool isValidIndex(v3s16 index);
-
+ bool isValidIndex(v3s16 index);
/* algorithm functions */
@@ -253,7 +253,7 @@ private:
* @param pos position to calc distance
* @return integer distance
*/
- int getXZManhattanDist(v3s16 pos);
+ int getXZManhattanDist(v3s16 pos);
/**
* calculate cost of movement
@@ -261,7 +261,7 @@ private:
* @param dir direction to move to
* @return cost information
*/
- PathCost calcCost(v3s16 pos, v3s16 dir);
+ PathCost calcCost(v3s16 pos, v3s16 dir);
/**
* recursive update whole search areas total cost information
@@ -271,7 +271,7 @@ private:
* @param level current recursion depth
* @return true/false path to destination has been found
*/
- bool updateAllCosts(v3s16 ipos, v3s16 srcdir, int current_cost, int level);
+ bool updateAllCosts(v3s16 ipos, v3s16 srcdir, int current_cost, int level);
/**
* try to find a path to destination using a heuristic function
@@ -280,7 +280,7 @@ private:
* @param idestination end position (index pos)
* @return true/false path to destination has been found
*/
- bool updateCostHeuristic(v3s16 isource, v3s16 idestination);
+ bool updateCostHeuristic(v3s16 isource, v3s16 idestination);
/**
* build a vector containing all nodes from destination to source;
@@ -289,7 +289,7 @@ private:
* @param ipos initial pos to check (index pos)
* @return true/false path has been fully built
*/
- bool buildPath(std::vector<v3s16> &path, v3s16 ipos);
+ bool buildPath(std::vector<v3s16> &path, v3s16 ipos);
/**
* go downwards from a position until some barrier
@@ -299,23 +299,22 @@ private:
* @return new position after movement; if too far down,
* pos is returned
*/
- v3s16 walkDownwards(v3s16 pos, unsigned int max_down);
+ v3s16 walkDownwards(v3s16 pos, unsigned int max_down);
/* variables */
- int m_max_index_x = 0; /**< max index of search area in x direction */
- int m_max_index_y = 0; /**< max index of search area in y direction */
- int m_max_index_z = 0; /**< max index of search area in z direction */
-
+ int m_max_index_x = 0; /**< max index of search area in x direction */
+ int m_max_index_y = 0; /**< max index of search area in y direction */
+ int m_max_index_z = 0; /**< max index of search area in z direction */
- int m_searchdistance = 0; /**< max distance to search in each direction */
- int m_maxdrop = 0; /**< maximum number of blocks a path may drop */
- int m_maxjump = 0; /**< maximum number of blocks a path may jump */
- int m_min_target_distance = 0; /**< current smalest path to target */
+ int m_searchdistance = 0; /**< max distance to search in each direction */
+ int m_maxdrop = 0; /**< maximum number of blocks a path may drop */
+ int m_maxjump = 0; /**< maximum number of blocks a path may jump */
+ int m_min_target_distance = 0; /**< current smalest path to target */
- bool m_prefetch = true; /**< prefetch cost data */
+ bool m_prefetch = true; /**< prefetch cost data */
- v3s16 m_start; /**< source position */
- v3s16 m_destination; /**< destination position */
+ v3s16 m_start; /**< source position */
+ v3s16 m_destination; /**< destination position */
core::aabbox3d<s16> m_limits; /**< position limits in real map coordinates */
@@ -384,72 +383,62 @@ private:
*/
class PathfinderCompareHeuristic
{
- private:
- Pathfinder *myPathfinder;
- public:
- PathfinderCompareHeuristic(Pathfinder *pf)
- {
- myPathfinder = pf;
- }
- bool operator() (v3s16 pos1, v3s16 pos2) {
- v3s16 ipos1 = myPathfinder->getIndexPos(pos1);
- v3s16 ipos2 = myPathfinder->getIndexPos(pos2);
- PathGridnode &g_pos1 = myPathfinder->getIndexElement(ipos1);
- PathGridnode &g_pos2 = myPathfinder->getIndexElement(ipos2);
- if (!g_pos1.valid)
- return false;
- if (!g_pos2.valid)
- return false;
- return g_pos1.estimated_cost > g_pos2.estimated_cost;
- }
+private:
+ Pathfinder *myPathfinder;
+
+public:
+ PathfinderCompareHeuristic(Pathfinder *pf) { myPathfinder = pf; }
+ bool operator()(v3s16 pos1, v3s16 pos2)
+ {
+ v3s16 ipos1 = myPathfinder->getIndexPos(pos1);
+ v3s16 ipos2 = myPathfinder->getIndexPos(pos2);
+ PathGridnode &g_pos1 = myPathfinder->getIndexElement(ipos1);
+ PathGridnode &g_pos2 = myPathfinder->getIndexElement(ipos2);
+ if (!g_pos1.valid)
+ return false;
+ if (!g_pos2.valid)
+ return false;
+ return g_pos1.estimated_cost > g_pos2.estimated_cost;
+ }
};
/******************************************************************************/
/* implementation */
/******************************************************************************/
-std::vector<v3s16> get_path(Map* map, const NodeDefManager *ndef,
- v3s16 source,
- v3s16 destination,
- unsigned int searchdistance,
- unsigned int max_jump,
- unsigned int max_drop,
- PathAlgorithm algo)
+std::vector<v3s16> get_path(Map *map, const NodeDefManager *ndef, v3s16 source,
+ v3s16 destination, unsigned int searchdistance, unsigned int max_jump,
+ unsigned int max_drop, PathAlgorithm algo)
{
- return Pathfinder(map, ndef).getPath(source, destination,
- searchdistance, max_jump, max_drop, algo);
+ return Pathfinder(map, ndef).getPath(
+ source, destination, searchdistance, max_jump, max_drop, algo);
}
/******************************************************************************/
PathCost::PathCost(const PathCost &b)
{
- valid = b.valid;
- y_change = b.y_change;
- value = b.value;
- updated = b.updated;
+ valid = b.valid;
+ y_change = b.y_change;
+ value = b.value;
+ updated = b.updated;
}
/******************************************************************************/
-PathCost &PathCost::operator= (const PathCost &b)
+PathCost &PathCost::operator=(const PathCost &b)
{
- valid = b.valid;
- y_change = b.y_change;
- value = b.value;
- updated = b.updated;
+ valid = b.valid;
+ y_change = b.y_change;
+ value = b.value;
+ updated = b.updated;
return *this;
}
/******************************************************************************/
-PathGridnode::PathGridnode(const PathGridnode &b)
-: valid(b.valid),
- target(b.target),
- source(b.source),
- totalcost(b.totalcost),
- sourcedir(b.sourcedir),
- pos(b.pos),
- is_element(b.is_element),
- type(b.type)
+PathGridnode::PathGridnode(const PathGridnode &b) :
+ valid(b.valid), target(b.target), source(b.source),
+ totalcost(b.totalcost), sourcedir(b.sourcedir), pos(b.pos),
+ is_element(b.is_element), type(b.type)
{
directions[DIR_XP] = b.directions[DIR_XP];
@@ -459,16 +448,16 @@ PathGridnode::PathGridnode(const PathGridnode &b)
}
/******************************************************************************/
-PathGridnode &PathGridnode::operator= (const PathGridnode &b)
+PathGridnode &PathGridnode::operator=(const PathGridnode &b)
{
- valid = b.valid;
- target = b.target;
- source = b.source;
+ valid = b.valid;
+ target = b.target;
+ source = b.source;
is_element = b.is_element;
- totalcost = b.totalcost;
- sourcedir = b.sourcedir;
- pos = b.pos;
- type = b.type;
+ totalcost = b.totalcost;
+ sourcedir = b.sourcedir;
+ pos = b.pos;
+ type = b.type;
directions[DIR_XP] = b.directions[DIR_XP];
directions[DIR_XM] = b.directions[DIR_XM];
@@ -522,13 +511,12 @@ void GridNodeContainer::initNode(v3s16 ipos, PathGridnode *p_node)
v3s16 realpos = m_pathf->getRealPos(ipos);
MapNode current = m_pathf->m_map->getNode(realpos);
- MapNode below = m_pathf->m_map->getNode(realpos + v3s16(0, -1, 0));
-
+ MapNode below = m_pathf->m_map->getNode(realpos + v3s16(0, -1, 0));
- if ((current.param0 == CONTENT_IGNORE) ||
- (below.param0 == CONTENT_IGNORE)) {
- DEBUG_OUT("Pathfinder: " << PP(realpos) <<
- " current or below is invalid element" << std::endl);
+ if ((current.param0 == CONTENT_IGNORE) || (below.param0 == CONTENT_IGNORE)) {
+ DEBUG_OUT("Pathfinder: " << PP(realpos)
+ << " current or below is invalid element"
+ << std::endl);
if (current.param0 == CONTENT_IGNORE) {
elem.type = 'i';
DEBUG_OUT(PP(ipos) << ": " << 'i' << std::endl);
@@ -536,36 +524,35 @@ void GridNodeContainer::initNode(v3s16 ipos, PathGridnode *p_node)
return;
}
- //don't add anything if it isn't an air node
+ // don't add anything if it isn't an air node
if (ndef->get(current).walkable || !ndef->get(below).walkable) {
- DEBUG_OUT("Pathfinder: " << PP(realpos)
- << " not on surface" << std::endl);
- if (ndef->get(current).walkable) {
- elem.type = 's';
- DEBUG_OUT(PP(ipos) << ": " << 's' << std::endl);
- } else {
- elem.type = '-';
- DEBUG_OUT(PP(ipos) << ": " << '-' << std::endl);
- }
- return;
+ DEBUG_OUT("Pathfinder: " << PP(realpos) << " not on surface"
+ << std::endl);
+ if (ndef->get(current).walkable) {
+ elem.type = 's';
+ DEBUG_OUT(PP(ipos) << ": " << 's' << std::endl);
+ } else {
+ elem.type = '-';
+ DEBUG_OUT(PP(ipos) << ": " << '-' << std::endl);
+ }
+ return;
}
elem.valid = true;
- elem.pos = realpos;
- elem.type = 'g';
+ elem.pos = realpos;
+ elem.type = 'g';
DEBUG_OUT(PP(ipos) << ": " << 'a' << std::endl);
if (m_pathf->m_prefetch) {
- elem.directions[DIR_XP] = m_pathf->calcCost(realpos, v3s16( 1, 0, 0));
+ elem.directions[DIR_XP] = m_pathf->calcCost(realpos, v3s16(1, 0, 0));
elem.directions[DIR_XM] = m_pathf->calcCost(realpos, v3s16(-1, 0, 0));
- elem.directions[DIR_ZP] = m_pathf->calcCost(realpos, v3s16( 0, 0, 1));
- elem.directions[DIR_ZM] = m_pathf->calcCost(realpos, v3s16( 0, 0,-1));
+ elem.directions[DIR_ZP] = m_pathf->calcCost(realpos, v3s16(0, 0, 1));
+ elem.directions[DIR_ZM] = m_pathf->calcCost(realpos, v3s16(0, 0, -1));
}
}
ArrayGridNodeContainer::ArrayGridNodeContainer(Pathfinder *pathf, v3s16 dimensions) :
- m_x_stride(dimensions.Y * dimensions.Z),
- m_y_stride(dimensions.Z)
+ m_x_stride(dimensions.Y * dimensions.Z), m_y_stride(dimensions.Z)
{
m_pathf = pathf;
@@ -573,7 +560,7 @@ ArrayGridNodeContainer::ArrayGridNodeContainer(Pathfinder *pathf, v3s16 dimensio
INFO_TARGET << "Pathfinder ArrayGridNodeContainer constructor." << std::endl;
for (int x = 0; x < dimensions.X; x++) {
for (int y = 0; y < dimensions.Y; y++) {
- for (int z= 0; z < dimensions.Z; z++) {
+ for (int z = 0; z < dimensions.Z; z++) {
v3s16 ipos(x, y, z);
initNode(ipos, &access(ipos));
}
@@ -602,15 +589,10 @@ PathGridnode &MapGridNodeContainer::access(v3s16 p)
return n;
}
-
-
/******************************************************************************/
-std::vector<v3s16> Pathfinder::getPath(v3s16 source,
- v3s16 destination,
- unsigned int searchdistance,
- unsigned int max_jump,
- unsigned int max_drop,
- PathAlgorithm algo)
+std::vector<v3s16> Pathfinder::getPath(v3s16 source, v3s16 destination,
+ unsigned int searchdistance, unsigned int max_jump, unsigned int max_drop,
+ PathAlgorithm algo)
{
#ifdef PATHFINDER_CALC_TIME
timespec ts;
@@ -618,11 +600,11 @@ std::vector<v3s16> Pathfinder::getPath(v3s16 source,
#endif
std::vector<v3s16> retval;
- //initialization
+ // initialization
m_searchdistance = searchdistance;
m_maxjump = max_jump;
m_maxdrop = max_drop;
- m_start = source;
+ m_start = source;
m_destination = destination;
m_min_target_distance = -1;
m_prefetch = true;
@@ -631,7 +613,7 @@ std::vector<v3s16> Pathfinder::getPath(v3s16 source,
m_prefetch = false;
}
- //calculate boundaries within we're allowed to search
+ // calculate boundaries within we're allowed to search
int min_x = MYMIN(source.X, destination.X);
int max_x = MYMAX(source.X, destination.X);
@@ -667,73 +649,73 @@ std::vector<v3s16> Pathfinder::getPath(v3s16 source,
printYdir();
#endif
- //fail if source or destination is walkable
+ // fail if source or destination is walkable
MapNode node_at_pos = m_map->getNode(destination);
if (m_ndef->get(node_at_pos).walkable) {
- VERBOSE_TARGET << "Destination is walkable. " <<
- "Pos: " << PP(destination) << std::endl;
+ VERBOSE_TARGET << "Destination is walkable. "
+ << "Pos: " << PP(destination) << std::endl;
return retval;
}
node_at_pos = m_map->getNode(source);
if (m_ndef->get(node_at_pos).walkable) {
- VERBOSE_TARGET << "Source is walkable. " <<
- "Pos: " << PP(source) << std::endl;
+ VERBOSE_TARGET << "Source is walkable. "
+ << "Pos: " << PP(source) << std::endl;
return retval;
}
- //If source pos is hovering above air, drop
- //to the first walkable node (up to m_maxdrop).
- //All algorithms expect the source pos to be *directly* above
- //a walkable node.
+ // If source pos is hovering above air, drop
+ // to the first walkable node (up to m_maxdrop).
+ // All algorithms expect the source pos to be *directly* above
+ // a walkable node.
v3s16 true_source = v3s16(source);
source = walkDownwards(source, m_maxdrop);
- //If destination pos is hovering above air, go downwards
- //to the first walkable node (up to m_maxjump).
- //This means a hovering destination pos could be reached
- //by a final upwards jump.
+ // If destination pos is hovering above air, go downwards
+ // to the first walkable node (up to m_maxjump).
+ // This means a hovering destination pos could be reached
+ // by a final upwards jump.
v3s16 true_destination = v3s16(destination);
destination = walkDownwards(destination, m_maxjump);
- //validate and mark start and end pos
+ // validate and mark start and end pos
- v3s16 StartIndex = getIndexPos(source);
- v3s16 EndIndex = getIndexPos(destination);
+ v3s16 StartIndex = getIndexPos(source);
+ v3s16 EndIndex = getIndexPos(destination);
PathGridnode &startpos = getIndexElement(StartIndex);
- PathGridnode &endpos = getIndexElement(EndIndex);
+ PathGridnode &endpos = getIndexElement(EndIndex);
if (!startpos.valid) {
- VERBOSE_TARGET << "Invalid startpos " <<
- "Index: " << PP(StartIndex) <<
- "Realpos: " << PP(getRealPos(StartIndex)) << std::endl;
+ VERBOSE_TARGET << "Invalid startpos "
+ << "Index: " << PP(StartIndex)
+ << "Realpos: " << PP(getRealPos(StartIndex)) << std::endl;
return retval;
}
if (!endpos.valid) {
- VERBOSE_TARGET << "Invalid stoppos " <<
- "Index: " << PP(EndIndex) <<
- "Realpos: " << PP(getRealPos(EndIndex)) << std::endl;
+ VERBOSE_TARGET << "Invalid stoppos "
+ << "Index: " << PP(EndIndex)
+ << "Realpos: " << PP(getRealPos(EndIndex)) << std::endl;
return retval;
}
- endpos.target = true;
- startpos.source = true;
+ endpos.target = true;
+ startpos.source = true;
startpos.totalcost = 0;
bool update_cost_retval = false;
- //calculate node costs
+ // calculate node costs
switch (algo) {
- case PA_DIJKSTRA:
- update_cost_retval = updateAllCosts(StartIndex, v3s16(0, 0, 0), 0, 0);
- break;
- case PA_PLAIN_NP:
- case PA_PLAIN:
- update_cost_retval = updateCostHeuristic(StartIndex, EndIndex);
- break;
- default:
- ERROR_TARGET << "Missing PathAlgorithm" << std::endl;
- break;
+ case PA_DIJKSTRA:
+ update_cost_retval = updateAllCosts(StartIndex, v3s16(0, 0, 0), 0, 0);
+ break;
+ case PA_PLAIN_NP:
+ case PA_PLAIN:
+ update_cost_retval = updateCostHeuristic(StartIndex, EndIndex);
+ break;
+ default:
+ ERROR_TARGET << "Missing PathAlgorithm" << std::endl;
+ break;
}
if (update_cost_retval) {
@@ -743,22 +725,22 @@ std::vector<v3s16> Pathfinder::getPath(v3s16 source,
printPathLen();
#endif
- //find path
+ // find path
std::vector<v3s16> index_path;
buildPath(index_path, EndIndex);
- //Now we have a path of index positions,
- //and it's in reverse.
- //The "true" start or end position might be missing
- //since those have been given special treatment.
+ // Now we have a path of index positions,
+ // and it's in reverse.
+ // The "true" start or end position might be missing
+ // since those have been given special treatment.
#ifdef PATHFINDER_DEBUG
std::cout << "Index path:" << std::endl;
printPath(index_path);
#endif
- //from here we'll make the final changes to the path
+ // from here we'll make the final changes to the path
std::vector<v3s16> full_path;
- //calculate required size
+ // calculate required size
int full_path_size = index_path.size();
if (source != true_source) {
full_path_size++;
@@ -768,23 +750,22 @@ std::vector<v3s16> Pathfinder::getPath(v3s16 source,
}
full_path.reserve(full_path_size);
- //manually add true_source to start of path, if needed
+ // manually add true_source to start of path, if needed
if (source != true_source) {
full_path.push_back(true_source);
}
- //convert all index positions to "normal" positions and insert
- //them into full_path in reverse
+ // convert all index positions to "normal" positions and insert
+ // them into full_path in reverse
std::vector<v3s16>::reverse_iterator rit = index_path.rbegin();
for (; rit != index_path.rend(); ++rit) {
full_path.push_back(getIndexElement(*rit).pos);
}
- //manually add true_destination to end of path, if needed
+ // manually add true_destination to end of path, if needed
if (destination != true_destination) {
full_path.push_back(true_destination);
}
- //Done! We now have a complete path of normal positions.
-
+ // Done! We now have a complete path of normal positions.
#ifdef PATHFINDER_DEBUG
std::cout << "Full path:" << std::endl;
@@ -794,25 +775,23 @@ std::vector<v3s16> Pathfinder::getPath(v3s16 source,
timespec ts2;
clock_gettime(CLOCK_REALTIME, &ts2);
- int ms = (ts2.tv_nsec - ts.tv_nsec)/(1000*1000);
- int us = ((ts2.tv_nsec - ts.tv_nsec) - (ms*1000*1000))/1000;
- int ns = ((ts2.tv_nsec - ts.tv_nsec) - ( (ms*1000*1000) + (us*1000)));
-
+ int ms = (ts2.tv_nsec - ts.tv_nsec) / (1000 * 1000);
+ int us = ((ts2.tv_nsec - ts.tv_nsec) - (ms * 1000 * 1000)) / 1000;
+ int ns = ((ts2.tv_nsec - ts.tv_nsec) -
+ ((ms * 1000 * 1000) + (us * 1000)));
- std::cout << "Calculating path took: " << (ts2.tv_sec - ts.tv_sec) <<
- "s " << ms << "ms " << us << "us " << ns << "ns " << std::endl;
+ std::cout << "Calculating path took: " << (ts2.tv_sec - ts.tv_sec) << "s "
+ << ms << "ms " << us << "us " << ns << "ns " << std::endl;
#endif
return full_path;
- }
- else {
+ } else {
#ifdef PATHFINDER_DEBUG
printPathLen();
#endif
INFO_TARGET << "No path found" << std::endl;
}
-
- //return
+ // return
return retval;
}
@@ -835,44 +814,42 @@ PathCost Pathfinder::calcCost(v3s16 pos, v3s16 dir)
v3s16 pos2 = pos + dir;
- //check limits
+ // check limits
if (!m_limits.isPointInside(pos2)) {
- DEBUG_OUT("Pathfinder: " << PP(pos2) <<
- " no cost -> out of limits" << std::endl);
+ DEBUG_OUT("Pathfinder: " << PP(pos2) << " no cost -> out of limits"
+ << std::endl);
return retval;
}
MapNode node_at_pos2 = m_map->getNode(pos2);
- //did we get information about node?
- if (node_at_pos2.param0 == CONTENT_IGNORE ) {
- VERBOSE_TARGET << "Pathfinder: (1) area at pos: "
- << PP(pos2) << " not loaded";
- return retval;
+ // did we get information about node?
+ if (node_at_pos2.param0 == CONTENT_IGNORE) {
+ VERBOSE_TARGET << "Pathfinder: (1) area at pos: " << PP(pos2)
+ << " not loaded";
+ return retval;
}
if (!m_ndef->get(node_at_pos2).walkable) {
- MapNode node_below_pos2 =
- m_map->getNode(pos2 + v3s16(0, -1, 0));
-
- //did we get information about node?
- if (node_below_pos2.param0 == CONTENT_IGNORE ) {
- VERBOSE_TARGET << "Pathfinder: (2) area at pos: "
- << PP((pos2 + v3s16(0, -1, 0))) << " not loaded";
- return retval;
+ MapNode node_below_pos2 = m_map->getNode(pos2 + v3s16(0, -1, 0));
+
+ // did we get information about node?
+ if (node_below_pos2.param0 == CONTENT_IGNORE) {
+ VERBOSE_TARGET << "Pathfinder: (2) area at pos: "
+ << PP((pos2 + v3s16(0, -1, 0))) << " not loaded";
+ return retval;
}
- //test if the same-height neighbor is suitable
+ // test if the same-height neighbor is suitable
if (m_ndef->get(node_below_pos2).walkable) {
- //SUCCESS!
+ // SUCCESS!
retval.valid = true;
retval.value = 1;
retval.y_change = 0;
- DEBUG_OUT("Pathfinder: "<< PP(pos)
- << " cost same height found" << std::endl);
- }
- else {
- //test if we can fall a couple of nodes (m_maxdrop)
+ DEBUG_OUT("Pathfinder: " << PP(pos) << " cost same height found"
+ << std::endl);
+ } else {
+ // test if we can fall a couple of nodes (m_maxdrop)
v3s16 testpos = pos2 + v3s16(0, -1, 0);
MapNode node_at_pos = m_map->getNode(testpos);
@@ -883,35 +860,36 @@ PathCost Pathfinder::calcCost(v3s16 pos, v3s16 dir)
node_at_pos = m_map->getNode(testpos);
}
- //did we find surface?
+ // did we find surface?
if ((testpos.Y >= m_limits.MinEdge.Y) &&
(node_at_pos.param0 != CONTENT_IGNORE) &&
(m_ndef->get(node_at_pos).walkable)) {
if ((pos2.Y - testpos.Y - 1) <= m_maxdrop) {
- //SUCCESS!
+ // SUCCESS!
retval.valid = true;
retval.value = 2;
- //difference of y-pos +1 (target node is ABOVE solid node)
- retval.y_change = ((testpos.Y - pos2.Y) +1);
- DEBUG_OUT("Pathfinder cost below height found" << std::endl);
- }
- else {
+ // difference of y-pos +1 (target node is ABOVE
+ // solid node)
+ retval.y_change = ((testpos.Y - pos2.Y) + 1);
+ DEBUG_OUT("Pathfinder cost below height found"
+ << std::endl);
+ } else {
INFO_TARGET << "Pathfinder:"
- " distance to surface below too big: "
- << (testpos.Y - pos2.Y) << " max: " << m_maxdrop
- << std::endl;
+ " distance to surface below too "
+ "big: "
+ << (testpos.Y - pos2.Y)
+ << " max: " << m_maxdrop << std::endl;
}
- }
- else {
- DEBUG_OUT("Pathfinder: no surface below found" << std::endl);
+ } else {
+ DEBUG_OUT("Pathfinder: no surface below found"
+ << std::endl);
}
}
- }
- else {
- //test if we can jump upwards (m_maxjump)
+ } else {
+ // test if we can jump upwards (m_maxjump)
v3s16 targetpos = pos2; // position for jump target
- v3s16 jumppos = pos; // position for checking if jumping space is free
+ v3s16 jumppos = pos; // position for checking if jumping space is free
MapNode node_target = m_map->getNode(targetpos);
MapNode node_jump = m_map->getNode(jumppos);
bool headbanger = false; // true if anything blocks jumppath
@@ -919,42 +897,40 @@ PathCost Pathfinder::calcCost(v3s16 pos, v3s16 dir)
while ((node_target.param0 != CONTENT_IGNORE) &&
(m_ndef->get(node_target).walkable) &&
(targetpos.Y < m_limits.MaxEdge.Y)) {
- //if the jump would hit any solid node, discard
+ // if the jump would hit any solid node, discard
if ((node_jump.param0 == CONTENT_IGNORE) ||
(m_ndef->get(node_jump).walkable)) {
- headbanger = true;
+ headbanger = true;
break;
}
targetpos += v3s16(0, 1, 0);
- jumppos += v3s16(0, 1, 0);
+ jumppos += v3s16(0, 1, 0);
node_target = m_map->getNode(targetpos);
- node_jump = m_map->getNode(jumppos);
-
+ node_jump = m_map->getNode(jumppos);
}
- //check headbanger one last time
+ // check headbanger one last time
if ((node_jump.param0 == CONTENT_IGNORE) ||
- (m_ndef->get(node_jump).walkable)) {
+ (m_ndef->get(node_jump).walkable)) {
headbanger = true;
}
- //did we find surface without banging our head?
+ // did we find surface without banging our head?
if ((!headbanger) && (targetpos.Y <= m_limits.MaxEdge.Y) &&
(!m_ndef->get(node_target).walkable)) {
if (targetpos.Y - pos2.Y <= m_maxjump) {
- //SUCCESS!
+ // SUCCESS!
retval.valid = true;
retval.value = 2;
retval.y_change = (targetpos.Y - pos2.Y);
DEBUG_OUT("Pathfinder cost above found" << std::endl);
+ } else {
+ DEBUG_OUT("Pathfinder: distance to surface above too "
+ "big: "
+ << (targetpos.Y - pos2.Y)
+ << " max: " << m_maxjump << std::endl);
}
- else {
- DEBUG_OUT("Pathfinder: distance to surface above too big: "
- << (targetpos.Y - pos2.Y) << " max: " << m_maxjump
- << std::endl);
- }
- }
- else {
+ } else {
DEBUG_OUT("Pathfinder: no surface above found" << std::endl);
}
}
@@ -976,17 +952,14 @@ PathGridnode &Pathfinder::getIndexElement(v3s16 ipos)
/******************************************************************************/
inline PathGridnode &Pathfinder::getIdxElem(s16 x, s16 y, s16 z)
{
- return m_nodes_container->access(v3s16(x,y,z));
+ return m_nodes_container->access(v3s16(x, y, z));
}
/******************************************************************************/
bool Pathfinder::isValidIndex(v3s16 index)
{
- if ( (index.X < m_max_index_x) &&
- (index.Y < m_max_index_y) &&
- (index.Z < m_max_index_z) &&
- (index.X >= 0) &&
- (index.Y >= 0) &&
+ if ((index.X < m_max_index_x) && (index.Y < m_max_index_y) &&
+ (index.Z < m_max_index_z) && (index.X >= 0) && (index.Y >= 0) &&
(index.Z >= 0))
return true;
@@ -998,26 +971,23 @@ v3s16 Pathfinder::invert(v3s16 pos)
{
v3s16 retval = pos;
- retval.X *=-1;
- retval.Y *=-1;
- retval.Z *=-1;
+ retval.X *= -1;
+ retval.Y *= -1;
+ retval.Z *= -1;
return retval;
}
/******************************************************************************/
-bool Pathfinder::updateAllCosts(v3s16 ipos,
- v3s16 srcdir,
- int current_cost,
- int level)
+bool Pathfinder::updateAllCosts(v3s16 ipos, v3s16 srcdir, int current_cost, int level)
{
PathGridnode &g_pos = getIndexElement(ipos);
g_pos.totalcost = current_cost;
g_pos.sourcedir = srcdir;
- level ++;
+ level++;
- //check if target has been found
+ // check if target has been found
if (g_pos.target) {
m_min_target_distance = current_cost;
DEBUG_OUT(LVL " Pathfinder: target found!" << std::endl);
@@ -1028,11 +998,7 @@ bool Pathfinder::updateAllCosts(v3s16 ipos,
// the 4 cardinal directions
const static v3s16 directions[4] = {
- v3s16(1,0, 0),
- v3s16(-1,0, 0),
- v3s16(0,0, 1),
- v3s16(0,0,-1)
- };
+ v3s16(1, 0, 0), v3s16(-1, 0, 0), v3s16(0, 0, 1), v3s16(0, 0, -1)};
for (v3s16 direction : directions) {
if (direction != srcdir) {
@@ -1044,16 +1010,20 @@ bool Pathfinder::updateAllCosts(v3s16 ipos,
v3s16 ipos2 = ipos + direction;
if (!isValidIndex(ipos2)) {
- DEBUG_OUT(LVL " Pathfinder: " << PP(ipos2) <<
- " out of range, max=" << PP(m_limits.MaxEdge) << std::endl);
+ DEBUG_OUT(LVL " Pathfinder: "
+ << PP(ipos2)
+ << " out of range, max="
+ << PP(m_limits.MaxEdge)
+ << std::endl);
continue;
}
PathGridnode &g_pos2 = getIndexElement(ipos2);
if (!g_pos2.valid) {
- VERBOSE_TARGET << LVL "Pathfinder: no data for new position: "
- << PP(ipos2) << std::endl;
+ VERBOSE_TARGET << LVL "Pathfinder: no data for "
+ "new position: "
+ << PP(ipos2) << std::endl;
continue;
}
@@ -1069,23 +1039,22 @@ bool Pathfinder::updateAllCosts(v3s16 ipos,
if ((g_pos2.totalcost < 0) ||
(g_pos2.totalcost > new_cost)) {
- DEBUG_OUT(LVL "Pathfinder: updating path at: "<<
- PP(ipos2) << " from: " << g_pos2.totalcost << " to "<<
- new_cost << std::endl);
+ DEBUG_OUT(LVL "Pathfinder: updating path at: "
+ << PP(ipos2) << " from: "
+ << g_pos2.totalcost << " to "
+ << new_cost << std::endl);
if (updateAllCosts(ipos2, invert(direction),
- new_cost, level)) {
+ new_cost, level)) {
retval = true;
- }
}
- else {
+ } else {
DEBUG_OUT(LVL "Pathfinder:"
- " already found shorter path to: "
+ " already found shorter path to: "
<< PP(ipos2) << std::endl);
}
- }
- else {
+ } else {
DEBUG_OUT(LVL "Pathfinder:"
- " not moving to invalid direction: "
+ " not moving to invalid direction: "
<< PP(directions[i]) << std::endl);
}
}
@@ -1104,8 +1073,6 @@ int Pathfinder::getXZManhattanDist(v3s16 pos)
return (max_x - min_x) + (max_z - min_z);
}
-
-
/******************************************************************************/
bool Pathfinder::updateCostHeuristic(v3s16 isource, v3s16 idestination)
{
@@ -1125,14 +1092,10 @@ bool Pathfinder::updateCostHeuristic(v3s16 isource, v3s16 idestination)
// the 4 cardinal directions
const static v3s16 directions[4] = {
- v3s16(1,0, 0),
- v3s16(-1,0, 0),
- v3s16(0,0, 1),
- v3s16(0,0,-1)
- };
+ v3s16(1, 0, 0), v3s16(-1, 0, 0), v3s16(0, 0, 1), v3s16(0, 0, -1)};
v3s16 current_pos;
- PathGridnode& s_pos = getIndexElement(isource);
+ PathGridnode &s_pos = getIndexElement(isource);
s_pos.source = true;
s_pos.totalcost = 0;
@@ -1149,12 +1112,14 @@ bool Pathfinder::updateCostHeuristic(v3s16 isource, v3s16 idestination)
// check if node is inside searchdistance and valid
if (!isValidIndex(ipos)) {
- DEBUG_OUT(LVL " Pathfinder: " << PP(current_pos) <<
- " out of search distance, max=" << PP(m_limits.MaxEdge) << std::endl);
+ DEBUG_OUT(LVL " Pathfinder: " << PP(current_pos)
+ << " out of search distance, max="
+ << PP(m_limits.MaxEdge)
+ << std::endl);
continue;
}
- PathGridnode& g_pos = getIndexElement(ipos);
+ PathGridnode &g_pos = getIndexElement(ipos);
g_pos.is_closed = true;
g_pos.is_open = false;
if (!g_pos.valid) {
@@ -1177,7 +1142,8 @@ bool Pathfinder::updateCostHeuristic(v3s16 isource, v3s16 idestination)
cost = calcCost(current_pos, direction_flat);
g_pos.setCost(direction_flat, cost);
}
- // update Y component of direction if neighbor requires jump or fall
+ // update Y component of direction if neighbor requires jump or
+ // fall
v3s16 direction_3d = v3s16(direction_flat);
direction_3d.Y = cost.y_change;
@@ -1187,13 +1153,15 @@ bool Pathfinder::updateCostHeuristic(v3s16 isource, v3s16 idestination)
PathGridnode &n_pos = getIndexElement(ineighbor);
if (cost.valid && !n_pos.is_closed && !n_pos.is_open) {
- // heuristic function; estimate cost from neighbor to destination
+ // heuristic function; estimate cost from neighbor to
+ // destination
cur_manhattan = getXZManhattanDist(neighbor);
// add neighbor to open list
n_pos.sourcedir = invert(direction_3d);
n_pos.totalcost = current_totalcost + cost.value;
- n_pos.estimated_cost = current_totalcost + cost.value + cur_manhattan;
+ n_pos.estimated_cost = current_totalcost + cost.value +
+ cur_manhattan;
n_pos.is_open = true;
openList.push(neighbor);
}
@@ -1207,16 +1175,21 @@ bool Pathfinder::updateCostHeuristic(v3s16 isource, v3s16 idestination)
bool Pathfinder::buildPath(std::vector<v3s16> &path, v3s16 ipos)
{
// The cost calculation should have set a source direction for all relevant nodes.
- // To build the path, we go backwards from the destination until we reach the start.
- for(u32 waypoints = 1; waypoints++; ) {
+ // To build the path, we go backwards from the destination until we reach the
+ // start.
+ for (u32 waypoints = 1; waypoints++;) {
if (waypoints > PATHFINDER_MAX_WAYPOINTS) {
- ERROR_TARGET << "Pathfinder: buildPath: path is too long (too many waypoints), aborting" << std::endl;
+ ERROR_TARGET << "Pathfinder: buildPath: path is too long (too "
+ "many waypoints), aborting"
+ << std::endl;
return false;
}
// Insert node into path
PathGridnode &g_pos = getIndexElement(ipos);
if (!g_pos.valid) {
- ERROR_TARGET << "Pathfinder: buildPath: invalid next pos detected, aborting" << std::endl;
+ ERROR_TARGET << "Pathfinder: buildPath: invalid next pos "
+ "detected, aborting"
+ << std::endl;
return false;
}
@@ -1235,7 +1208,8 @@ bool Pathfinder::buildPath(std::vector<v3s16> &path, v3s16 ipos)
}
/******************************************************************************/
-v3s16 Pathfinder::walkDownwards(v3s16 pos, unsigned int max_down) {
+v3s16 Pathfinder::walkDownwards(v3s16 pos, unsigned int max_down)
+{
if (max_down == 0)
return pos;
v3s16 testpos = v3s16(pos);
@@ -1243,27 +1217,25 @@ v3s16 Pathfinder::walkDownwards(v3s16 pos, unsigned int max_down) {
unsigned int down = 0;
while ((node_at_pos.param0 != CONTENT_IGNORE) &&
(!m_ndef->get(node_at_pos).walkable) &&
- (testpos.Y > m_limits.MinEdge.Y) &&
- (down <= max_down)) {
+ (testpos.Y > m_limits.MinEdge.Y) && (down <= max_down)) {
testpos += v3s16(0, -1, 0);
down++;
node_at_pos = m_map->getNode(testpos);
}
- //did we find surface?
- if ((testpos.Y >= m_limits.MinEdge.Y) &&
- (node_at_pos.param0 != CONTENT_IGNORE) &&
+ // did we find surface?
+ if ((testpos.Y >= m_limits.MinEdge.Y) && (node_at_pos.param0 != CONTENT_IGNORE) &&
(m_ndef->get(node_at_pos).walkable)) {
if (down == 0) {
pos = testpos;
} else if ((down - 1) <= max_down) {
- //difference of y-pos +1 (target node is ABOVE solid node)
+ // difference of y-pos +1 (target node is ABOVE solid node)
testpos += v3s16(0, 1, 0);
pos = testpos;
- }
- else {
- VERBOSE_TARGET << "Pos too far above ground: " <<
- "Index: " << PP(getIndexPos(pos)) <<
- "Realpos: " << PP(getRealPos(getIndexPos(pos))) << std::endl;
+ } else {
+ VERBOSE_TARGET << "Pos too far above ground: "
+ << "Index: " << PP(getIndexPos(pos))
+ << "Realpos: " << PP(getRealPos(getIndexPos(pos)))
+ << std::endl;
}
} else {
DEBUG_OUT("Pathfinder: no surface found below pos" << std::endl);
@@ -1301,21 +1273,23 @@ void Pathfinder::printCost(PathDirections dir)
std::cout << "Level: " << y << std::endl;
- std::cout << std::setw(4) << " " << " ";
+ std::cout << std::setw(4) << " "
+ << " ";
for (int x = 0; x < m_max_index_x; x++) {
std::cout << std::setw(4) << x;
}
std::cout << std::endl;
for (int z = 0; z < m_max_index_z; z++) {
- std::cout << std::setw(4) << z <<": ";
+ std::cout << std::setw(4) << z << ": ";
for (int x = 0; x < m_max_index_x; x++) {
if (getIdxElem(x, y, z).directions[dir].valid)
std::cout << std::setw(4)
- << getIdxElem(x, y, z).directions[dir].value;
+ << getIdxElem(x, y, z).directions[dir]
+ .value;
else
std::cout << std::setw(4) << "-";
- }
+ }
std::cout << std::endl;
}
std::cout << std::endl;
@@ -1332,21 +1306,23 @@ void Pathfinder::printYdir(PathDirections dir)
std::cout << "Level: " << y << std::endl;
- std::cout << std::setw(4) << " " << " ";
+ std::cout << std::setw(4) << " "
+ << " ";
for (int x = 0; x < m_max_index_x; x++) {
std::cout << std::setw(4) << x;
}
std::cout << std::endl;
for (int z = 0; z < m_max_index_z; z++) {
- std::cout << std::setw(4) << z <<": ";
+ std::cout << std::setw(4) << z << ": ";
for (int x = 0; x < m_max_index_x; x++) {
if (getIdxElem(x, y, z).directions[dir].valid)
std::cout << std::setw(4)
- << getIdxElem(x, y, z).directions[dir].y_change;
+ << getIdxElem(x, y, z).directions[dir]
+ .y_change;
else
std::cout << std::setw(4) << "-";
- }
+ }
std::cout << std::endl;
}
std::cout << std::endl;
@@ -1363,14 +1339,15 @@ void Pathfinder::printType()
std::cout << "Level: " << y << std::endl;
- std::cout << std::setw(3) << " " << " ";
+ std::cout << std::setw(3) << " "
+ << " ";
for (int x = 0; x < m_max_index_x; x++) {
std::cout << std::setw(3) << x;
}
std::cout << std::endl;
for (int z = 0; z < m_max_index_z; z++) {
- std::cout << std::setw(3) << z <<": ";
+ std::cout << std::setw(3) << z << ": ";
for (int x = 0; x < m_max_index_x; x++) {
char toshow = getIdxElem(x, y, z).type;
std::cout << std::setw(3) << toshow;
@@ -1386,28 +1363,30 @@ void Pathfinder::printType()
void Pathfinder::printPathLen()
{
std::cout << "Pathlen:" << std::endl;
- std::cout << std::setfill('-') << std::setw(80) << "-" << std::endl;
- std::cout << std::setfill(' ');
- for (int y = 0; y < m_max_index_y; y++) {
+ std::cout << std::setfill('-') << std::setw(80) << "-" << std::endl;
+ std::cout << std::setfill(' ');
+ for (int y = 0; y < m_max_index_y; y++) {
- std::cout << "Level: " << y << std::endl;
+ std::cout << "Level: " << y << std::endl;
- std::cout << std::setw(3) << " " << " ";
- for (int x = 0; x < m_max_index_x; x++) {
- std::cout << std::setw(3) << x;
- }
- std::cout << std::endl;
+ std::cout << std::setw(3) << " "
+ << " ";
+ for (int x = 0; x < m_max_index_x; x++) {
+ std::cout << std::setw(3) << x;
+ }
+ std::cout << std::endl;
- for (int z = 0; z < m_max_index_z; z++) {
- std::cout << std::setw(3) << z <<": ";
- for (int x = 0; x < m_max_index_x; x++) {
- std::cout << std::setw(3) << getIdxElem(x, y, z).totalcost;
- }
- std::cout << std::endl;
+ for (int z = 0; z < m_max_index_z; z++) {
+ std::cout << std::setw(3) << z << ": ";
+ for (int x = 0; x < m_max_index_x; x++) {
+ std::cout << std::setw(3)
+ << getIdxElem(x, y, z).totalcost;
}
std::cout << std::endl;
}
std::cout << std::endl;
+ }
+ std::cout << std::endl;
}
/******************************************************************************/
@@ -1435,8 +1414,7 @@ std::string Pathfinder::dirToName(PathDirections dir)
void Pathfinder::printPath(std::vector<v3s16> path)
{
unsigned int current = 0;
- for (std::vector<v3s16>::iterator i = path.begin();
- i != path.end(); ++i) {
+ for (std::vector<v3s16>::iterator i = path.begin(); i != path.end(); ++i) {
std::cout << std::setw(3) << current << ":" << PP((*i)) << std::endl;
current++;
}