Added parameter to disable rendering meshes generated from OpenDRIVE.

This commit is contained in:
Axel1092 2020-04-03 17:00:16 +02:00 committed by bernat
parent 8c8acee730
commit 5ddb97a58e
13 changed files with 109 additions and 32 deletions

View File

@ -64,14 +64,9 @@ namespace client {
World GenerateOpenDriveWorld(
std::string opendrive,
double resolution=2.f,
double wall_height=1.f,
double additional_width=.6f) const {
const rpc::OpendriveGenerationParameters & params) const {
return World{_simulator->LoadOpenDriveEpisode(
std::move(opendrive),
resolution,
wall_height,
additional_width)};
std::move(opendrive), params)};
}
/// Return an instance of the world currently active in the simulator.

View File

@ -145,9 +145,9 @@ namespace detail {
_pimpl->CallAndWait<void>("load_new_episode", std::move(map_name));
}
void Client::CopyOpenDriveToServer(std::string opendrive, double resolution, double wall_height, double additional_width) {
void Client::CopyOpenDriveToServer(std::string opendrive, const rpc::OpendriveGenerationParameters & params) {
// Await response, we need to be sure in this one.
_pimpl->CallAndWait<void>("copy_opendrive_to_file", std::move(opendrive), resolution, wall_height, additional_width);
_pimpl->CallAndWait<void>("copy_opendrive_to_file", std::move(opendrive), params);
}
rpc::EpisodeInfo Client::GetEpisodeInfo() {

View File

@ -22,6 +22,7 @@
#include "carla/rpc/VehiclePhysicsControl.h"
#include "carla/rpc/VehicleLightState.h"
#include "carla/rpc/WeatherParameters.h"
#include "carla/rpc/OpendriveGenerationParameters.h"
#include <functional>
#include <memory>
@ -86,7 +87,8 @@ namespace detail {
void LoadEpisode(std::string map_name);
void CopyOpenDriveToServer(std::string opendrive, double resolution, double wall_height, double additional_width);
void CopyOpenDriveToServer(
std::string opendrive, const rpc::OpendriveGenerationParameters & params);
rpc::EpisodeInfo GetEpisodeInfo();

View File

@ -98,14 +98,12 @@ namespace detail {
EpisodeProxy Simulator::LoadOpenDriveEpisode(
std::string opendrive,
double resolution,
double wall_height,
double additional_width) {
const rpc::OpendriveGenerationParameters & params) {
// The "OpenDriveMap" is an ".umap" located in:
// "carla/Unreal/CarlaUE4/Content/Carla/Maps/"
// It will load the last sended OpenDRIVE by client's "LoadOpenDriveEpisode()"
constexpr auto custom_opendrive_map = "OpenDriveMap";
_client.CopyOpenDriveToServer(std::move(opendrive), resolution, wall_height, additional_width);
_client.CopyOpenDriveToServer(std::move(opendrive), params);
return LoadEpisode(custom_opendrive_map);
}

View File

@ -70,9 +70,7 @@ namespace detail {
EpisodeProxy LoadOpenDriveEpisode(
std::string opendrive,
double resolution,
double wall_height,
double additional_width);
const rpc::OpendriveGenerationParameters & params);
/// @}
// =========================================================================

View File

@ -0,0 +1,35 @@
// Copyright (c) 2019 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 "carla/MsgPack.h"
namespace carla {
namespace rpc {
/// Seting for map generation from opendrive without additional geometry
struct OpendriveGenerationParameters {
OpendriveGenerationParameters(){}
OpendriveGenerationParameters(
double v_distance,
double w_height,
double a_width,
bool e_visibility)
: vertex_distance(v_distance),
wall_height(w_height),
additional_width(a_width),
enable_mesh_visibility(e_visibility)
{}
double vertex_distance = 2.f;
double wall_height = 1.f;
double additional_width = 0.6f;
bool enable_mesh_visibility = true;
MSGPACK_DEFINE_ARRAY(vertex_distance, wall_height, additional_width, enable_mesh_visibility);
};
}
}

View File

@ -163,6 +163,15 @@ static auto ApplyBatchCommandsSync(
void export_client() {
using namespace boost::python;
namespace cc = carla::client;
namespace rpc = carla::rpc;
class_<rpc::OpendriveGenerationParameters>("OpendriveGenerationParameters",
init<double, double, double, bool>((arg("vertex_distance")=2.0, arg("wall_height")=1.0, arg("additional_width")=0.6, arg("enable_mesh_visibility")=true)))
.def_readwrite("vertex_distance", &rpc::OpendriveGenerationParameters::vertex_distance)
.def_readwrite("wall_height", &rpc::OpendriveGenerationParameters::wall_height)
.def_readwrite("additional_width", &rpc::OpendriveGenerationParameters::additional_width)
.def_readwrite("enable_mesh_visibility", &rpc::OpendriveGenerationParameters::enable_mesh_visibility)
;
class_<cc::Client>("Client",
init<std::string, uint16_t, size_t>((arg("host"), arg("port"), arg("worker_threads")=0u)))
@ -173,7 +182,8 @@ void export_client() {
.def("get_available_maps", &GetAvailableMaps)
.def("reload_world", CONST_CALL_WITHOUT_GIL(cc::Client, ReloadWorld))
.def("load_world", CONST_CALL_WITHOUT_GIL_1(cc::Client, LoadWorld, std::string), (arg("map_name")))
.def("generate_opendrive_world", CONST_CALL_WITHOUT_GIL_4(cc::Client, GenerateOpenDriveWorld, std::string, double, double, double), (arg("opendrive"), arg("resolution")=2.0, arg("wall_height")=1.0, arg("additional_width")=0.6))
.def("generate_opendrive_world", CONST_CALL_WITHOUT_GIL_2(cc::Client, GenerateOpenDriveWorld, std::string,
rpc::OpendriveGenerationParameters), (arg("opendrive"), arg("parameters")=rpc::OpendriveGenerationParameters()))
.def("start_recorder", CALL_WITHOUT_GIL_1(cc::Client, StartRecorder, std::string), (arg("name")))
.def("stop_recorder", &cc::Client::StopRecorder)
.def("show_recorder_file_info", CALL_WITHOUT_GIL_2(cc::Client, ShowRecorderFileInfo, std::string, bool), (arg("name"), arg("show_all")))

View File

@ -50,6 +50,7 @@ static boost::python::object OptionalToPythonObject(OptionalT &optional) {
// Convenient for const requests without arguments.
#define CONST_CALL_WITHOUT_GIL(cls, fn) CALL_WITHOUT_GIL(const cls, fn)
#define CONST_CALL_WITHOUT_GIL_1(cls, fn, T1_) CALL_WITHOUT_GIL_1(const cls, fn, T1_)
#define CONST_CALL_WITHOUT_GIL_2(cls, fn, T1_, T2_) CALL_WITHOUT_GIL_2(const cls, fn, T1_, T2_)
#define CONST_CALL_WITHOUT_GIL_4(cls, fn, T1_, T2_, T3_, T4_) CALL_WITHOUT_GIL_4(const cls, fn, T1_, T2_, T3_, T4_)
// Convenient for const requests that need to make a copy of the returned value.

View File

@ -210,10 +210,15 @@ def main():
print('file could not be readed.')
sys.exit()
print('load opendrive map %r.' % os.path.basename(args.xodr_path))
resolution = 2.0 # in meters
vertex_distance = 2.0 # in meters
wall_height = 1.0 # in meters
extra_width = 0.6 # in meters
world = client.generate_opendrive_world(data, resolution, wall_height, extra_width)
world = client.generate_opendrive_world(
data, carla.OpendriveGenerationParameters(
vertex_distance,
wall_height,
extra_width,
True))
else:
print('file not found.')

View File

@ -130,9 +130,17 @@ static FString BuildRecastBuilderFile()
bool UCarlaEpisode::LoadNewOpendriveEpisode(
const FString &OpenDriveString,
float Resolution,
float VertexDistance,
float WallHeight,
float AdditionalWidth)
{
return LoadNewOpendriveEpisode(OpenDriveString,
carla::rpc::OpendriveGenerationParameters(VertexDistance, WallHeight, AdditionalWidth, true));
}
bool UCarlaEpisode::LoadNewOpendriveEpisode(
const FString &OpenDriveString,
const carla::rpc::OpendriveGenerationParameters &Params)
{
if (OpenDriveString.IsEmpty())
{
@ -152,7 +160,7 @@ bool UCarlaEpisode::LoadNewOpendriveEpisode(
}
// Generate the OBJ (as string)
const auto RoadMesh = CarlaMap->GenerateMesh(Resolution);
const auto RoadMesh = CarlaMap->GenerateMesh(Params.vertex_distance);
const auto CrosswalksMesh = CarlaMap->GetAllCrosswalkMesh();
const auto RecastOBJ = (RoadMesh + CrosswalksMesh).GenerateOBJForRecast();
@ -185,12 +193,22 @@ bool UCarlaEpisode::LoadNewOpendriveEpisode(
const FString AbsoluteCONFPath = FPaths::ConvertRelativePathToFull(
FPaths::ProjectContentDir() + "Carla/Maps/OpenDrive/OpenDriveMap.conf");
FString MeshVisibilityStr = "true";
if(Params.enable_mesh_visibility)
{
MeshVisibilityStr = "true";
}
else
{
MeshVisibilityStr = "false";
}
// Build the mesh generation config file
const FString ConfigData = FString::Printf(
TEXT("resolution=%s\nwall_height=%s\nadditional_width=%s\n"),
*FString::SanitizeFloat(Resolution),
*FString::SanitizeFloat(WallHeight),
*FString::SanitizeFloat(AdditionalWidth));
TEXT("resolution=%s\nwall_height=%s\nadditional_width=%s\nmesh_visibility=%s"),
*FString::SanitizeFloat(Params.vertex_distance),
*FString::SanitizeFloat(Params.wall_height),
*FString::SanitizeFloat(Params.additional_width),
*MeshVisibilityStr);
// Save the config file
FFileHelper::SaveStringToFile(

View File

@ -21,6 +21,7 @@
#include <carla/geom/GeoLocation.h>
#include <carla/rpc/Actor.h>
#include <carla/rpc/ActorDescription.h>
#include <carla/rpc/OpendriveGenerationParameters.h>
#include <carla/streaming/Server.h>
#include <compiler/enable-ue4-macros.h>
@ -61,10 +62,18 @@ public:
UFUNCTION(BlueprintCallable)
bool LoadNewOpendriveEpisode(
const FString &OpenDriveString,
float Resolution,
float VertexDistance,
float WallHeight,
float AdditionalWidth);
/// Load a new map generating the mesh from OpenDRIVE data and
/// start a new episode.
///
/// If @a MapString is empty, it fails.
bool LoadNewOpendriveEpisode(
const FString &OpenDriveString,
const carla::rpc::OpendriveGenerationParameters &Params);
// ===========================================================================
// -- Episode settings -------------------------------------------------------
// ===========================================================================

View File

@ -67,9 +67,10 @@ void AOpenDriveGenerator::GenerateRoadMesh()
static const FString ConfigFilePath =
FPaths::ProjectContentDir() + "Carla/Maps/OpenDrive/OpenDriveMap.conf";
float Resolution = 2.0f;
float WallHeight = 1.0f;
float AdditionalWidth = 0.6f;
float Resolution = 2.f;
float WallHeight = 1.f;
float AdditionalWidth = .6f;
bool MeshVisibility = true;
if (FPaths::FileExists(ConfigFilePath)) {
FString ConfigData;
TArray<FString> Lines;
@ -90,6 +91,10 @@ void AOpenDriveGenerator::GenerateRoadMesh()
{
AdditionalWidth = FCString::Atof(*Value);
}
else if (Key == "mesh_visibility")
{
MeshVisibility = Value.ToBool();
}
}
}

View File

@ -234,10 +234,11 @@ void FCarlaServer::FPimpl::BindActions()
return R<void>::Success();
};
BIND_SYNC(copy_opendrive_to_file) << [this](const std::string &opendrive, double resolution, double wall_height, double additional_width) -> R<void>
BIND_SYNC(copy_opendrive_to_file) << [this](const std::string &opendrive, carla::rpc::OpendriveGenerationParameters Params) -> R<void>
{
carla::log_warning("Hello", Params.vertex_distance);
REQUIRE_CARLA_EPISODE();
if (!Episode->LoadNewOpendriveEpisode(cr::ToFString(opendrive), resolution, wall_height, additional_width))
if (!Episode->LoadNewOpendriveEpisode(cr::ToFString(opendrive), Params))
{
RESPOND_ERROR("opendrive could not be correctly parsed");
}