Exposed max chunk size to the PythonAPI
This commit is contained in:
parent
5ddb97a58e
commit
e2c0349ef6
|
@ -214,10 +214,10 @@ namespace geom {
|
|||
}
|
||||
|
||||
std::vector<std::unique_ptr<Mesh>> MeshFactory::GenerateWithMaxLen(
|
||||
const road::Road &road, const double max_len) const {
|
||||
const road::Road &road) const {
|
||||
std::vector<std::unique_ptr<Mesh>> mesh_uptr_list;
|
||||
for (auto &&lane_section : road.GetLaneSections()) {
|
||||
auto section_uptr_list = GenerateWithMaxLen(lane_section, max_len);
|
||||
auto section_uptr_list = GenerateWithMaxLen(lane_section);
|
||||
mesh_uptr_list.insert(
|
||||
mesh_uptr_list.end(),
|
||||
std::make_move_iterator(section_uptr_list.begin()),
|
||||
|
@ -227,15 +227,15 @@ namespace geom {
|
|||
}
|
||||
|
||||
std::vector<std::unique_ptr<Mesh>> MeshFactory::GenerateWithMaxLen(
|
||||
const road::LaneSection &lane_section, const double max_len) const {
|
||||
const road::LaneSection &lane_section) const {
|
||||
std::vector<std::unique_ptr<Mesh>> mesh_uptr_list;
|
||||
if (lane_section.GetLength() < max_len) {
|
||||
if (lane_section.GetLength() < road_param.max_road_len) {
|
||||
mesh_uptr_list.emplace_back(Generate(lane_section));
|
||||
} else {
|
||||
double s_current = lane_section.GetDistance() + EPSILON;
|
||||
const double s_end = lane_section.GetDistance() + lane_section.GetLength() - EPSILON;
|
||||
while(s_current + max_len < s_end) {
|
||||
const auto s_until = s_current + max_len;
|
||||
while(s_current + road_param.max_road_len < s_end) {
|
||||
const auto s_until = s_current + road_param.max_road_len;
|
||||
Mesh lane_section_mesh;
|
||||
for (auto &&lane_pair : lane_section.GetLanes()) {
|
||||
lane_section_mesh += *Generate(lane_pair.second, s_current, s_until);
|
||||
|
@ -255,10 +255,10 @@ namespace geom {
|
|||
}
|
||||
|
||||
std::vector<std::unique_ptr<Mesh>> MeshFactory::GenerateWallsWithMaxLen(
|
||||
const road::Road &road, const double max_len) const {
|
||||
const road::Road &road) const {
|
||||
std::vector<std::unique_ptr<Mesh>> mesh_uptr_list;
|
||||
for (auto &&lane_section : road.GetLaneSections()) {
|
||||
auto section_uptr_list = GenerateWallsWithMaxLen(lane_section, max_len);
|
||||
auto section_uptr_list = GenerateWallsWithMaxLen(lane_section);
|
||||
mesh_uptr_list.insert(
|
||||
mesh_uptr_list.end(),
|
||||
std::make_move_iterator(section_uptr_list.begin()),
|
||||
|
@ -268,7 +268,7 @@ namespace geom {
|
|||
}
|
||||
|
||||
std::vector<std::unique_ptr<Mesh>> MeshFactory::GenerateWallsWithMaxLen(
|
||||
const road::LaneSection &lane_section, const double max_len) const {
|
||||
const road::LaneSection &lane_section) const {
|
||||
std::vector<std::unique_ptr<Mesh>> mesh_uptr_list;
|
||||
|
||||
const auto min_lane = lane_section.GetLanes().begin()->first == 0 ?
|
||||
|
@ -276,13 +276,13 @@ namespace geom {
|
|||
const auto max_lane = lane_section.GetLanes().rbegin()->first == 0 ?
|
||||
-1 : lane_section.GetLanes().rbegin()->first;
|
||||
|
||||
if (lane_section.GetLength() < max_len) {
|
||||
if (lane_section.GetLength() < road_param.max_road_len) {
|
||||
mesh_uptr_list.emplace_back(GenerateWalls(lane_section));
|
||||
} else {
|
||||
double s_current = lane_section.GetDistance() + EPSILON;
|
||||
const double s_end = lane_section.GetDistance() + lane_section.GetLength() - EPSILON;
|
||||
while(s_current + max_len < s_end) {
|
||||
const auto s_until = s_current + max_len;
|
||||
while(s_current + road_param.max_road_len < s_end) {
|
||||
const auto s_until = s_current + road_param.max_road_len;
|
||||
Mesh lane_section_mesh;
|
||||
for (auto &&lane_pair : lane_section.GetLanes()) {
|
||||
const auto &lane = lane_pair.second;
|
||||
|
@ -314,11 +314,11 @@ namespace geom {
|
|||
}
|
||||
|
||||
std::vector<std::unique_ptr<Mesh>> MeshFactory::GenerateAllWithMaxLen(
|
||||
const road::Road &road, const double max_len) const {
|
||||
const road::Road &road) const {
|
||||
std::vector<std::unique_ptr<Mesh>> mesh_uptr_list;
|
||||
|
||||
// Get road meshes
|
||||
auto roads = GenerateWithMaxLen(road, max_len);
|
||||
auto roads = GenerateWithMaxLen(road);
|
||||
mesh_uptr_list.insert(
|
||||
mesh_uptr_list.end(),
|
||||
std::make_move_iterator(roads.begin()),
|
||||
|
@ -326,7 +326,7 @@ namespace geom {
|
|||
|
||||
// Get wall meshes only if is not a junction
|
||||
if (!road.IsJunction()) {
|
||||
auto walls = GenerateWallsWithMaxLen(road, max_len);
|
||||
auto walls = GenerateWallsWithMaxLen(road);
|
||||
|
||||
if (roads.size() == walls.size()) {
|
||||
for (size_t i = 0; i < walls.size(); ++i) {
|
||||
|
|
|
@ -60,23 +60,23 @@ namespace geom {
|
|||
|
||||
/// Generates list of meshes that defines a single road with a maximum length
|
||||
std::vector<std::unique_ptr<Mesh>> GenerateWithMaxLen(
|
||||
const road::Road &road, const double max_len) const;
|
||||
const road::Road &road) const;
|
||||
|
||||
/// Generates list of meshes that defines a single lane_section with a maximum length
|
||||
std::vector<std::unique_ptr<Mesh>> GenerateWithMaxLen(
|
||||
const road::LaneSection &lane_section, const double max_len) const;
|
||||
const road::LaneSection &lane_section) const;
|
||||
|
||||
std::vector<std::unique_ptr<Mesh>> GenerateWallsWithMaxLen(
|
||||
const road::Road &road, const double max_len) const;
|
||||
const road::Road &road) const;
|
||||
|
||||
std::vector<std::unique_ptr<Mesh>> GenerateWallsWithMaxLen(
|
||||
const road::LaneSection &lane_section, const double max_len) const;
|
||||
const road::LaneSection &lane_section) const;
|
||||
|
||||
// -- Util --
|
||||
|
||||
/// Generates a chunked road with all the features needed for simulation
|
||||
std::vector<std::unique_ptr<Mesh>> GenerateAllWithMaxLen(
|
||||
const road::Road &road, const double max_len) const;
|
||||
const road::Road &road) const;
|
||||
|
||||
// =========================================================================
|
||||
// -- Generation parameters ------------------------------------------------
|
||||
|
@ -85,6 +85,7 @@ namespace geom {
|
|||
/// Parameters for the road generation
|
||||
struct RoadParameters {
|
||||
float resolution = 2.0f;
|
||||
float max_road_len = 50.0f;
|
||||
float extra_lane_width = 1.0f;
|
||||
float wall_height = 0.6f;
|
||||
};
|
||||
|
|
|
@ -955,6 +955,7 @@ namespace road {
|
|||
RELEASE_ASSERT(max_road_len > 0.0);
|
||||
geom::MeshFactory mesh_factory;
|
||||
mesh_factory.road_param.resolution = static_cast<float>(distance);
|
||||
mesh_factory.road_param.max_road_len = max_road_len;
|
||||
mesh_factory.road_param.extra_lane_width = extra_width;
|
||||
std::vector<std::unique_ptr<geom::Mesh>> out_mesh_list;
|
||||
|
||||
|
@ -962,7 +963,7 @@ namespace road {
|
|||
for (auto &&pair : _data.GetRoads()) {
|
||||
const auto &road = pair.second;
|
||||
std::vector<std::unique_ptr<geom::Mesh>> road_mesh_list =
|
||||
mesh_factory.GenerateAllWithMaxLen(road, max_road_len);
|
||||
mesh_factory.GenerateAllWithMaxLen(road);
|
||||
|
||||
// If the road in in a junction, add the road to the junction mesh instead of
|
||||
// doing it separately, this is needed for the road mesh smooth algorithm
|
||||
|
|
|
@ -150,10 +150,10 @@ namespace road {
|
|||
ComputeJunctionConflicts(JuncId id) const;
|
||||
|
||||
/// Buids a mesh based on the OpenDRIVE
|
||||
geom::Mesh GenerateMesh(const double distance, const float extra_width = 0.f) const;
|
||||
geom::Mesh GenerateMesh(const double distance, const float extra_width = 0.6f) const;
|
||||
|
||||
std::vector<std::unique_ptr<geom::Mesh>> GenerateChunkedMesh(
|
||||
const double distance, const float max_road_len, const float extra_width = 0.f) const;
|
||||
const double distance, const float max_road_len = 50.0f, const float extra_width = 0.6f) const;
|
||||
|
||||
/// Buids a mesh of all crosswalks based on the OpenDRIVE
|
||||
geom::Mesh GetAllCrosswalkMesh() const;
|
||||
|
|
|
@ -14,21 +14,29 @@ namespace rpc {
|
|||
OpendriveGenerationParameters(){}
|
||||
OpendriveGenerationParameters(
|
||||
double v_distance,
|
||||
double max_road_len,
|
||||
double w_height,
|
||||
double a_width,
|
||||
bool e_visibility)
|
||||
: vertex_distance(v_distance),
|
||||
max_road_length(max_road_len),
|
||||
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;
|
||||
double vertex_distance = 2.0;
|
||||
double max_road_length = 50.0;
|
||||
double wall_height = 1.0;
|
||||
double additional_width = 0.6;
|
||||
bool enable_mesh_visibility = true;
|
||||
|
||||
MSGPACK_DEFINE_ARRAY(vertex_distance, wall_height, additional_width, enable_mesh_visibility);
|
||||
MSGPACK_DEFINE_ARRAY(
|
||||
vertex_distance,
|
||||
max_road_length,
|
||||
wall_height,
|
||||
additional_width,
|
||||
enable_mesh_visibility);
|
||||
};
|
||||
|
||||
}
|
||||
|
|
|
@ -166,8 +166,9 @@ void export_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)))
|
||||
init<double, double, double, double, bool>((arg("vertex_distance")=2.0, arg("max_road_length")=50.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("max_road_length", &rpc::OpendriveGenerationParameters::max_road_length)
|
||||
.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)
|
||||
|
|
|
@ -210,15 +210,17 @@ def main():
|
|||
print('file could not be readed.')
|
||||
sys.exit()
|
||||
print('load opendrive map %r.' % os.path.basename(args.xodr_path))
|
||||
vertex_distance = 2.0 # in meters
|
||||
wall_height = 1.0 # in meters
|
||||
extra_width = 0.6 # in meters
|
||||
vertex_distance = 2.0 # in meters
|
||||
max_road_length = 50.0 # in meters
|
||||
wall_height = 1.0 # in meters
|
||||
extra_width = 0.6 # in meters
|
||||
world = client.generate_opendrive_world(
|
||||
data, carla.OpendriveGenerationParameters(
|
||||
vertex_distance,
|
||||
wall_height,
|
||||
extra_width,
|
||||
True))
|
||||
vertex_distance=vertex_distance,
|
||||
max_road_length=max_road_length,
|
||||
wall_height=wall_height,
|
||||
additional_width=extra_width,
|
||||
enable_mesh_visibility=True))
|
||||
else:
|
||||
print('file not found.')
|
||||
|
||||
|
|
|
@ -128,16 +128,6 @@ static FString BuildRecastBuilderFile()
|
|||
return AbsoluteRecastBuilderPath;
|
||||
}
|
||||
|
||||
bool UCarlaEpisode::LoadNewOpendriveEpisode(
|
||||
const FString &OpenDriveString,
|
||||
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)
|
||||
|
@ -204,8 +194,9 @@ bool UCarlaEpisode::LoadNewOpendriveEpisode(
|
|||
}
|
||||
// Build the mesh generation config file
|
||||
const FString ConfigData = FString::Printf(
|
||||
TEXT("resolution=%s\nwall_height=%s\nadditional_width=%s\nmesh_visibility=%s"),
|
||||
TEXT("resolution=%s\nmax_road_length=%s\nwall_height=%s\nadditional_width=%s\nmesh_visibility=%s\n"),
|
||||
*FString::SanitizeFloat(Params.vertex_distance),
|
||||
*FString::SanitizeFloat(Params.max_road_length),
|
||||
*FString::SanitizeFloat(Params.wall_height),
|
||||
*FString::SanitizeFloat(Params.additional_width),
|
||||
*MeshVisibilityStr);
|
||||
|
|
|
@ -55,17 +55,6 @@ public:
|
|||
UFUNCTION(BlueprintCallable)
|
||||
bool LoadNewEpisode(const FString &MapString);
|
||||
|
||||
/// Load a new map generating the mesh from OpenDRIVE data and
|
||||
/// start a new episode.
|
||||
///
|
||||
/// If @a MapString is empty, it fails.
|
||||
UFUNCTION(BlueprintCallable)
|
||||
bool LoadNewOpendriveEpisode(
|
||||
const FString &OpenDriveString,
|
||||
float VertexDistance,
|
||||
float WallHeight,
|
||||
float AdditionalWidth);
|
||||
|
||||
/// Load a new map generating the mesh from OpenDRIVE data and
|
||||
/// start a new episode.
|
||||
///
|
||||
|
|
|
@ -68,6 +68,7 @@ void AOpenDriveGenerator::GenerateRoadMesh()
|
|||
static const FString ConfigFilePath =
|
||||
FPaths::ProjectContentDir() + "Carla/Maps/OpenDrive/OpenDriveMap.conf";
|
||||
float Resolution = 2.f;
|
||||
float MaxRoadLength = 50.0f;
|
||||
float WallHeight = 1.f;
|
||||
float AdditionalWidth = .6f;
|
||||
bool MeshVisibility = true;
|
||||
|
@ -87,6 +88,10 @@ void AOpenDriveGenerator::GenerateRoadMesh()
|
|||
{
|
||||
WallHeight = FCString::Atof(*Value);
|
||||
}
|
||||
else if (Key == "max_road_length")
|
||||
{
|
||||
MaxRoadLength = FCString::Atof(*Value);
|
||||
}
|
||||
else if (Key == "additional_width")
|
||||
{
|
||||
AdditionalWidth = FCString::Atof(*Value);
|
||||
|
@ -98,11 +103,8 @@ void AOpenDriveGenerator::GenerateRoadMesh()
|
|||
}
|
||||
}
|
||||
|
||||
// const FProceduralCustomMesh MeshData =
|
||||
// CarlaMap->GenerateMesh(Resolution, AdditionalWidth) +
|
||||
// CarlaMap->GenerateWalls(Resolution, WallHeight);
|
||||
|
||||
const auto Meshes = CarlaMap->GenerateChunkedMesh(Resolution, 50.0f, AdditionalWidth);
|
||||
const auto Meshes = CarlaMap->GenerateChunkedMesh(
|
||||
Resolution, MaxRoadLength, AdditionalWidth);
|
||||
for (const auto &Mesh : Meshes) {
|
||||
AActor *TempActor = GetWorld()->SpawnActor<AActor>();
|
||||
UProceduralMeshComponent *TempPMC = NewObject<UProceduralMeshComponent>(TempActor);
|
||||
|
|
Loading…
Reference in New Issue