Skip to content

Commit

Permalink
Generates OBJ file either from multilane or dragway implementation. (#3)
Browse files Browse the repository at this point in the history
  • Loading branch information
francocipollone authored Apr 6, 2020
1 parent 8450210 commit 2c209ad
Show file tree
Hide file tree
Showing 4 changed files with 74 additions and 27 deletions.
12 changes: 7 additions & 5 deletions src/maliput_integration/CMakeLists.txt
Original file line number Diff line number Diff line change
Expand Up @@ -18,17 +18,19 @@ target_link_libraries(dragway_to_urdf
maliput_dragway::maliput_dragway
)

add_executable(yaml_to_obj
yaml_to_obj.cc)
add_executable(maliput_to_obj
maliput_to_obj.cc)

ament_target_dependencies(yaml_to_obj
ament_target_dependencies(maliput_to_obj
"maliput"
"maliput_dragway"
"maliput_multilane"
)

target_link_libraries(yaml_to_obj
target_link_libraries(maliput_to_obj
gflags
maliput::utilities
maliput_dragway::maliput_dragway
maliput_multilane::maliput_multilane
yaml-cpp
)
Expand All @@ -37,7 +39,7 @@ target_link_libraries(yaml_to_obj
# Install
##############################################################################

install(TARGETS dragway_to_urdf yaml_to_obj
install(TARGETS dragway_to_urdf maliput_to_obj
ARCHIVE DESTINATION lib
LIBRARY DESTINATION lib
RUNTIME DESTINATION bin
Expand Down
Original file line number Diff line number Diff line change
@@ -1,7 +1,18 @@
/// @file yaml_to_obj.cc
/// @file maliput_to_obj.cc
///
/// Take a yaml file as input, build the resulting multilane road geometry, and
/// render the road surface to a WaveFront OBJ output file.
/// Builds a dragway road geometry from flags or a multilane road geometry from a file,
/// and render the road surface to a WaveFront OBJ output file.
///
/// Notes:
/// 1 - It allows to create an OBJ file from different road geometry implementations. If a valid
/// filepath of an YAML file is passed, a multilane RoadGeometry will be created. Otherwise,
/// the following arguments will help to carry out a dragway implementation:
/// -num_lanes, -length, -lane_width, -shoulder_width, maximum_height.
/// 2 - The applications possesses flags to modify the OBJ file builder:
/// -obj_dir, -obj_file, -max_grid_unit, -min_grid_resolution, -draw_elevation_bounds, -simplify_mesh_threshold
/// 3 - The level of the logger could be setted by: -log_level.

#include <limits>
#include <string>

#include <gflags/gflags.h>
Expand All @@ -11,14 +22,33 @@

#include "maliput/utilities/generate_obj.h"

#include "maliput_dragway/road_geometry.h"
#include "maliput_multilane/builder.h"
#include "maliput_multilane/loader.h"

#include "yaml-cpp/yaml.h"

// Gflags for road geometry loaded from file/
DEFINE_string(yaml_file, "", "yaml input file defining a multilane road geometry");

// Gflags for implementing a dragway road geometry manually.
DEFINE_int32(num_lanes, 2, "The number of lanes.");
DEFINE_double(length, 10, "The length of the dragway in meters.");
// By default, each lane is 3.7m (12 feet) wide, which is the standard used by
// the U.S. interstate highway system.
DEFINE_double(lane_width, 3.7, "The width of each lane in meters.");
// By default, the shoulder width is 3 m (10 feet) wide, which is the standard
// used by the U.S. interstate highway system.
DEFINE_double(shoulder_width, 3.0,
"The width of the shoulders in meters. Both shoulders have the same "
"width.");
DEFINE_double(maximum_height, 5.2, "The maximum modelled height above the road surface (meters).");

// Gflags for output files.
DEFINE_string(obj_dir, ".", "Directory to contain rendered road surface");
DEFINE_string(obj_file, "", "Basename for output Wavefront OBJ and MTL files");

// Gflags for OBJ generation configuration.
DEFINE_double(max_grid_unit, maliput::utility::ObjFeatures().max_grid_unit,
"Maximum size of a grid unit in the rendered mesh covering the "
"road surface");
Expand All @@ -31,7 +61,7 @@ DEFINE_double(simplify_mesh_threshold, maliput::utility::ObjFeatures().simplify_
"Optional tolerance for mesh simplification, in meters. Make it "
"equal to the road linear tolerance to get a mesh size reduction "
"while keeping geometrical fidelity.");
DEFINE_string(spdlog_level, "unchanged",
DEFINE_string(log_level, "unchanged",
"sets the spdlog output threshold; possible values are "
"'unchanged', "
"'trace', "
Expand All @@ -48,6 +78,7 @@ namespace {

// Available maliput implementations to load.
enum class MaliputImplementation {
kDragway, //< dragway implementation.
kMultilane, //< multilane implementation.
kUnknown //< Used when none of the implementations could be identified.
};
Expand All @@ -56,25 +87,26 @@ enum class MaliputImplementation {
// "maliput_multilane_builder". If it is found,
// MaliputImplementation::kMultilane is returned. Otherwise,
// MaliputImplementation::kUnknown is returned.
MaliputImplementation GetMaliputImplementation(const std::string& filename) {
MaliputImplementation GetMaliputImplementationFromFile(const std::string& filename) {
const YAML::Node yaml_file = YAML::LoadFile(filename);
MALIPUT_DEMAND(yaml_file.IsMap());
if (yaml_file["maliput_multilane_builder"]) {
return MaliputImplementation::kMultilane;
}
return MaliputImplementation::kUnknown;
return yaml_file["maliput_multilane_builder"] ? MaliputImplementation::kMultilane : MaliputImplementation::kUnknown;
}

// Decides which type of road geometry implementation the application should select.
// If `filename` is empty it returns MaliputImplementation:kDragway.
// If `filename` is not empty it will load the file and check which implementation it refers to.
MaliputImplementation GetMaliputImplementation(const std::string& filename) {
return filename.empty() ? MaliputImplementation::kDragway : GetMaliputImplementationFromFile(filename);
}

// Generates an OBJ file from a YAML file path given as CLI argument.
// Generates an OBJ file from a YAML file path or from
// configurable values given as CLI arguments.
int main(int argc, char* argv[]) {
maliput::log()->debug("main()");
gflags::ParseCommandLineFlags(&argc, &argv, true);
maliput::common::set_log_level(FLAGS_spdlog_level);
maliput::common::set_log_level(FLAGS_log_level);

if (FLAGS_yaml_file.empty()) {
maliput::log()->critical("No input file specified.");
return 1;
}
if (FLAGS_obj_file.empty()) {
maliput::log()->critical("No output file specified.");
return 1;
Expand All @@ -83,6 +115,14 @@ int main(int argc, char* argv[]) {
maliput::log()->info("Loading road geometry...");
std::unique_ptr<const maliput::api::RoadGeometry> rg{};
switch (GetMaliputImplementation(FLAGS_yaml_file)) {
case MaliputImplementation::kDragway: {
rg = std::make_unique<dragway::RoadGeometry>(
api::RoadGeometryId{"Dragway with " + std::to_string(FLAGS_num_lanes) + " lanes."}, FLAGS_num_lanes,
FLAGS_length, FLAGS_lane_width, FLAGS_shoulder_width, FLAGS_maximum_height,
std::numeric_limits<double>::epsilon(), std::numeric_limits<double>::epsilon());
maliput::log()->info("Loaded a dragway road geometry.");
break;
}
case MaliputImplementation::kMultilane: {
rg = maliput::multilane::LoadFile(maliput::multilane::BuilderFactory(), FLAGS_yaml_file);
maliput::log()->info("Loaded a multilane road geometry.");
Expand Down
6 changes: 3 additions & 3 deletions test/CMakeLists.txt
Original file line number Diff line number Diff line change
@@ -1,7 +1,7 @@
find_package(ament_cmake_pytest REQUIRED)

ament_add_pytest_test(yaml_to_obj_test yaml_to_obj_test.py WORKING_DIRECTORY ${CMAKE_INSTALL_PREFIX}/bin TIMEOUT 360)
ament_add_pytest_test(maliput_to_obj_test maliput_to_obj_test.py WORKING_DIRECTORY ${CMAKE_INSTALL_PREFIX}/bin TIMEOUT 360)

if (TARGET yaml_to_obj_test)
add_dependencies(yaml_to_obj_test yaml_to_obj)
if (TARGET maliput_to_obj_test)
add_dependencies(maliput_to_obj_test maliput_to_obj)
endif()
13 changes: 9 additions & 4 deletions test/yaml_to_obj_test.py → test/maliput_to_obj_test.py
Original file line number Diff line number Diff line change
Expand Up @@ -15,9 +15,9 @@
class TestYamlObjing(unittest.TestCase):

def setUp(self):
self._yaml_to_obj = os.path.join(os.getcwd(), "yaml_to_obj")
self.assertTrue(os.path.exists(self._yaml_to_obj),
self._yaml_to_obj + " not found")
self._maliput_to_obj = os.path.join(os.getcwd(), "maliput_to_obj")
self.assertTrue(os.path.exists(self._maliput_to_obj),
self._maliput_to_obj + " not found")

def test_yaml_files(self):
this_dir = os.path.dirname(_THIS_DIR)
Expand All @@ -33,7 +33,12 @@ def test_yaml_files(self):

for yf in test_yaml_files:
subprocess.check_call([
self._yaml_to_obj,
self._maliput_to_obj,
"-yaml_file", yf,
"-obj_file", "/dev/null",
])
def test_dragway_creation(self):
subprocess.check_call([
self._maliput_to_obj,
"-obj_file", "/dev/null",
])

0 comments on commit 2c209ad

Please sign in to comment.