Remove duplicated code in navmesh

This commit is contained in:
Benau 2016-08-03 12:37:48 +08:00
parent 9f0529f26f
commit 10937333a1
13 changed files with 245 additions and 474 deletions

View File

@ -567,7 +567,7 @@ bool ItemManager::randomItemsForArena(const AlignedArray<btTransform>& pos)
j > NITRO_BIG ? Item::ITEM_NITRO_BIG :
j > NITRO_SMALL ? Item::ITEM_NITRO_SMALL : Item::ITEM_BANANA);
Vec3 loc = BattleGraph::get()
->getPolyOfNode(used_location[i]).getCenter();
->getQuadOfNode(used_location[i]).getCenter();
Item* item = newItem(type, loc, Vec3(0, 1, 0));
BattleGraph::get()->insertItems(item, used_location[i]);
}

View File

@ -27,6 +27,7 @@
#include "karts/controller/ai_properties.hpp"
#include "karts/kart_properties.hpp"
#include "tracks/battle_graph.hpp"
#include "tracks/quad.hpp"
#include "utils/log.hpp"
int ArenaAI::m_test_node_for_banana = BattleGraph::UNKNOWN_POLY;
@ -156,7 +157,7 @@ bool ArenaAI::updateAimingPosition()
if (forward == m_target_node)
{
m_aiming_points.push_back(BattleGraph::get()
->getPolyOfNode(forward).getCenter());
->getQuadOfNode(forward).getCenter());
m_aiming_points.push_back(m_target_point);
m_aiming_nodes.insert(forward);
@ -174,9 +175,9 @@ bool ArenaAI::updateAimingPosition()
}
m_aiming_points.push_back(BattleGraph::get()
->getPolyOfNode(forward).getCenter());
->getQuadOfNode(forward).getCenter());
m_aiming_points.push_back(BattleGraph::get()
->getPolyOfNode(next_node).getCenter());
->getQuadOfNode(next_node).getCenter());
m_aiming_nodes.insert(forward);
m_aiming_nodes.insert(next_node);

View File

@ -28,10 +28,12 @@
#include "items/item_manager.hpp"
#include "race/race_manager.hpp"
#include "tracks/navmesh.hpp"
#include "tracks/quad.hpp"
#include "tracks/track.hpp"
#include "tracks/track_manager.hpp"
#include "utils/log.hpp"
#include <algorithm>
#include <queue>
const int BattleGraph::UNKNOWN_POLY = -1;
@ -50,9 +52,10 @@ BattleGraph::BattleGraph(const std::string &navmesh_file_name,
buildGraph(NavMesh::get());
// Compute shortest distance from all nodes
for(unsigned int i=0; i < NavMesh::get()->getNumberOfPolys(); i++)
for(unsigned int i=0; i < NavMesh::get()->getNumberOfQuads(); i++)
computeDijkstra(i);
sortNearbyQuad();
if (node && race_manager->getMinorMode() == RaceManager::MINOR_MODE_SOCCER)
loadGoalNodes(node);
@ -74,35 +77,32 @@ BattleGraph::~BattleGraph(void)
* adjacency matrix. */
void BattleGraph::buildGraph(NavMesh* navmesh)
{
unsigned int n_polys = navmesh->getNumberOfPolys();
const unsigned int n_quads = navmesh->getNumberOfQuads();
m_distance_matrix = std::vector< std::vector<float> >
(n_polys, std::vector<float>(n_polys, 9999.9f));
for(unsigned int i=0; i<n_polys; i++)
m_distance_matrix = std::vector<std::vector<float>>
(n_quads, std::vector<float>(n_quads, 9999.9f));
for(unsigned int i = 0; i < n_quads; i++)
{
NavPoly currentPoly = navmesh->getNavPoly(i);
const std::vector<int> &adjacents = navmesh->getAdjacentPolys(i);
for(unsigned int j=0; j<adjacents.size(); j++)
const Quad& cur_quad = navmesh->getQuad(i);
for (const int& adjacent : navmesh->getAdjacentQuads(i))
{
Vec3 diff = navmesh->getCenterOfPoly(adjacents[j])
- currentPoly.getCenter();
Vec3 diff = navmesh->getQuad(adjacent).getCenter()
- cur_quad.getCenter();
float distance = diff.length();
m_distance_matrix[i][adjacents[j]] = distance;
//m_distance_matrix[adjacents[j]][i] = distance;
m_distance_matrix[i][adjacent] = distance;
}
m_distance_matrix[i][i] = 0.0f;
}
// Allocate and initialise the previous node data structure:
unsigned int n = getNumNodes();
m_parent_poly = std::vector< std::vector<int> >
(n, std::vector<int>(n, BattleGraph::UNKNOWN_POLY));
for(unsigned int i=0; i<n; i++)
m_parent_poly = std::vector<std::vector<int>>
(n_quads, std::vector<int>(n_quads, BattleGraph::UNKNOWN_POLY));
for (unsigned int i = 0; i < n_quads; i++)
{
for(unsigned int j=0; j<n; j++)
for (unsigned int j = 0; j < n_quads; j++)
{
if(i == j || m_distance_matrix[i][j]>=9899.9f)
m_parent_poly[i][j]=-1;
if(i == j || m_distance_matrix[i][j] >= 9899.9f)
m_parent_poly[i][j] = -1;
else
m_parent_poly[i][j] = i;
} // for j
@ -146,11 +146,9 @@ void BattleGraph::computeDijkstra(int source)
int cur_index = current.first;
if(visited[cur_index]) continue;
visited[cur_index] = true;
const NavPoly &current_poly = navmesh->getNavPoly(cur_index);
const std::vector<int> &adjacents = current_poly.getAdjacents();
for(unsigned int j=0; j<adjacents.size(); j++)
for (const int& adjacent : navmesh->getAdjacentQuads(cur_index))
{
int adjacent = adjacents[j];
// Distance already computed, can be ignored
if(visited[adjacent]) continue;
@ -225,7 +223,7 @@ void BattleGraph::findItemsOnGraphNodes()
for (unsigned int j = 0; j < this->getNumNodes(); ++j)
{
if (NavMesh::get()->getNavPoly(j).pointInPoly(xyz, false))
if (getQuadOfNode(j).pointInQuad(xyz, false))
polygon = j;
}
@ -244,70 +242,50 @@ int BattleGraph::pointToNode(const int cur_node,
const Vec3& cur_point,
bool ignore_vertical) const
{
int final_node = BattleGraph::UNKNOWN_POLY;
if (cur_node == BattleGraph::UNKNOWN_POLY)
{
// Try all nodes in the battle graph
bool found = false;
unsigned int node = 0;
while (!found && node < this->getNumNodes())
for (unsigned int node = 0; node < this->getNumNodes(); node++)
{
const NavPoly& p_all = this->getPolyOfNode(node);
if (p_all.pointInPoly(cur_point, ignore_vertical))
const Quad& quad = this->getQuadOfNode(node);
if (quad.pointInQuad(cur_point, ignore_vertical))
{
final_node = node;
found = true;
return node;
}
node++;
}
}
else
{
// Check if the point is still on the same node
const NavPoly& p_cur = this->getPolyOfNode(cur_node);
if (p_cur.pointInPoly(cur_point, ignore_vertical)) return cur_node;
const Quad& cur_quad = this->getQuadOfNode(cur_node);
if (cur_quad.pointInQuad(cur_point, ignore_vertical)) return cur_node;
// If not then check all adjacent polys
const std::vector<int>& adjacents = NavMesh::get()
->getAdjacentPolys(cur_node);
bool found = false;
unsigned int num = 0;
while (!found && num < adjacents.size())
// If not then check all nearby quads (8 quads)
// Skip the same node
assert(cur_node == m_nearby_quads[cur_node][0]);
for (unsigned int i = 1; i < m_nearby_quads[0].size(); i++)
{
const NavPoly& p_temp = this->getPolyOfNode(adjacents[num]);
if (p_temp.pointInPoly(cur_point, ignore_vertical))
const int test_node = m_nearby_quads[cur_node][i];
const Quad& quad = this->getQuadOfNode(test_node);
if (quad.pointInQuad(cur_point, ignore_vertical))
{
final_node = adjacents[num];
found = true;
return test_node;
}
num++;
}
// Current node is still unkown
if (final_node == BattleGraph::UNKNOWN_POLY)
{
// Calculated distance from saved node to current position,
// if it's close enough than use the saved node anyway, it
// may happen when the kart stays on the edge of obstacles
const NavPoly& p = this->getPolyOfNode(cur_node);
const float dist = (p.getCenter() - cur_point).length_2d();
// Current node is still unkown:
// Calculated distance from saved node to current position,
// if it's close enough than use the saved node anyway, it
// may happen when the kart stays on the edge of obstacles
Vec3 diff = (cur_quad.getCenter() - cur_point);
float dist = diff.length();
if (dist < 3.0f)
final_node = cur_node;
}
if (dist < 3.0f)
return cur_node;
}
return final_node;
} // pointToNode
// -----------------------------------------------------------------------------
const int BattleGraph::getNextShortestPathPoly(int i, int j) const
{
if (i == BattleGraph::UNKNOWN_POLY || j == BattleGraph::UNKNOWN_POLY)
return BattleGraph::UNKNOWN_POLY;
return m_parent_poly[j][i];
} // getNextShortestPathPoly
return BattleGraph::UNKNOWN_POLY;
} // pointToNode
// -----------------------------------------------------------------------------
const bool BattleGraph::differentNodeColor(int n, NodeColor* c) const
@ -456,4 +434,40 @@ std::vector<int> BattleGraph::getPathFromTo(int from, int to,
path.push_back(to);
}
return path;
} // getPathFromTo
} // getPathFromTo
// ----------------------------------------------------------------------------
void BattleGraph::sortNearbyQuad()
{
// Only try the nearby 8 quads
const unsigned int n = 8;
m_nearby_quads = std::vector< std::vector<int> >
(this->getNumNodes(), std::vector<int>(n, BattleGraph::UNKNOWN_POLY));
for (unsigned int i = 0; i < this->getNumNodes(); i++)
{
// Get the distance to all nodes at i
std::vector<float> dist = m_distance_matrix[i];
for (unsigned int j = 0; j < n; j++)
{
std::vector<float>::iterator it =
std::min_element(dist.begin(), dist.end());
const int pos = it - dist.begin();
m_nearby_quads[i][j] = pos;
dist[pos] = 999999.0f;
}
}
} // sortNearbyQuad
// ----------------------------------------------------------------------------
void BattleGraph::set3DVerticesOfGraph(int i, video::S3DVertex *v,
const video::SColor &color) const
{
NavMesh::get()->getQuad(i).getVertices(v, color);
} // set3DVerticesOfGraph
// ----------------------------------------------------------------------------
const bool BattleGraph::isNodeInvisible(int n) const
{
return NavMesh::get()->getQuad(n).isInvisible();
} // isNodeInvisible

View File

@ -26,10 +26,8 @@
#include "tracks/graph_structure.hpp"
#include "tracks/navmesh.hpp"
class GraphStructure;
class Item;
class ItemManager;
class Navmesh;
class XMLNode;
/**
@ -53,6 +51,8 @@ private:
/** The matrix that is used to store computed shortest paths */
std::vector< std::vector< int > > m_parent_poly;
std::vector< std::vector< int > > m_nearby_quads;
/** Stores the name of the file containing the NavMesh data */
std::string m_navmesh_file;
@ -64,23 +64,19 @@ private:
void buildGraph(NavMesh*);
void computeFloydWarshall();
void loadGoalNodes(const XMLNode *node);
void sortNearbyQuad();
BattleGraph(const std::string &navmesh_file_name, const XMLNode *node=NULL);
~BattleGraph(void);
// ------------------------------------------------------------------------
virtual void set3DVerticesOfGraph(int i, video::S3DVertex *v,
const video::SColor &color) const
{ NavMesh::get()->setVertices(i, v, color); }
const video::SColor &color) const;
// ------------------------------------------------------------------------
virtual void getGraphBoundingBox(Vec3 *min, Vec3 *max) const
{ NavMesh::get()->getBoundingBox(min, max); }
// ------------------------------------------------------------------------
virtual const bool isNodeInvisible(int n) const
{ return false; }
// ------------------------------------------------------------------------
virtual const bool isNodeInvalid(int n) const
{ return (NavMesh::get()->getNavPoly(n).getVerticesIndex()).size()!=4; }
virtual const bool isNodeInvisible(int n) const;
// ------------------------------------------------------------------------
virtual const bool hasLapLine() const
{ return false; }
@ -94,15 +90,16 @@ public:
static const int UNKNOWN_POLY;
void findItemsOnGraphNodes();
// ----------------------------------------------------------------------
int pointToNode(const int cur_node,
const Vec3& cur_point,
bool ignore_vertical) const;
// ------------------------------------------------------------------------
static void unitTesting();
// ------------------------------------------------------------------------
/** Returns the one instance of this object. */
static BattleGraph *get() { return m_battle_graph; }
// ----------------------------------------------------------------------
// ------------------------------------------------------------------------
/** Asserts that no BattleGraph instance exists. Then
* creates a BattleGraph instance. */
static void create(const std::string &navmesh_file_name,
@ -110,9 +107,8 @@ public:
{
assert(m_battle_graph==NULL);
m_battle_graph = new BattleGraph(navmesh_file_name, node);
} // create
// ----------------------------------------------------------------------
// ------------------------------------------------------------------------
/** Cleans up the BattleGraph instance if it exists */
static void destroy()
{
@ -122,14 +118,13 @@ public:
m_battle_graph = NULL;
}
} // destroy
// ----------------------------------------------------------------------
/** Returns the number of nodes in the BattleGraph (equal to the number of
* polygons in the NavMesh */
// ------------------------------------------------------------------------
/** Returns the number of nodes in the BattleGraph (equal to the number
* of quads in the NavMesh
*/
virtual const unsigned int getNumNodes() const
{ return m_distance_matrix.size(); }
// ----------------------------------------------------------------------
{ return NavMesh::get()->getNumberOfQuads(); }
// ------------------------------------------------------------------------
/** Returns the distance between any two nodes */
float getDistance(int from, int to) const
{
@ -139,26 +134,33 @@ public:
return m_distance_matrix[from][to];
}
// ------------------------------------------------------------------------
/** Returns the NavPoly corresponding to the i-th node of the BattleGraph */
const NavPoly& getPolyOfNode(int i) const
{ return NavMesh::get()->getNavPoly(i); }
// ------------------------------------------------------------------------
/** Returns true if the NavPoly lies near the edge. */
bool isNearEdge(int i) const
{ return NavMesh::get()->getNavPoly(i).isPolyNearEdge(); }
// ------------------------------------------------------------------------
/** Returns the next polygon on the shortest path from i to j.
* Note: m_parent_poly[j][i] contains the parent of i on path from j to i,
* which is the next node on the path from i to j (undirected graph) */
const int getNextShortestPathPoly(int i, int j) const;
* Note: m_parent_poly[j][i] contains the parent of i on path from j to i,
* which is the next node on the path from i to j (undirected graph)
*/
int getNextShortestPathPoly(int i, int j) const
{
if (i == BattleGraph::UNKNOWN_POLY || j == BattleGraph::UNKNOWN_POLY)
return BattleGraph::UNKNOWN_POLY;
return m_parent_poly[j][i];
}
// ------------------------------------------------------------------------
std::vector<std::pair<const Item*, int>>& getItemList()
{ return m_items_on_graph; }
// ------------------------------------------------------------------------
void insertItems(Item* item, int polygon)
{ m_items_on_graph.push_back(std::make_pair(item, polygon)); }
// ------------------------------------------------------------------------
/** Returns the quad that belongs to a node. */
const Quad& getQuadOfNode(unsigned int n) const
{ return NavMesh::get()->getQuad(n); }
// ------------------------------------------------------------------------
/** Returns true if the quad lies near the edge, which means it doesn't
* have 4 adjacent quads.
*/
bool isNearEdge(unsigned int n) const
{ return NavMesh::get()->getAdjacentQuads(n).size() != 4; }
// ------------------------------------------------------------------------
}; //BattleGraph
#endif

View File

@ -28,6 +28,7 @@
#include "graphics/shaders.hpp"
#include "graphics/rtts.hpp"
#include "modes/world.hpp"
#include "modes/profile_world.hpp"
#include "utils/log.hpp"
// -----------------------------------------------------------------------------
@ -140,12 +141,6 @@ void GraphStructure::createMesh(bool show_invisible,
// Ignore invisible quads
if (!show_invisible && isNodeInvisible(count))
continue;
else if (isNodeInvalid(count))
{
// There should not be a node which isn't made of 4 vertices
Log::warn("Graph Structure", "There is an invalid node!");
continue;
}
// Swap the colours from red to blue and back
if (!track_color)
@ -248,6 +243,9 @@ void GraphStructure::makeMiniMap(const core::dimension2du &dimension,
video::ITexture** oldRttMinimap,
FrameBuffer** newRttMinimap)
{
// Skip minimap when profiling
if (ProfileWorld::isNoGraphics()) return;
const video::SColor oldClearColor = World::getWorld()->getClearColor();
World::getWorld()->setClearbackBufferColor(video::SColor(0, 255, 255, 255));
World::getWorld()->forceFogDisabled(true);

View File

@ -82,7 +82,6 @@ private:
const video::SColor &color) const = 0;
virtual void getGraphBoundingBox(Vec3 *min, Vec3 *max) const = 0;
virtual const bool isNodeInvisible(int n) const = 0;
virtual const bool isNodeInvalid(int n) const = 0;
virtual const bool hasLapLine() const = 0;
virtual const bool differentNodeColor(int n, NodeColor* c) const = 0;

View File

@ -1,87 +0,0 @@
//
// SuperTuxKart - a fun racing game with go-kart
// Copyright (C) 2009-2015 Joerg Henrichs
//
// This program is free software; you can redistribute it and/or
// modify it under the terms of the GNU General Public License
// as published by the Free Software Foundation; either version 3
// of the License, or (at your option) any later version.
//
// This program is distributed in the hope that it will be useful,
// but WITHOUT ANY WARRANTY; without even the implied warranty of
// MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
// GNU General Public License for more details.
//
// You should have received a copy of the GNU General Public License
// along with this program; if not, write to the Free Software
// Foundation, Inc., 59 Temple Place - Suite 330, Boston, MA 02111-1307, USA.
#include "tracks/nav_poly.hpp"
#include "tracks/navmesh.hpp"
#include <algorithm>
#include <iostream>
/** Constructor that takes a vector of points and a vector of adjacent polygons */
NavPoly::NavPoly(const std::vector<int> &polygonVertIndices,
const std::vector<int> &adjacentPolygonIndices)
{
m_vertices = polygonVertIndices;
m_adjacents = adjacentPolygonIndices;
std::vector<Vec3> xyz_points = getVertices();
Vec3 temp(0.0f,0.0f,0.0f);
for(unsigned int i=0; i<xyz_points.size(); i++)
temp = temp + xyz_points[i];
m_center = (temp)*( 1.0f / xyz_points.size());
}
//-----------------------------------------------------------------------------
const std::vector<Vec3> NavPoly::getVertices()
{
std::vector<Vec3> points;
for(unsigned int i=0; i<m_vertices.size(); i++)
points.push_back(NavMesh::get()->getVertex(m_vertices[i]));
return points;
}
//-----------------------------------------------------------------------------
bool NavPoly::pointInPoly(const Vec3& p, bool ignore_vertical) const
{
std::vector<Vec3> points;
for(unsigned int i=0; i<m_vertices.size(); i++)
points.push_back(NavMesh::get()->getVertex(m_vertices[i]));
// The point is on which side of the first edge
float side = p.sideOfLine2D(points[0],points[1]);
// The point is inside the polygon if it is on the same side for all edges
for(unsigned int i=1; i<points.size(); i++)
{
// If it is on different side then product is < 0 , return false
if(p.sideOfLine2D(points[i % points.size()],
points[(i+1)% points.size()]) * side < 0)
return false;
}
if (ignore_vertical) return true;
// Check for vertical distance too
const float dist = p.getY() - m_center.getY();
if (fabsf(dist) > 1.0f)
return false;
return true;
}
//-----------------------------------------------------------------------------
const Vec3& NavPoly::operator[](int i) const
{
return NavMesh::get()->getVertex(m_vertices[i]);
}

View File

@ -1,75 +0,0 @@
//
// SuperTuxKart - a fun racing game with go-kart
// Copyright (C) 2009-2015 Joerg Henrichs
//
// This program is free software; you can redistribute it and/or
// modify it under the terms of the GNU General Public License
// as published by the Free Software Foundation; either version 3
// of the License, or (at your option) any later version.
//
// This program is distributed in the hope that it will be useful,
// but WITHOUT ANY WARRANTY; without even the implied warranty of
// MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
// GNU General Public License for more details.
//
// You should have received a copy of the GNU General Public License
// along with this program; if not, write to the Free Software
// Foundation, Inc., 59 Temple Place - Suite 330, Boston, MA 02111-1307, USA.
#ifndef HEADER_NAV_POLY_HPP
#define HEADER_NAV_POLY_HPP
#include <vector>
#include <string>
#include <SColor.h>
#include "utils/vec3.hpp"
/**
* \ingroup tracks
*/
class NavPoly
{
private:
/** Holds the index of vertices for a polygon **/
std::vector<int> m_vertices;
/** Center of this polygon. **/
Vec3 m_center;
/** Holds the index of adjacent polyogns **/
std::vector<int> m_adjacents;
public:
NavPoly(const std::vector<int> &polygonVertIndices,
const std::vector<int> &adjacentPolygonIndices);
// ------------------------------------------------------------------------
/** Returns the center point of a polygon. */
const Vec3& getCenter() const { return m_center; }
// ------------------------------------------------------------------------
/** Returns the adjacent polygons of a polygon. */
const std::vector<int>& getAdjacents() const { return m_adjacents; }
// ------------------------------------------------------------------------
/** Returns the vertices(Vec3) of this polygon. */
const std::vector<Vec3> getVertices();
// ------------------------------------------------------------------------
/** Returns the indices of the vertices of this polygon */
const std::vector<int> getVerticesIndex() const
{ return m_vertices; }
// ------------------------------------------------------------------------
/** Returns true if a given point lies in this polygon. */
bool pointInPoly(const Vec3& p,
bool ignore_vertical) const;
// ------------------------------------------------------------------------
/** Returns true if this polygon lies near the edge. */
bool isPolyNearEdge() const
{ return m_adjacents.size() < 4; }
// ------------------------------------------------------------------------
const Vec3& operator[](int i) const ;
}; // class NavPoly
#endif

View File

@ -17,16 +17,13 @@
// Foundation, Inc., 59 Temple Place - Suite 330, Boston, MA 02111-1307, USA.
#include "tracks/navmesh.hpp"
#include "tracks/nav_poly.hpp"
#include <algorithm>
#include <S3DVertex.h>
#include <triangle3d.h>
#include "LinearMath/btTransform.h"
#include "io/file_manager.hpp"
#include "io/xml_node.hpp"
#include "utils/string_utils.hpp"
#include "tracks/quad.hpp"
#include "utils/log.hpp"
#include <algorithm>
NavMesh *NavMesh::m_nav_mesh = NULL;
@ -39,78 +36,68 @@ NavMesh::NavMesh(const std::string &filename)
m_min = Vec3( 99999, 99999, 99999);
m_max = Vec3(-99999, -99999, -99999);
m_n_verts=0;
m_n_polys=0;
XMLNode *xml = file_manager->createXMLTree(filename);
if(xml->getName()!="navmesh")
if (xml->getName() != "navmesh")
{
Log::error("NavMesh", "NavMesh is invalid. \n");
delete xml;
Log::error("NavMesh", "NavMesh is invalid.");
delete xml;
return;
}
// Assigning m_nav_mesh here because constructing NavPoly requires m_nav_mesh to be defined
m_nav_mesh = this;
for(unsigned int i=0; i<xml->getNumNodes(); i++)
std::vector<Vec3> all_vertices;
for (unsigned int i = 0; i < xml->getNumNodes(); i++)
{
const XMLNode *xml_node = xml->getNode(i);
if(xml_node->getName()=="vertices")
if (xml_node->getName() == "vertices")
{
for(unsigned int i=0; i<xml_node->getNumNodes(); i++)
for (unsigned int i = 0; i < xml_node->getNumNodes(); i++)
{
const XMLNode *xml_node_node = xml_node->getNode(i);
if(!(xml_node_node->getName()=="vertex"))
if (!(xml_node_node->getName() == "vertex"))
{
Log::error("NavMesh", "Unsupported type '%s' found in '%s' - ignored. \n",
xml_node_node->getName().c_str(),filename.c_str());
Log::error("NavMesh", "Unsupported type '%s' found"
"in '%s' - ignored.",
xml_node_node->getName().c_str(), filename.c_str());
continue;
}
//Reading vertices
// Reading vertices
Vec3 p;
readVertex(xml_node_node, &p);
m_max.max(p);
m_min.min(p);
m_n_verts++;
m_verts.push_back(p);
all_vertices.push_back(p);
}
}
if(xml_node->getName()=="faces")
if (xml_node->getName() == "faces")
{
for(unsigned int i=0; i<xml_node->getNumNodes(); i++)
for(unsigned int i = 0; i < xml_node->getNumNodes(); i++)
{
const XMLNode *xml_node_node = xml_node->getNode(i);
if(xml_node_node->getName()!="face")
if (xml_node_node->getName() != "face")
{
Log::error("NavMesh", "Unsupported type '%s' found in '%s' - ignored. \n",
xml_node_node->getName().c_str(),filename.c_str());
Log::error("NavMesh", "Unsupported type '%s' found in '%s'"
" - ignored.",
xml_node_node->getName().c_str(), filename.c_str());
continue;
}
//Reading faces/polys
std::vector<int> polygonVertIndices;
std::vector<int> adjacentPolygonIndices;
xml_node_node->get("indices", &polygonVertIndices);
xml_node_node->get("adjacents", &adjacentPolygonIndices);
NavPoly *np = new NavPoly(polygonVertIndices, adjacentPolygonIndices);
m_polys.push_back(*np);
m_n_polys++;
// Reading quads
std::vector<int> quad_index;
std::vector<int> adjacent_quad_index;
xml_node_node->get("indices", &quad_index);
xml_node_node->get("adjacents", &adjacent_quad_index);
assert(quad_index.size() == 4);
m_adjacent_quads.push_back(adjacent_quad_index);
m_quads.push_back(new Quad(
all_vertices[quad_index[0]], all_vertices[quad_index[1]],
all_vertices[quad_index[2]], all_vertices[quad_index[3]]));
}
}
if(xml_node->getName()=="MaxVertsPerPoly")
{
xml_node->get("nvp", &m_nvp);
}
//delete xml_node;
}
delete xml;
} // NavMesh
@ -119,48 +106,14 @@ NavMesh::NavMesh(const std::string &filename)
NavMesh::~NavMesh()
{
for (unsigned int i = 0; i < m_quads.size(); i++)
{
delete m_quads[i];
}
m_quads.clear();
} // ~NavMesh
// ----------------------------------------------------------------------------
/** Sets the vertices in a irrlicht vertex array to the 4 points of this quad.
*/
void NavMesh::setVertices(int n, video::S3DVertex *v, const video::SColor &color) const
{
NavPoly poly = NavMesh::get()->getNavPoly(n);
const std::vector<Vec3>& p = poly.getVertices();
if (p.size() !=4) return;
// Eps is used to raise the track debug quads a little bit higher than
// the ground, so that they are actually visible.
core::vector3df eps(0, 0.1f, 0);
v[0].Pos = p[0].toIrrVector()+eps;
v[1].Pos = p[1].toIrrVector()+eps;
v[2].Pos = p[2].toIrrVector()+eps;
v[3].Pos = p[3].toIrrVector()+eps;
core::triangle3df tri(p[0].toIrrVector(), p[1].toIrrVector(),
p[2].toIrrVector());
core::vector3df normal = tri.getNormal();
normal.normalize();
v[0].Normal = normal;
v[1].Normal = normal;
v[2].Normal = normal;
core::triangle3df tri1(p[0].toIrrVector(), p[2].toIrrVector(),
p[3].toIrrVector());
core::vector3df normal1 = tri1.getNormal();
normal1.normalize();
v[3].Normal = normal1;
v[0].Color = color;
v[1].Color = color;
v[2].Color = color;
v[3].Color = color;
} // setVertices
// ----------------------------------------------------------------------------
/** Reads the vertex information from an XMLNode */
void NavMesh::readVertex(const XMLNode *xml, Vec3* result) const
{
@ -170,4 +123,11 @@ void NavMesh::readVertex(const XMLNode *xml, Vec3* result) const
xml->get("z", &z);
Vec3 temp(x, y, z);
*result = temp;
} // readVertex
} // readVertex
// ----------------------------------------------------------------------------
const Vec3& NavMesh::getCenterOfQuad(unsigned int n) const
{
assert(m_quads.size() > 0 && n < m_quads.size());
return m_quads[n]->getCenter();
} // getCenterOfQuad

View File

@ -19,144 +19,103 @@
#ifndef HEADER_NAVMESH_HPP
#define HEADER_NAVMESH_HPP
#include "tracks/nav_poly.hpp"
#include <vector>
#include <string>
#include <set>
#include "utils/vec3.hpp"
namespace irr
{
namespace video { struct S3DVertex; }
}
using namespace irr;
class btTransform;
class Quad;
class XMLNode;
/**
* \ingroup tracks
*
* \brief This class stores a set of navigatoin polygons. It uses a
* 'simplified singleton' design pattern: it has a static create function
* to create exactly one instance, a destroy function, and a get function
* (that does not have the side effect of the 'normal singleton' design
* pattern to create an instance). Besides saving on the if statement in get(),
* this is necessary since certain race modes might not have a navigaton
* mesh at all (e.g. race mode). So get() returns NULL in this case, and
* this is tested where necessary.
\ingroup tracks
*/
* \brief This class stores a set of navigation quads. It uses a
* 'simplified singleton' design pattern: it has a static create function
* to create exactly one instance, a destroy function, and a get function
* (that does not have the side effect of the 'normal singleton' design
* pattern to create an instance). Besides saving on the if statement in
* get(), this is necessary since certain race modes might not have a
* navigation mesh at all (e.g. race mode). So get() returns NULL in this
* case, and this is tested where necessary.
* \ingroup tracks
*/
class NavMesh
{
private:
static NavMesh *m_nav_mesh;
static NavMesh *m_nav_mesh;
/** The 2d bounding box, used for hashing. */
Vec3 m_min;
Vec3 m_max;
Vec3 m_min;
Vec3 m_max;
/** The actual set of nav polys that constitute the nav mesh */
std::vector<NavPoly> m_polys;
/** The actual set of quads that constitute the nav mesh */
std::vector<Quad*> m_quads;
/** The set of vertices that are part of this nav mesh*/
std::vector< Vec3 > m_verts;
/** Number of vertices */
unsigned int m_n_verts;
/** Number of polygons */
unsigned int m_n_polys;
/** Maximum vertices per polygon */
unsigned int m_nvp;
std::vector<std::vector<int>> m_adjacent_quads;
void readVertex(const XMLNode *xml, Vec3* result) const;
//void readFace(const XMLNode *xml, Vec3* result) const;
// ------------------------------------------------------------------------
NavMesh(const std::string &filename);
// ------------------------------------------------------------------------
~NavMesh();
public:
/** Creates a NavMesh instance. */
static void create(const std::string &filename)
{
assert(m_nav_mesh==NULL);
// m_nav_mesh assigned in the constructor because it needs to defined
// for NavPoly which is constructed in NavMesh()
new NavMesh(filename);
assert(m_nav_mesh == NULL);
m_nav_mesh = new NavMesh(filename);
}
// ------------------------------------------------------------------------
/** Cleans up the nav mesh. It is possible that this function is called
* even if no instance exists (e.g. in race). So it is not an
* error if there is no instance. */
* even if no instance exists (e.g. in race). So it is not an
* error if there is no instance.
*/
static void destroy()
{
if(m_nav_mesh)
{
delete m_nav_mesh;
m_nav_mesh = NULL;
}
if (m_nav_mesh)
{
delete m_nav_mesh;
m_nav_mesh = NULL;
}
}
// ------------------------------------------------------------------------
/** Returns the one instance of this object. It is possible that there
* is no instance created (e.g. in normal race, since it doesn't have
* a nav mesh), so we don't assert that an instance exist, and we
* also don't create one if it doesn't exists. */
static NavMesh *get() { return m_nav_mesh; }
* is no instance created (e.g. in normal race, since it doesn't have
* a nav mesh), so we don't assert that an instance exist, and we
* also don't create one if it doesn't exists.
*/
static NavMesh *get() { return m_nav_mesh; }
// ------------------------------------------------------------------------
/** Return the minimum and maximum coordinates of this navmesh. */
void getBoundingBox(Vec3 *min, Vec3 *max)
{ *min=m_min; *max=m_max; }
void getBoundingBox(Vec3 *min, Vec3 *max) { *min=m_min; *max=m_max; }
// ------------------------------------------------------------------------
/** Returns a const reference to a NavPoly */
const NavPoly& getNavPoly(int n) const
{ return m_polys[n]; }
// ------------------------------------------------------------------------
/** Returns a const reference to a vertex(Vec3) */
const Vec3& getVertex(int n) const
{ return m_verts[n]; }
// ------------------------------------------------------------------------
/** Sets the vertices in a irrlicht vertex array to
* the 4 points of a navpoly.
* \param n The number of a navpoly.
* \param v The vertex array in which to set the vertices.
* \param color The color to use for this quad.
*/
void setVertices(int n, video::S3DVertex *v,
const video::SColor &color) const;
// ------------------------------------------------------------------------
/** Returns a const reference to a vector containing all vertices */
const std::vector<Vec3>& getAllVertices() const
{ return m_verts; }
// ------------------------------------------------------------------------
/** Returns the total number of polys */
unsigned int getNumberOfPolys() const
{ return m_n_polys; }
// ------------------------------------------------------------------------
/** Returns the total number of vertices */
unsigned int getNumberOfVerts() const
{ return m_n_verts; }
// ------------------------------------------------------------------------
/** Returns maximum vertices per polygon */
unsigned int getMaxVertsPerPoly() const
{ return m_nvp; }
// ------------------------------------------------------------------------
/** Returns the center of a polygon */
const Vec3& getCenterOfPoly(int n) const
{return m_polys[n].getCenter();}
/** Returns a const reference to a quad */
const Quad& getQuad(unsigned int n) const
{
assert(m_quads.size() > 0 && n < m_quads.size());
return *(m_quads[n]);
}
// ------------------------------------------------------------------------
/** Returns a const referece to a vector containing the indices
* of polygons adjacent to a given polygon */
const std::vector<int>& getAdjacentPolys(int n) const
{return m_polys[n].getAdjacents();}
* of quads adjacent to a given quad
*/
const std::vector<int>& getAdjacentQuads(unsigned int n) const
{
assert(m_adjacent_quads.size() > 0 && n < m_adjacent_quads.size() &&
m_quads.size() == m_adjacent_quads.size());
return m_adjacent_quads[n];
}
// ------------------------------------------------------------------------
/** Returns a const reference to a vector containing the vertices
* of a given polygon. */
const std::vector<Vec3> getVertsOfPoly(int n)
{return m_polys[n].getVertices();}
/** Returns the total number of quads */
unsigned int getNumberOfQuads() const
{
assert(m_quads.size() > 0);
return m_quads.size();
}
// ------------------------------------------------------------------------
/** Returns the center of a quad */
const Vec3& getCenterOfQuad(unsigned int n) const;
};
#endif

View File

@ -88,7 +88,7 @@ void Quad::getVertices(video::S3DVertex *v, const video::SColor &color) const
} // setVertices
// ----------------------------------------------------------------------------
bool Quad::pointInQuad(const Vec3& p) const
bool Quad::pointInQuad(const Vec3& p, bool ignore_vertical) const
{
// In case that a kart can validly run too high over one driveline
// and it should not be considered to be on that driveline. Example:
@ -98,17 +98,21 @@ bool Quad::pointInQuad(const Vec3& p) const
// is taken into account, too. to simplify this test we only compare
// with the minimum height of the quad (and not with the actual
// height of the quad at the point where the kart is).
if(p.getY() - m_max_height > 5.0f ||
p.getY() - m_min_height < -1.0f )
if(!ignore_vertical &&
(p.getY() - m_max_height > 5.0f ||
p.getY() - m_min_height < -1.0f ))
return false;
// If a point is exactly on the line of two quads (e.g. between points
// 0,1 on one quad, and 3,2 of the previous quad), assign this point
// to be on the 'later' quad, i.e. on the line between points 0 and 1.
if(p.sideOfLine2D(m_p[0], m_p[2])<0) {
if(p.sideOfLine2D(m_p[0], m_p[2])<0)
{
return p.sideOfLine2D(m_p[0], m_p[1]) >= 0.0 &&
p.sideOfLine2D(m_p[1], m_p[2]) >= 0.0;
} else {
}
else
{
return p.sideOfLine2D(m_p[2], m_p[3]) > 0.0 &&
p.sideOfLine2D(m_p[3], m_p[0]) >= 0.0;
}

View File

@ -61,7 +61,7 @@ public:
Quad(const Vec3 &p0, const Vec3 &p1, const Vec3 &p2, const Vec3 &p3,
bool invis=false, bool ai_ignore=false);
void getVertices(video::S3DVertex *v, const video::SColor &color) const;
bool pointInQuad(const Vec3& p) const;
bool pointInQuad(const Vec3& p, bool ignore_vertical = false) const;
void transform(const btTransform &t, Quad *result) const;
// ------------------------------------------------------------------------
/** Returns the i-th. point of a quad. */

View File

@ -29,7 +29,6 @@
#include "utils/aligned_array.hpp"
class CheckLine;
class GraphStructure;
/**
* \brief This class stores a graph of quads. It uses a 'simplified singleton'
@ -85,9 +84,6 @@ private:
virtual const bool isNodeInvisible(int n) const
{ return m_all_nodes[n]->getQuad().isInvisible(); }
// ------------------------------------------------------------------------
virtual const bool isNodeInvalid(int n) const
{ return false; }
// ------------------------------------------------------------------------
virtual const bool hasLapLine() const
{ return true; }
// ------------------------------------------------------------------------