15 #ifndef TRAFFIC_SIMULATOR__API__CONFIGURATION_HPP_
16 #define TRAFFIC_SIMULATOR__API__CONFIGURATION_HPP_
19 #include <boost/filesystem.hpp>
20 #include <boost/filesystem/operations.hpp>
21 #include <boost/range/iterator_range.hpp>
79 }
else if (not boost::filesystem::is_directory(
map_path)) {
81 "The map_path must be a directory (given an ", std::quoted(
map_path.string()),
")");
91 template <
typename... Ts>
102 for (
const auto & each :
103 boost::make_iterator_range(boost::filesystem::directory_iterator(pathname), {})) {
104 const auto filename = each.path().filename().string();
106 each.path().extension() == extension and
107 std::lexicographical_compare(
108 std::cbegin(result), std::cend(result), std::cbegin(filename), std::cend(filename))) {
Definition: junit5.hpp:25
std::string string
Definition: junit5.hpp:26
A problem occurred that interfered with the continuation of the simulation.
Definition: exception.hpp:47
Definition: configuration.hpp:30
auto lanelet2_map_path() const
Definition: configuration.hpp:134
auto contains(Ts &&... xs) const -> bool
Definition: configuration.hpp:92
const Pathname map_path
Definition: configuration.hpp:60
Configuration(const Pathname &map_path)
Definition: configuration.hpp:68
auto getLanelet2MapFile() const -> const auto &
Definition: configuration.hpp:116
auto assertMapPath(const Pathname &map_path) const -> const Pathname &
Definition: configuration.hpp:75
std::string Filename
Definition: configuration.hpp:31
auto findLexicographicallyFirstFilenameOf(const Pathname &pathname, const std::string &extension) const -> Filename
Definition: configuration.hpp:97
double v2i_traffic_light_publish_rate
Definition: configuration.hpp:45
auto getPointCloudMapFile() const -> const auto &
Definition: configuration.hpp:125
bool standalone_mode
Definition: configuration.hpp:39
Filename pointcloud_map_file
Definition: configuration.hpp:64
bool verbose
Definition: configuration.hpp:37
std::string simulator_host
Definition: configuration.hpp:41
Pathname scenario_path
Definition: configuration.hpp:66
Filename lanelet2_map_file
Definition: configuration.hpp:62
boost::filesystem::path Pathname
Definition: configuration.hpp:33
std::set< std::uint8_t > auto_sink_entity_types
Definition: configuration.hpp:35
double conventional_traffic_light_publish_rate
Definition: configuration.hpp:43
auto pointcloud_map_path() const
Definition: configuration.hpp:136