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>
97 }
else if (not boost::filesystem::is_directory(
map_path)) {
99 "The map_path must be a directory (given an ", std::quoted(
map_path.string()),
")");
109 template <
typename... Ts>
120 for (
const auto & each :
121 boost::make_iterator_range(boost::filesystem::directory_iterator(pathname), {})) {
122 const auto filename = each.path().filename().string();
124 each.path().extension() == extension and
125 std::lexicographical_compare(
126 std::cbegin(result), std::cend(result), std::cbegin(filename), std::cend(filename))) {
auto activate(Ts &&... xs)
Definition: lanelet_map.hpp:33
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:31
auto lanelet2_map_path() const -> boost::filesystem::path
Definition: configuration.hpp:152
auto contains(Ts &&... xs) const -> bool
Definition: configuration.hpp:110
const Pathname map_path
Definition: configuration.hpp:61
auto getLanelet2MapFile() const -> const auto &
Definition: configuration.hpp:134
Configuration(const Pathname &map_path, const Pathname &scenario_path, const std::set< std::uint8_t > &auto_sink_entity_types={})
Definition: configuration.hpp:69
auto assertMapPath(const Pathname &map_path) const -> const Pathname &
Definition: configuration.hpp:93
const Filename lanelet2_map_file
Definition: configuration.hpp:63
const Filename pointcloud_map_file
Definition: configuration.hpp:65
std::string Filename
Definition: configuration.hpp:32
auto findLexicographicallyFirstFilenameOf(const Pathname &pathname, const std::string &extension) const -> Filename
Definition: configuration.hpp:115
auto getPointCloudMapFile() const -> const auto &
Definition: configuration.hpp:143
const double v2i_traffic_light_publish_rate
Definition: configuration.hpp:44
bool verbose
Definition: configuration.hpp:36
const Pathname scenario_path
Definition: configuration.hpp:67
const std::set< std::uint8_t > auto_sink_entity_types
Definition: configuration.hpp:46
std::string simulator_host
Definition: configuration.hpp:38
const double conventional_traffic_light_publish_rate
Definition: configuration.hpp:42
boost::filesystem::path Pathname
Definition: configuration.hpp:34
const bool standalone_mode
Definition: configuration.hpp:40
auto pointcloud_map_path() const -> boost::filesystem::path
Definition: configuration.hpp:154
Configuration(const Pathname &map_path, const Filename &lanelet2_map_file, const Pathname &scenario_path, const std::set< std::uint8_t > &auto_sink_entity_types={})
Definition: configuration.hpp:81