Added fast conversion from/to FString and std::string.

This commit is contained in:
Axel1092 2020-05-28 16:43:26 +02:00 committed by Marc Garcia Puig
parent 3e8e6dc4de
commit d26f69957f
6 changed files with 21 additions and 9 deletions

View File

@ -17,9 +17,20 @@ namespace rpc {
#ifdef LIBCARLA_INCLUDED_FROM_UE4
// Fast conversion from fstring
static inline std::string FromFString(const FString &Str) {
return TCHAR_TO_UTF8(*Str);
}
// Fast conversion to fstring
static inline FString ToFString(const std::string &str) {
return FString(str.size(), UTF8_TO_TCHAR(str.c_str()));
}
constexpr size_t MaxStringLength = 5000000;
static inline std::string FromFString(const FString &Str) {
// Slower conversion from fstring for long text
static inline std::string FromLongFString(const FString &Str) {
std::string result;
size_t i = 0;
while(i + MaxStringLength < Str.Len()) {
@ -34,7 +45,8 @@ namespace rpc {
return result;
}
static inline FString ToFString(const std::string &str) {
// Slower conversion to fstring for long text
static inline FString ToLongFString(const std::string &str) {
FString result = "";
size_t i = 0;
while(i + MaxStringLength < str.size()) {

View File

@ -141,7 +141,7 @@ bool UCarlaEpisode::LoadNewOpendriveEpisode(
// Build the Map from the OpenDRIVE data
const auto CarlaMap = carla::opendrive::OpenDriveParser::Load(
carla::rpc::FromFString(OpenDriveString));
carla::rpc::FromLongFString(OpenDriveString));
// Check the Map is correclty generated
if (!CarlaMap.has_value())
@ -160,7 +160,7 @@ bool UCarlaEpisode::LoadNewOpendriveEpisode(
// Store the OBJ string to a file in order to that RecastBuilder can load it
FFileHelper::SaveStringToFile(
carla::rpc::ToFString(RecastOBJ),
carla::rpc::ToLongFString(RecastOBJ),
*AbsoluteOBJPath,
FFileHelper::EEncodingOptions::ForceUTF8,
&IFileManager::Get());

View File

@ -196,7 +196,7 @@ void ACarlaGameModeBase::ParseOpenDrive(const FString &MapName)
{
if(!UCarlaStatics::GetGameInstance(Episode->GetWorld())->IsLevelPendingLoad())
{
std::string opendrive_xml = carla::rpc::FromFString(UOpenDrive::LoadXODR(MapName));
std::string opendrive_xml = carla::rpc::FromLongFString(UOpenDrive::LoadXODR(MapName));
Map = carla::opendrive::OpenDriveParser::Load(opendrive_xml);
if (!Map.has_value()) {
UE_LOG(LogCarla, Error, TEXT("Invalid Map"));

View File

@ -138,7 +138,7 @@ void AOpenDriveActor::BuildRoutes(FString MapName)
// xodr file using the lavel name and the game content directory.
const FString XodrContent = UOpenDrive::LoadXODR(MapName);
auto map = carla::opendrive::OpenDriveParser::Load(carla::rpc::FromFString(XodrContent));
auto map = carla::opendrive::OpenDriveParser::Load(carla::rpc::FromLongFString(XodrContent));
if (!map.has_value())
{

View File

@ -55,7 +55,7 @@ UOpenDriveMap::UOpenDriveMap(const FObjectInitializer &ObjectInitializer)
bool UOpenDriveMap::Load(const FString &XODRContent)
{
auto ResultMap = carla::opendrive::OpenDriveParser::Load(
carla::rpc::FromFString(XODRContent));
carla::rpc::FromLongFString(XODRContent));
if (ResultMap)
{
Map = std::move(*ResultMap);

View File

@ -259,7 +259,7 @@ void FCarlaServer::FPimpl::BindActions()
BIND_SYNC(copy_opendrive_to_file) << [this](const std::string &opendrive, carla::rpc::OpendriveGenerationParameters Params) -> R<void>
{
REQUIRE_CARLA_EPISODE();
if (!Episode->LoadNewOpendriveEpisode(cr::ToFString(opendrive), Params))
if (!Episode->LoadNewOpendriveEpisode(cr::ToLongFString(opendrive), Params))
{
RESPOND_ERROR("opendrive could not be correctly parsed");
}
@ -281,7 +281,7 @@ void FCarlaServer::FPimpl::BindActions()
const auto &SpawnPoints = Episode->GetRecommendedSpawnPoints();
return cr::MapInfo{
cr::FromFString(Episode->GetMapName()),
cr::FromFString(FileContents),
cr::FromLongFString(FileContents),
MakeVectorFromTArray<cg::Transform>(SpawnPoints)};
};