fix: bots can't plant bomb on multi-scenario maps (fix #537)

This commit is contained in:
jeefo 2024-03-19 23:38:48 +03:00
commit c03d8ac790
No known key found for this signature in database
GPG key ID: 927BCA0779BEA8ED
3 changed files with 462 additions and 460 deletions

14
.gitattributes vendored
View file

@ -1,7 +1,7 @@
# Auto detect text files and perform LF normalization # Auto detect text files and perform LF normalization
* text=auto * text=lf
# Custom for Visual Studio # Custom for Visual Studio
*.sln merge=union *.sln merge=union
*.vcxproj merge=union *.vcxproj merge=union

View file

@ -1,449 +1,449 @@
// //
// YaPB, based on PODBot by Markus Klinge ("CountFloyd"). // YaPB, based on PODBot by Markus Klinge ("CountFloyd").
// Copyright © YaPB Project Developers <yapb@jeefo.net>. // Copyright © YaPB Project Developers <yapb@jeefo.net>.
// //
// SPDX-License-Identifier: MIT // SPDX-License-Identifier: MIT
// //
#include <yapb.h> #include <yapb.h>
#if defined (BOT_STORAGE_EXPLICIT_INSTANTIATIONS) #if defined (BOT_STORAGE_EXPLICIT_INSTANTIATIONS)
template <typename U> bool BotStorage::load (SmallArray <U> &data, ExtenHeader *exten, int32_t *outOptions) { template <typename U> bool BotStorage::load (SmallArray <U> &data, ExtenHeader *exten, int32_t *outOptions) {
auto type = guessType <U> (); auto type = guessType <U> ();
String filename = buildPath (storageToBotFile (type.option), true); String filename = buildPath (storageToBotFile (type.option), true);
extern ConVar cv_debug, cv_graph_url; extern ConVar cv_debug, cv_graph_url;
// graphs can be downloaded... // graphs can be downloaded...
const auto isGraph = !!(type.option & StorageOption::Graph); const auto isGraph = !!(type.option & StorageOption::Graph);
const auto isDebug = cv_debug.bool_ (); const auto isDebug = cv_debug.bool_ ();
MemFile file (filename); // open the file MemFile file (filename); // open the file
data.clear (); data.clear ();
// resize data to fit the stuff // resize data to fit the stuff
auto resizeData = [&] (const size_t length) { auto resizeData = [&] (const size_t length) {
data.resize (length); // for non-graph data the graph should be already loaded data.resize (length); // for non-graph data the graph should be already loaded
data.shrink (); // free up memory to minimum data.shrink (); // free up memory to minimum
// ensure we're have enough memory to decompress the data // ensure we're have enough memory to decompress the data
data.ensure (length + ULZ::Excess); data.ensure (length + ULZ::Excess);
}; };
// if graph & attempted to load multiple times, bail out, we're failed // if graph & attempted to load multiple times, bail out, we're failed
if (isGraph && ++m_retries > 2) { if (isGraph && ++m_retries > 2) {
resetRetries (); resetRetries ();
return error (isGraph, isDebug, file, "Unable to load %s (filename: '%s'). Download process has failed as well. No nodes has been found.", type.name, filename); return error (isGraph, isDebug, file, "Unable to load %s (filename: '%s'). Download process has failed as well. No nodes has been found.", type.name, filename);
} }
// downloader for graph // downloader for graph
auto download = [&] () -> bool { auto download = [&] () -> bool {
if (!graph.canDownload ()) { if (!graph.canDownload ()) {
return false; return false;
} }
String lowercaseMapName = game.getMapName (); String lowercaseMapName = game.getMapName ();
lowercaseMapName = lowercaseMapName.lowercase (); lowercaseMapName = lowercaseMapName.lowercase ();
auto downloadAddress = cv_graph_url.str (); auto downloadAddress = cv_graph_url.str ();
auto toDownload = buildPath (storageToBotFile (type.option), false); auto toDownload = buildPath (storageToBotFile (type.option), false);
auto fromDownload = strings.format ("%s://%s/graph/%s.graph", product.httpScheme, downloadAddress, lowercaseMapName); auto fromDownload = strings.format ("%s://%s/graph/%s.graph", product.httpScheme, downloadAddress, lowercaseMapName);
// try to download // try to download
if (http.downloadFile (fromDownload, toDownload)) { if (http.downloadFile (fromDownload, toDownload)) {
ctrl.msg ("%s file '%s' successfully downloaded. Processing...", type.name, filename); ctrl.msg ("%s file '%s' successfully downloaded. Processing...", type.name, filename);
return true; return true;
} }
else { else {
ctrl.msg ("Can't download '%s' from '%s' to '%s'... (%d).", filename, fromDownload, toDownload, http.getLastStatusCode ()); ctrl.msg ("Can't download '%s' from '%s' to '%s'... (%d).", filename, fromDownload, toDownload, http.getLastStatusCode ());
} }
return false; return false;
}; };
// tries to reload or open pwf file // tries to reload or open pwf file
auto tryReload = [&] () -> bool { auto tryReload = [&] () -> bool {
file.close (); file.close ();
if (!isGraph) { if (!isGraph) {
return false; return false;
} }
if (download ()) { if (download ()) {
return load (data, exten, outOptions); return load (data, exten, outOptions);
} }
if (graph.convertOldFormat ()) { if (graph.convertOldFormat ()) {
return load (data, exten, outOptions); return load (data, exten, outOptions);
} }
return false; return false;
}; };
// no open no fun // no open no fun
if (!file) { if (!file) {
if (tryReload ()) { if (tryReload ()) {
return true; return true;
} }
return error (isGraph, isDebug, file, "Unable to open %s file for reading (filename: '%s').", type.name, filename); return error (isGraph, isDebug, file, "Unable to open %s file for reading (filename: '%s').", type.name, filename);
} }
// read the header // read the header
StorageHeader hdr {}; StorageHeader hdr {};
file.read (&hdr, sizeof (StorageHeader)); file.read (&hdr, sizeof (StorageHeader));
// check the magic // check the magic
if (hdr.magic != kStorageMagic && hdr.magic != kStorageMagicUB) { if (hdr.magic != kStorageMagic && hdr.magic != kStorageMagicUB) {
if (tryReload ()) { if (tryReload ()) {
return true; return true;
} }
return error (isGraph, isDebug, file, "Unable to read magic of %s (filename: '%s').", type.name, filename); return error (isGraph, isDebug, file, "Unable to read magic of %s (filename: '%s').", type.name, filename);
} }
// check the path-numbers // check the path-numbers
if (!isGraph && hdr.length != graph.length ()) { if (!isGraph && hdr.length != graph.length ()) {
return error (isGraph, isDebug, file, "Damaged %s (filename: '%s'). Mismatch number of nodes (got: '%d', need: '%d').", type.name, filename, hdr.length, graph.length ()); return error (isGraph, isDebug, file, "Damaged %s (filename: '%s'). Mismatch number of nodes (got: '%d', need: '%d').", type.name, filename, hdr.length, graph.length ());
} }
// check the count // check the count
if (hdr.length == 0 || hdr.length > kMaxNodes || hdr.length < kMaxNodeLinks) { if (hdr.length == 0 || hdr.length > kMaxNodes || hdr.length < kMaxNodeLinks) {
if (tryReload ()) { if (tryReload ()) {
return true; return true;
} }
return error (isGraph, isDebug, file, "Damaged %s (filename: '%s'). Paths length is overflowed (got: '%d').", type.name, filename, hdr.length); return error (isGraph, isDebug, file, "Damaged %s (filename: '%s'). Paths length is overflowed (got: '%d').", type.name, filename, hdr.length);
} }
// check the version // check the version
if (hdr.version > type.version && isGraph) { if (hdr.version > type.version && isGraph) {
ctrl.msg ("Graph version mismatch %s (filename: '%s'). Version number differs (got: '%d', need: '%d') Please, upgrade %s.", type.name, filename, hdr.version, type.version, product.name); ctrl.msg ("Graph version mismatch %s (filename: '%s'). Version number differs (got: '%d', need: '%d') Please, upgrade %s.", type.name, filename, hdr.version, type.version, product.name);
} }
else if (hdr.version != type.version && !isGraph) { else if (hdr.version != type.version && !isGraph) {
return error (isGraph, isDebug, file, "Damaged %s (filename: '%s'). Version number differs (got: '%d', need: '%d').", type.name, filename, hdr.version, type.version); return error (isGraph, isDebug, file, "Damaged %s (filename: '%s'). Version number differs (got: '%d', need: '%d').", type.name, filename, hdr.version, type.version);
} }
// save graph version // save graph version
if (isGraph) { if (isGraph) {
graph.setGraphHeader (&hdr); graph.setGraphHeader (&hdr);
} }
// check the storage type // check the storage type
if ((hdr.options & type.option) != type.option) { if ((hdr.options & type.option) != type.option) {
return error (isGraph, isDebug, file, "Incorrect storage format for %s (filename: '%s').", type.name, filename); return error (isGraph, isDebug, file, "Incorrect storage format for %s (filename: '%s').", type.name, filename);
} }
const auto compressedSize = static_cast <size_t> (hdr.compressed); const auto compressedSize = static_cast <size_t> (hdr.compressed);
const auto numberNodes = static_cast <size_t> (hdr.length); const auto numberNodes = static_cast <size_t> (hdr.length);
SmallArray <uint8_t> compressed (compressedSize + sizeof (uint8_t) * ULZ::Excess); SmallArray <uint8_t> compressed (compressedSize + sizeof (uint8_t) * ULZ::Excess);
// graph is not resized upon load // graph is not resized upon load
if (isGraph) { if (isGraph) {
resizeData (numberNodes); resizeData (numberNodes);
} }
else { else {
resizeData (hdr.uncompressed / sizeof (U)); resizeData (hdr.uncompressed / sizeof (U));
} }
// read compressed data // read compressed data
if (file.read (compressed.data (), sizeof (uint8_t), compressedSize) == compressedSize) { if (file.read (compressed.data (), sizeof (uint8_t), compressedSize) == compressedSize) {
// try to uncompress // try to uncompress
if (ulz.uncompress (compressed.data (), hdr.compressed, reinterpret_cast <uint8_t *> (data.data ()), hdr.uncompressed) == ULZ::UncompressFailure) { if (ulz.uncompress (compressed.data (), hdr.compressed, reinterpret_cast <uint8_t *> (data.data ()), hdr.uncompressed) == ULZ::UncompressFailure) {
return error (isGraph, isDebug, file, "Unable to decompress ULZ data for %s (filename: '%s').", type.name, filename); return error (isGraph, isDebug, file, "Unable to decompress ULZ data for %s (filename: '%s').", type.name, filename);
} }
else { else {
if (outOptions) { if (outOptions) {
outOptions = &hdr.options; outOptions = &hdr.options;
} }
// author of graph.. save // author of graph.. save
if ((hdr.options & StorageOption::Exten) && exten != nullptr) { if ((hdr.options & StorageOption::Exten) && exten != nullptr) {
const auto extenSize = sizeof (ExtenHeader); const auto extenSize = sizeof (ExtenHeader);
const auto actuallyRead = file.read (exten, extenSize) * extenSize; const auto actuallyRead = file.read (exten, extenSize) * extenSize;
if (isGraph) { if (isGraph) {
resetRetries (); resetRetries ();
ExtenHeader extenHeader; ExtenHeader extenHeader;
strings.copy (extenHeader.author, exten->author, cr::bufsize (exten->author)); strings.copy (extenHeader.author, exten->author, cr::bufsize (exten->author));
if (extenSize <= actuallyRead) { if (extenSize <= actuallyRead) {
// write modified by, only if the name is different // write modified by, only if the name is different
if (!strings.isEmpty (extenHeader.author) if (!strings.isEmpty (extenHeader.author)
&& strncmp (extenHeader.author, exten->modified, cr::bufsize (extenHeader.author)) != 0) { && strncmp (extenHeader.author, exten->modified, cr::bufsize (extenHeader.author)) != 0) {
strings.copy (extenHeader.modified, exten->modified, cr::bufsize (exten->modified)); strings.copy (extenHeader.modified, exten->modified, cr::bufsize (exten->modified));
} }
} }
else { else {
strings.copy (extenHeader.modified, "(none)", cr::bufsize (exten->modified)); strings.copy (extenHeader.modified, "(none)", cr::bufsize (exten->modified));
} }
extenHeader.mapSize = exten->mapSize; extenHeader.mapSize = exten->mapSize;
// tell graph about exten header // tell graph about exten header
graph.setExtenHeader (&extenHeader); graph.setExtenHeader (&extenHeader);
} }
} }
ctrl.msg ("Loaded Bots %s data v%d (Memory: %.2fMB).", type.name, hdr.version, static_cast <float> (data.capacity () * sizeof (U)) / 1024.0f / 1024.0f); ctrl.msg ("Loaded Bots %s data v%d (Memory: %.2fMB).", type.name, hdr.version, static_cast <float> (data.capacity () * sizeof (U)) / 1024.0f / 1024.0f);
file.close (); file.close ();
return true; return true;
} }
} }
else { else {
return error (isGraph, isDebug, file, "Unable to read ULZ data for %s (filename: '%s').", type.name, filename); return error (isGraph, isDebug, file, "Unable to read ULZ data for %s (filename: '%s').", type.name, filename);
} }
return false; return false;
} }
template <typename U> bool BotStorage::save (const SmallArray <U> &data, ExtenHeader *exten, int32_t passOptions) { template <typename U> bool BotStorage::save (const SmallArray <U> &data, ExtenHeader *exten, int32_t passOptions) {
auto type = guessType <U> (); auto type = guessType <U> ();
// append additional options // append additional options
if (passOptions != 0) { if (passOptions != 0) {
type.option |= passOptions; type.option |= passOptions;
} }
const auto isGraph = !!(type.option & StorageOption::Graph); const auto isGraph = !!(type.option & StorageOption::Graph);
// do not allow to save graph with less than 8 nodes // do not allow to save graph with less than 8 nodes
if (isGraph && graph.length () < kMaxNodeLinks) { if (isGraph && graph.length () < kMaxNodeLinks) {
ctrl.msg ("Can't save graph data with less than %d nodes. Please add some more before saving.", kMaxNodeLinks); ctrl.msg ("Can't save graph data with less than %d nodes. Please add some more before saving.", kMaxNodeLinks);
return false; return false;
} }
String filename = buildPath (storageToBotFile (type.option)); String filename = buildPath (storageToBotFile (type.option));
if (data.empty ()) { if (data.empty ()) {
logger.error ("Unable to save %s file. Empty data. (filename: '%s').", type.name, filename); logger.error ("Unable to save %s file. Empty data. (filename: '%s').", type.name, filename);
return false; return false;
} }
else if (isGraph) { else if (isGraph) {
for (auto &path : graph) { for (auto &path : graph) {
path.display = 0.0f; path.display = 0.0f;
path.light = illum.getLightLevel (path.origin); path.light = illum.getLightLevel (path.origin);
} }
} }
// open the file // open the file
File file (filename, "wb"); File file (filename, "wb");
// no open no fun // no open no fun
if (!file) { if (!file) {
logger.error ("Unable to open %s file for writing (filename: '%s').", type.name, filename); logger.error ("Unable to open %s file for writing (filename: '%s').", type.name, filename);
return false; return false;
} }
const auto rawLength = data.length () * sizeof (U); const auto rawLength = data.length () * sizeof (U);
SmallArray <uint8_t> compressed (rawLength + sizeof (uint8_t) * ULZ::Excess); SmallArray <uint8_t> compressed (rawLength + sizeof (uint8_t) * ULZ::Excess);
// try to compress // try to compress
const auto compressedLength = static_cast <size_t> (ulz.compress (reinterpret_cast <uint8_t *> (data.data ()), static_cast <int32_t> (rawLength), reinterpret_cast <uint8_t *> (compressed.data ()))); const auto compressedLength = static_cast <size_t> (ulz.compress (reinterpret_cast <uint8_t *> (data.data ()), static_cast <int32_t> (rawLength), reinterpret_cast <uint8_t *> (compressed.data ())));
if (compressedLength > 0) { if (compressedLength > 0) {
StorageHeader hdr {}; StorageHeader hdr {};
hdr.magic = kStorageMagic; hdr.magic = kStorageMagic;
hdr.version = type.version; hdr.version = type.version;
hdr.options = type.option; hdr.options = type.option;
hdr.length = graph.length (); hdr.length = graph.length ();
hdr.compressed = static_cast <int32_t> (compressedLength); hdr.compressed = static_cast <int32_t> (compressedLength);
hdr.uncompressed = static_cast <int32_t> (rawLength); hdr.uncompressed = static_cast <int32_t> (rawLength);
file.write (&hdr, sizeof (StorageHeader)); file.write (&hdr, sizeof (StorageHeader));
file.write (compressed.data (), sizeof (uint8_t), compressedLength); file.write (compressed.data (), sizeof (uint8_t), compressedLength);
// add extension // add extension
if ((type.option & StorageOption::Exten) && exten != nullptr) { if ((type.option & StorageOption::Exten) && exten != nullptr) {
file.write (exten, sizeof (ExtenHeader)); file.write (exten, sizeof (ExtenHeader));
} }
extern ConVar cv_debug; extern ConVar cv_debug;
// notify only about graph // notify only about graph
if (isGraph || cv_debug.bool_ ()) { if (isGraph || cv_debug.bool_ ()) {
ctrl.msg ("Successfully saved Bots %s data.", type.name); ctrl.msg ("Successfully saved Bots %s data.", type.name);
} }
} }
else { else {
logger.error ("Unable to compress %s data (filename: '%s').", type.name, filename); logger.error ("Unable to compress %s data (filename: '%s').", type.name, filename);
return false; return false;
} }
return true; return true;
} }
template <typename ...Args> bool BotStorage::error (bool isGraph, bool isDebug, MemFile &file, const char *fmt, Args &&...args) { template <typename ...Args> bool BotStorage::error (bool isGraph, bool isDebug, MemFile &file, const char *fmt, Args &&...args) {
auto result = strings.format (fmt, cr::forward <Args> (args)...); auto result = strings.format (fmt, cr::forward <Args> (args)...);
// display error only for graph file // display error only for graph file
if (isGraph || isDebug) { if (isGraph || isDebug) {
logger.error (result); logger.error (result);
} }
// if graph reset paths // if graph reset paths
if (isGraph) { if (isGraph) {
bots.kickEveryone (true); bots.kickEveryone (true);
graph.reset (); graph.reset ();
} }
file.close (); file.close ();
return false; return false;
} }
template <typename U> BotStorage::SaveLoadData BotStorage::guessType () { template <typename U> BotStorage::SaveLoadData BotStorage::guessType () {
if constexpr (cr::is_same <U, FloydWarshallAlgo::Matrix>::value) { if constexpr (cr::is_same <U, FloydWarshallAlgo::Matrix>::value) {
return { "Pathmatrix", StorageOption::Matrix, StorageVersion::Matrix }; return { "Pathmatrix", StorageOption::Matrix, StorageVersion::Matrix };
} }
else if constexpr (cr::is_same <U, BotPractice::DangerSaveRestore>::value) { else if constexpr (cr::is_same <U, BotPractice::DangerSaveRestore>::value) {
return { "Practice", StorageOption::Practice, StorageVersion::Practice }; return { "Practice", StorageOption::Practice, StorageVersion::Practice };
} }
else if constexpr (cr::is_same <U, GraphVistable::VisStorage>::value) { else if constexpr (cr::is_same <U, GraphVistable::VisStorage>::value) {
return { "Vistable", StorageOption::Vistable, StorageVersion::Vistable }; return { "Vistable", StorageOption::Vistable, StorageVersion::Vistable };
} }
else if constexpr (cr::is_same <U, Path>::value) { else if constexpr (cr::is_same <U, Path>::value) {
return { "Graph", StorageOption::Graph, StorageVersion::Graph }; return { "Graph", StorageOption::Graph, StorageVersion::Graph };
} }
} }
#else #else
String BotStorage::buildPath (int32_t file, bool isMemoryLoad, bool withoutMapName) { String BotStorage::buildPath (int32_t file, bool isMemoryLoad, bool withoutMapName) {
using FilePath = Twin <String, String>; using FilePath = Twin <String, String>;
static HashMap <int32_t, FilePath> paths = { static HashMap <int32_t, FilePath> paths = {
{ BotFile::Vistable, FilePath (folders.train, "vis")}, { BotFile::Vistable, FilePath (folders.train, "vis")},
{ BotFile::Practice, FilePath (folders.train, "prc")}, { BotFile::Practice, FilePath (folders.train, "prc")},
{ BotFile::Pathmatrix, FilePath (folders.train, "pmx")}, { BotFile::Pathmatrix, FilePath (folders.train, "pmx")},
{ BotFile::LogFile, FilePath (folders.logs, "txt")}, { BotFile::LogFile, FilePath (folders.logs, "txt")},
{ BotFile::Graph, FilePath (folders.graph, "graph")}, { BotFile::Graph, FilePath (folders.graph, "graph")},
{ BotFile::PodbotPWF, FilePath (folders.podbot, "pwf")}, { BotFile::PodbotPWF, FilePath (folders.podbot, "pwf")},
{ BotFile::EbotEWP, FilePath (folders.ebot, "ewp")}, { BotFile::EbotEWP, FilePath (folders.ebot, "ewp")},
}; };
static StringArray path; static StringArray path;
path.clear (); path.clear ();
// if not memory file we're don't need game dir // if not memory file we're don't need game dir
if (isMemoryLoad) { if (isMemoryLoad) {
path.emplace (getRunningPathVFS ()); path.emplace (getRunningPathVFS ());
} }
else { else {
path.emplace (getRunningPath ()); path.emplace (getRunningPath ());
} }
// the datadir // the datadir
path.emplace (folders.data); path.emplace (folders.data);
// append real filepath // append real filepath
path.emplace (paths[file].first); path.emplace (paths[file].first);
// if file is logfile use correct logfile name with date // if file is logfile use correct logfile name with date
if (file == BotFile::LogFile) { if (file == BotFile::LogFile) {
time_t ticks = time (&ticks); time_t ticks = time (&ticks);
tm timeinfo {}; tm timeinfo {};
plat.loctime (&timeinfo, &ticks); plat.loctime (&timeinfo, &ticks);
auto timebuf = strings.chars (); auto timebuf = strings.chars ();
strftime (timebuf, StringBuffer::StaticBufferSize, "L%d%m%Y", &timeinfo); strftime (timebuf, StringBuffer::StaticBufferSize, "L%d%m%Y", &timeinfo);
path.emplace (strings.format ("%s_%s.%s", product.nameLower, timebuf, paths[file].second)); path.emplace (strings.format ("%s_%s.%s", product.nameLower, timebuf, paths[file].second));
} }
else if (!withoutMapName) { else if (!withoutMapName) {
String mapName = game.getMapName (); String mapName = game.getMapName ();
path.emplace (strings.format ("%s.%s", mapName.lowercase (), paths[file].second)); path.emplace (strings.format ("%s.%s", mapName.lowercase (), paths[file].second));
} }
// finally use correct path separators for us // finally use correct path separators for us
return String::join (path, kPathSeparator); return String::join (path, kPathSeparator);
} }
int32_t BotStorage::storageToBotFile (int32_t options) { int32_t BotStorage::storageToBotFile (int32_t options) {
// converts storage option to storage filename // converts storage option to storage filename
if (options & StorageOption::Graph) { if (options & StorageOption::Graph) {
return BotFile::Graph; return BotFile::Graph;
} }
else if (options & StorageOption::Matrix) { else if (options & StorageOption::Matrix) {
return BotFile::Pathmatrix; return BotFile::Pathmatrix;
} }
else if (options & StorageOption::Vistable) { else if (options & StorageOption::Vistable) {
return BotFile::Vistable; return BotFile::Vistable;
} }
else if (options & StorageOption::Practice) { else if (options & StorageOption::Practice) {
return BotFile::Practice; return BotFile::Practice;
} }
return BotFile::Graph; return BotFile::Graph;
} }
void BotStorage::unlinkFromDisk () { void BotStorage::unlinkFromDisk () {
// this function removes graph file from the hard disk // this function removes graph file from the hard disk
StringArray unlinkable; StringArray unlinkable;
bots.kickEveryone (true); bots.kickEveryone (true);
// if we're delete graph, delete all corresponding to it files // if we're delete graph, delete all corresponding to it files
unlinkable.emplace (buildPath (BotFile::Graph)); // graph itself unlinkable.emplace (buildPath (BotFile::Graph)); // graph itself
unlinkable.emplace (buildPath (BotFile::Practice)); // corresponding to practice unlinkable.emplace (buildPath (BotFile::Practice)); // corresponding to practice
unlinkable.emplace (buildPath (BotFile::Vistable)); // corresponding to vistable unlinkable.emplace (buildPath (BotFile::Vistable)); // corresponding to vistable
unlinkable.emplace (buildPath (BotFile::Pathmatrix)); // corresponding to matrix unlinkable.emplace (buildPath (BotFile::Pathmatrix)); // corresponding to matrix
for (const auto &item : unlinkable) { for (const auto &item : unlinkable) {
if (plat.fileExists (item.chars ())) { if (plat.fileExists (item.chars ())) {
plat.removeFile (item.chars ()); plat.removeFile (item.chars ());
ctrl.msg ("File %s, has been deleted from the hard disk", item); ctrl.msg ("File %s, has been deleted from the hard disk", item);
} }
else { else {
logger.error ("Unable to open %s", item); logger.error ("Unable to open %s", item);
} }
} }
graph.reset (); // re-initialize points graph.reset (); // re-initialize points
} }
StringRef BotStorage::getRunningPath () { StringRef BotStorage::getRunningPath () {
// this function get's relative path against bot library (bot library should reside in bin dir) // this function get's relative path against bot library (bot library should reside in bin dir)
static String path; static String path;
// we're do not do relative (against bot's library) paths on android // we're do not do relative (against bot's library) paths on android
if (plat.android) { if (plat.android) {
if (path.empty ()) { if (path.empty ()) {
path = strings.joinPath (game.getRunningModName (), folders.addons, folders.bot); path = strings.joinPath (game.getRunningModName (), folders.addons, folders.bot);
} }
return path; return path;
} }
// compute the full path to the our folder // compute the full path to the our folder
if (path.empty ()) { if (path.empty ()) {
path = SharedLibrary::path (&bstor); path = SharedLibrary::path (&bstor);
if (path.startsWith ("<unk")) { if (path.startsWith ("<unk")) {
logger.fatal ("Unable to detect library path. Giving up..."); logger.fatal ("Unable to detect library path. Giving up...");
} }
auto parts = path.substr (1).split (kPathSeparator); auto parts = path.substr (1).split (kPathSeparator);
parts.pop (); // remove library name parts.pop (); // remove library name
parts.pop (); // remove bin directory parts.pop (); // remove bin directory
path = path.substr (0, 1) + String::join (parts, kPathSeparator); path = path.substr (0, 1) + String::join (parts, kPathSeparator);
} }
return path; return path;
} }
StringRef BotStorage::getRunningPathVFS () { StringRef BotStorage::getRunningPathVFS () {
static String path; static String path;
// we're do not do relative (against bot's library) paths on android // we're do not do relative (against bot's library) paths on android
if (plat.android) { if (plat.android) {
if (path.empty ()) { if (path.empty ()) {
path = strings.joinPath (folders.addons, folders.bot); path = strings.joinPath (folders.addons, folders.bot);
} }
return path; return path;
} }
if (path.empty ()) { if (path.empty ()) {
path = getRunningPath (); path = getRunningPath ();
path = path.substr (path.find (game.getRunningModName ())); // skip to the game dir path = path.substr (path.find (game.getRunningModName ())); // skip to the game dir
path = path.substr (path.find (kPathSeparator) + 1); // skip the game dir path = path.substr (path.find (kPathSeparator) + 1); // skip the game dir
} }
return path; return path;
} }
#endif // BOT_STORAGE_EXPLICIT_INSTANTIATIONS #endif // BOT_STORAGE_EXPLICIT_INSTANTIATIONS

View file

@ -126,7 +126,7 @@ void Bot::normal_ () {
// don't allow vip on as_ maps to camp + don't allow terrorist carrying c4 to camp // don't allow vip on as_ maps to camp + don't allow terrorist carrying c4 to camp
if (campingAllowed if (campingAllowed
&& (m_isVIP || (game.mapIs (MapFlags::Demolition)&& m_team == Team::Terrorist && !bots.isBombPlanted () && m_hasC4))) { && (m_isVIP || (game.mapIs (MapFlags::Demolition) && m_team == Team::Terrorist && !bots.isBombPlanted () && m_hasC4))) {
campingAllowed = false; campingAllowed = false;
} }
@ -180,9 +180,9 @@ void Bot::normal_ () {
// and reached a rescue point? // and reached a rescue point?
if (m_pathFlags & NodeFlag::Rescue) { if (m_pathFlags & NodeFlag::Rescue) {
m_hostages.clear (); m_hostages.clear ();
} }
} }
else if (m_team == Team::Terrorist && rg.chance (75)) { else if (m_team == Team::Terrorist && rg.chance (75) && !game.mapIs (MapFlags::Demolition)) {
const int index = findDefendNode (m_path->origin); const int index = findDefendNode (m_path->origin);
startTask (Task::Camp, TaskPri::Camp, kInvalidNodeIndex, game.time () + rg.get (60.0f, 120.0f), true); // push camp task on to stack startTask (Task::Camp, TaskPri::Camp, kInvalidNodeIndex, game.time () + rg.get (60.0f, 120.0f), true); // push camp task on to stack
@ -193,7 +193,9 @@ void Bot::normal_ () {
pushChatterMessage (Chatter::GoingToGuardVIPSafety); // play info about that pushChatterMessage (Chatter::GoingToGuardVIPSafety); // play info about that
} }
} }
else if (game.mapIs (MapFlags::Demolition) && ((m_pathFlags & NodeFlag::Goal) && m_inBombZone)) {
// was elseif here but brokes csde_ scenario
if (game.mapIs (MapFlags::Demolition) && (m_pathFlags & NodeFlag::Goal) && m_inBombZone) {
// is it a terrorist carrying the bomb? // is it a terrorist carrying the bomb?
if (m_hasC4) { if (m_hasC4) {
if ((m_states & Sense::SeeingEnemy) && numFriendsNear (pev->origin, 768.0f) == 0) { if ((m_states & Sense::SeeingEnemy) && numFriendsNear (pev->origin, 768.0f) == 0) {