scenario_simulator_v2 C++ API
configuration.hpp
Go to the documentation of this file.
1 // Copyright 2015 TIER IV, Inc. All rights reserved.
2 //
3 // Licensed under the Apache License, Version 2.0 (the "License");
4 // you may not use this file except in compliance with the License.
5 // You may obtain a copy of the License at
6 //
7 // http://www.apache.org/licenses/LICENSE-2.0
8 //
9 // Unless required by applicable law or agreed to in writing, software
10 // distributed under the License is distributed on an "AS IS" BASIS,
11 // WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.
12 // See the License for the specific language governing permissions and
13 // limitations under the License.
14 
15 #ifndef TRAFFIC_SIMULATOR__API__CONFIGURATION_HPP_
16 #define TRAFFIC_SIMULATOR__API__CONFIGURATION_HPP_
17 
18 #include <algorithm>
19 #include <boost/range/iterator_range.hpp>
20 #include <filesystem>
21 #include <iomanip>
23 #include <set>
24 #include <string>
26 
27 namespace traffic_simulator
28 {
30 {
32 
33  using Pathname = std::filesystem::path;
34 
35  bool verbose = false;
36 
37  std::string simulator_host = "localhost";
38 
39  const bool standalone_mode = false;
40 
42 
43  const double v2i_traffic_light_publish_rate = 10.0;
44 
45  const std::set<std::uint8_t> auto_sink_entity_types;
46 
47  /* ---- NOTE -----------------------------------------------------------------
48  *
49  * This setting comes from the argument of the same name (= `map_path`) in
50  * the launch file of ArchitectureProposal. In general, Autoware expects
51  * this argument to be given the path to the directory containing the two HD
52  * maps, lanelet_map.osm and pointcloud_map.pcd.
53  *
54  * Depending on your map file, you may need to include additional files in
55  * this directory. For example, Autoware.Auto (at the time this comment was
56  * written) should be given the map origin coordinates in a separate yaml
57  * file.
58  *
59  * ------------------------------------------------------------------------ */
61 
63 
65 
67 
68  explicit Configuration(
69  const Pathname & map_path, const Pathname & scenario_path,
70  const std::set<std::uint8_t> & auto_sink_entity_types = {})
76  {
78  }
79 
80  explicit Configuration(
82  const std::set<std::uint8_t> & auto_sink_entity_types = {})
88  {
90  }
91 
92  auto assertMapPath(const Pathname & map_path) const -> const Pathname &
93  {
94  if (map_path.empty()) {
95  throw common::SimulationError("No map path is given");
96  } else if (not std::filesystem::is_directory(map_path)) {
98  "The map_path must be a directory (given an ", std::quoted(map_path.string()), ")");
99  } else if (not contains(map_path, ".osm")) {
100  throw common::SimulationError("The map_path must contain at least one *.osm file");
101  } else if (not contains(map_path, ".pcd")) {
102  throw common::SimulationError("The map_path must contain at least one *.pcd file");
103  } else {
104  return map_path;
105  }
106  }
107 
108  template <typename... Ts>
109  auto contains(Ts &&... xs) const -> bool
110  {
111  return not findLexicographicallyFirstFilenameOf(std::forward<decltype(xs)>(xs)...).empty();
112  }
113 
115  const Pathname & pathname, const std::string & extension) const -> Filename
116  {
117  Filename result;
118 
119  for (const auto & each : std::filesystem::directory_iterator(pathname)) {
120  const auto filename = each.path().filename().string();
121  if (
122  each.path().extension() == extension and
123  std::lexicographical_compare(
124  std::cbegin(result), std::cend(result), std::cbegin(filename), std::cend(filename))) {
125  result = filename;
126  }
127  }
128 
129  return result;
130  }
131 
132  auto getLanelet2MapFile() const -> const auto &
133  {
134  if (not lanelet2_map_file.empty()) {
135  return lanelet2_map_file;
136  } else {
137  throw common::SimulationError("The map_path must contain at least one *.osm file");
138  }
139  }
140 
141  auto getPointCloudMapFile() const -> const auto &
142  {
143  if (not pointcloud_map_file.empty()) {
144  return pointcloud_map_file;
145  } else {
146  throw common::SimulationError("The map_path must contain at least one *.pcd file");
147  }
148  }
149 
150  auto lanelet2_map_path() const -> std::filesystem::path { return map_path / lanelet2_map_file; }
151 
152  auto pointcloud_map_path() const -> std::filesystem::path
153  {
154  return map_path / pointcloud_map_file;
155  }
156 };
157 } // namespace traffic_simulator
158 
159 #endif // TRAFFIC_SIMULATOR__API__CONFIGURATION_HPP_
Definition: lanelet_wrapper.hpp:43
auto activate(Ts &&... xs)
Definition: lanelet_map.hpp:33
Definition: api.hpp:32
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 contains(Ts &&... xs) const -> bool
Definition: configuration.hpp:109
const Pathname map_path
Definition: configuration.hpp:60
auto getLanelet2MapFile() const -> const auto &
Definition: configuration.hpp:132
Configuration(const Pathname &map_path, const Pathname &scenario_path, const std::set< std::uint8_t > &auto_sink_entity_types={})
Definition: configuration.hpp:68
auto assertMapPath(const Pathname &map_path) const -> const Pathname &
Definition: configuration.hpp:92
const Filename lanelet2_map_file
Definition: configuration.hpp:62
const Filename pointcloud_map_file
Definition: configuration.hpp:64
std::string Filename
Definition: configuration.hpp:31
auto findLexicographicallyFirstFilenameOf(const Pathname &pathname, const std::string &extension) const -> Filename
Definition: configuration.hpp:114
auto lanelet2_map_path() const -> std::filesystem::path
Definition: configuration.hpp:150
auto getPointCloudMapFile() const -> const auto &
Definition: configuration.hpp:141
const double v2i_traffic_light_publish_rate
Definition: configuration.hpp:43
std::filesystem::path Pathname
Definition: configuration.hpp:33
bool verbose
Definition: configuration.hpp:35
const Pathname scenario_path
Definition: configuration.hpp:66
const std::set< std::uint8_t > auto_sink_entity_types
Definition: configuration.hpp:45
std::string simulator_host
Definition: configuration.hpp:37
const double conventional_traffic_light_publish_rate
Definition: configuration.hpp:41
const bool standalone_mode
Definition: configuration.hpp:39
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:80
auto pointcloud_map_path() const -> std::filesystem::path
Definition: configuration.hpp:152