Modified file transfer to avoid multiple downloads
This commit is contained in:
parent
9eba707216
commit
66cd52b7e8
|
@ -0,0 +1,18 @@
|
|||
// Copyright (c) 2021 Computer Vision Center (CVC) at the Universitat Autonoma
|
||||
// de Barcelona (UAB).
|
||||
//
|
||||
// This work is licensed under the terms of the MIT license.
|
||||
// For a copy, see <https://opensource.org/licenses/MIT>.
|
||||
|
||||
#include "FileTransfer.h"
|
||||
namespace carla {
|
||||
namespace client {
|
||||
|
||||
#ifdef _WIN32
|
||||
std::string FileTransfer::_filesBaseFolder = std::string(getenv("USERPROFILE")) + "/carlaCache/";
|
||||
#else
|
||||
std::string FileTransfer::_filesBaseFolder = std::string(getenv("HOME")) + "/carlaCache/";
|
||||
#endif
|
||||
|
||||
} // namespace client
|
||||
} // namespace carla
|
|
@ -1,4 +1,3 @@
|
|||
|
||||
// Copyright (c) 2021 Computer Vision Center (CVC) at the Universitat Autonoma
|
||||
// de Barcelona (UAB).
|
||||
//
|
||||
|
@ -76,11 +75,5 @@ namespace client {
|
|||
|
||||
};
|
||||
|
||||
#ifdef _WIN32
|
||||
std::string FileTransfer::_filesBaseFolder = std::string(getenv("USERPROFILE")) + "/carlaCache/";
|
||||
#else
|
||||
std::string FileTransfer::_filesBaseFolder = std::string(getenv("HOME")) + "/carlaCache/";
|
||||
#endif
|
||||
|
||||
} // namespace client
|
||||
} // namespace carla
|
||||
|
|
|
@ -16,7 +16,7 @@
|
|||
|
||||
namespace carla {
|
||||
namespace client {
|
||||
|
||||
|
||||
static auto MakeMap(const std::string &opendrive_contents) {
|
||||
auto stream = std::istringstream(opendrive_contents);
|
||||
auto map = opendrive::OpenDriveParser::Load(stream.str());
|
||||
|
@ -26,15 +26,15 @@ namespace client {
|
|||
return std::move(*map);
|
||||
}
|
||||
|
||||
Map::Map(rpc::MapInfo description)
|
||||
Map::Map(rpc::MapInfo description, std::string xodr_content)
|
||||
: _description(std::move(description)),
|
||||
_map(MakeMap(_description.open_drive_file)) {}
|
||||
_map(MakeMap(xodr_content)){}
|
||||
|
||||
|
||||
Map::Map(std::string name, std::string xodr_content)
|
||||
: Map(rpc::MapInfo{
|
||||
std::move(name),
|
||||
std::move(xodr_content),
|
||||
std::vector<geom::Transform>{}}) {}
|
||||
std::vector<geom::Transform>{}}, xodr_content) {}
|
||||
|
||||
Map::~Map() = default;
|
||||
|
||||
|
|
|
@ -29,7 +29,7 @@ namespace client {
|
|||
private NonCopyable {
|
||||
public:
|
||||
|
||||
explicit Map(rpc::MapInfo description);
|
||||
explicit Map(rpc::MapInfo description, std::string xodr_content);
|
||||
|
||||
explicit Map(std::string name, std::string xodr_content);
|
||||
|
||||
|
@ -44,7 +44,7 @@ namespace client {
|
|||
}
|
||||
|
||||
const std::string &GetOpenDrive() const {
|
||||
return _description.open_drive_file;
|
||||
return open_drive_file;
|
||||
}
|
||||
|
||||
const std::vector<geom::Transform> &GetRecommendedSpawnPoints() const {
|
||||
|
@ -96,6 +96,8 @@ namespace client {
|
|||
|
||||
private:
|
||||
|
||||
std::string open_drive_file;
|
||||
|
||||
const rpc::MapInfo _description;
|
||||
|
||||
const road::Map _map;
|
||||
|
|
|
@ -169,6 +169,10 @@ namespace detail {
|
|||
return _pimpl->CallAndWait<rpc::MapInfo>("get_map_info");
|
||||
}
|
||||
|
||||
std::string Client::GetMapData() const{
|
||||
return _pimpl->CallAndWait<std::string>("get_map_data");
|
||||
}
|
||||
|
||||
std::vector<uint8_t> Client::GetNavigationMesh() const {
|
||||
return _pimpl->CallAndWait<std::vector<uint8_t>>("get_navigation_mesh");
|
||||
}
|
||||
|
|
|
@ -111,6 +111,8 @@ namespace detail {
|
|||
|
||||
std::vector<std::string> GetRequiredFiles(const std::string &folder = "", const bool download = true) const;
|
||||
|
||||
std::string GetMapData() const;
|
||||
|
||||
void RequestFile(const std::string &name) const;
|
||||
|
||||
std::vector<uint8_t> GetCacheFile(const std::string &name, const bool request_otherwise = true) const;
|
||||
|
|
|
@ -11,6 +11,7 @@
|
|||
#include "carla/Logging.h"
|
||||
#include "carla/RecurrentSharedFuture.h"
|
||||
#include "carla/client/BlueprintLibrary.h"
|
||||
#include "carla/client/FileTransfer.h"
|
||||
#include "carla/client/Map.h"
|
||||
#include "carla/client/Sensor.h"
|
||||
#include "carla/client/TimeoutException.h"
|
||||
|
@ -143,7 +144,7 @@ namespace detail {
|
|||
return true;
|
||||
}
|
||||
if (map_info.name != _cached_map->GetName() ||
|
||||
map_info.open_drive_file.size() != _cached_map->GetOpenDrive().size()) {
|
||||
_open_drive_file.size() != _cached_map->GetOpenDrive().size()) {
|
||||
return true;
|
||||
}
|
||||
return false;
|
||||
|
@ -153,7 +154,26 @@ namespace detail {
|
|||
DEBUG_ASSERT(_episode != nullptr);
|
||||
if (!_cached_map || _episode->HasMapChangedSinceLastCall()) {
|
||||
rpc::MapInfo map_info = _client.GetMapInfo();
|
||||
_cached_map = MakeShared<Map>(map_info);
|
||||
std::string map_name;
|
||||
std::string map_base_path;
|
||||
bool fill_base_string = false;
|
||||
for(int i = map_info.name.size() - 1; i >= 0; --i){
|
||||
if(fill_base_string == false && map_info.name[i] != '/'){
|
||||
map_name += map_info.name[i];
|
||||
}
|
||||
else {
|
||||
map_base_path += map_info.name[i];
|
||||
fill_base_string = true;
|
||||
}
|
||||
}
|
||||
std::reverse(map_name.begin(), map_name.end());
|
||||
std::reverse(map_base_path.begin(), map_base_path.end());
|
||||
std::string XODRFolder = map_base_path + "/OpenDrive/" + map_name + ".xodr";
|
||||
if(FileTransfer::FileExists(XODRFolder) == false){
|
||||
_client.GetRequiredFiles();
|
||||
_open_drive_file = _client.GetMapData();
|
||||
_cached_map = MakeShared<Map>(map_info, _open_drive_file);
|
||||
}
|
||||
}
|
||||
return _cached_map;
|
||||
}
|
||||
|
|
|
@ -665,6 +665,8 @@ namespace detail {
|
|||
const GarbageCollectionPolicy _gc_policy;
|
||||
|
||||
SharedPtr<Map> _cached_map;
|
||||
|
||||
std::string _open_drive_file;
|
||||
};
|
||||
|
||||
} // namespace detail
|
||||
|
|
|
@ -20,11 +20,9 @@ namespace rpc {
|
|||
|
||||
std::string name;
|
||||
|
||||
std::string open_drive_file;
|
||||
|
||||
std::vector<geom::Transform> recommended_spawn_points;
|
||||
|
||||
MSGPACK_DEFINE_ARRAY(name, open_drive_file, recommended_spawn_points);
|
||||
MSGPACK_DEFINE_ARRAY(name, recommended_spawn_points);
|
||||
};
|
||||
|
||||
} // namespace rpc
|
||||
|
|
|
@ -109,7 +109,6 @@ def apply_weather_values(args, weather):
|
|||
if args.miescatteringscale is not None:
|
||||
weather.mie_scattering_scale = args.miescatteringscale
|
||||
if args.rayleighscatteringscale is not None:
|
||||
print(weather.rayleigh_scattering_scale)
|
||||
weather.rayleigh_scattering_scale = args.rayleighscatteringscale
|
||||
|
||||
|
||||
|
@ -245,19 +244,19 @@ def main():
|
|||
type=float,
|
||||
help='Wetness intensity [0.0, 100.0]')
|
||||
argparser.add_argument(
|
||||
'--scatteringintensity',
|
||||
metavar='Si',
|
||||
'--scatteringintensity', '-si'
|
||||
metavar='si',
|
||||
default=None,
|
||||
type=float,
|
||||
help='Scattering intensity [0.0, inf]')
|
||||
argparser.add_argument(
|
||||
'--rayleighscatteringscale',
|
||||
'--rayleighscatteringscale', '-rss'
|
||||
metavar='rss',
|
||||
default=None,
|
||||
type=float,
|
||||
help='Rayleigh scattering scale [0.0, 2.0]')
|
||||
argparser.add_argument(
|
||||
'--miescatteringscale',
|
||||
'--miescatteringscale', '-mss'
|
||||
metavar='mss',
|
||||
default=None,
|
||||
type=float,
|
||||
|
|
|
@ -341,14 +341,21 @@ void FCarlaServer::FPimpl::BindActions()
|
|||
BIND_SYNC(get_map_info) << [this]() -> R<cr::MapInfo>
|
||||
{
|
||||
REQUIRE_CARLA_EPISODE();
|
||||
auto FileContents = UOpenDrive::GetXODR(Episode->GetWorld());
|
||||
const auto &SpawnPoints = Episode->GetRecommendedSpawnPoints();
|
||||
FString FullMapPath = FPaths::GetPath(UCarlaStatics::GetGameInstance(Episode->GetWorld())->GetMapPath());
|
||||
FString MapDir = FullMapPath.RightChop(FullMapPath.Find("Content/", ESearchCase::CaseSensitive) + 8);
|
||||
MapDir += "/" + Episode->GetMapName();
|
||||
return cr::MapInfo{
|
||||
cr::FromFString(Episode->GetMapName()),
|
||||
cr::FromLongFString(FileContents),
|
||||
cr::FromFString(MapDir),
|
||||
MakeVectorFromTArray<cg::Transform>(SpawnPoints)};
|
||||
};
|
||||
|
||||
BIND_SYNC(get_map_data) << [this]() -> R<std::string>
|
||||
{
|
||||
REQUIRE_CARLA_EPISODE();
|
||||
return cr::FromFString(UOpenDrive::GetXODR(Episode->GetWorld()));
|
||||
};
|
||||
|
||||
BIND_SYNC(get_navigation_mesh) << [this]() -> R<std::vector<uint8_t>>
|
||||
{
|
||||
REQUIRE_CARLA_EPISODE();
|
||||
|
|
Loading…
Reference in New Issue