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/filesystem.hpp>
20 #include <boost/filesystem/operations.hpp>
21 #include <boost/range/iterator_range.hpp>
22 #include <iomanip>
24 #include <set>
25 #include <string>
27 
28 namespace traffic_simulator
29 {
31 {
33 
34  using Pathname = boost::filesystem::path;
35 
36  bool verbose = false;
37 
38  std::string simulator_host = "localhost";
39 
40  const bool standalone_mode = false;
41 
43 
44  const double v2i_traffic_light_publish_rate = 10.0;
45 
46  const std::set<std::uint8_t> auto_sink_entity_types;
47 
48  /* ---- NOTE -----------------------------------------------------------------
49  *
50  * This setting comes from the argument of the same name (= `map_path`) in
51  * the launch file of ArchitectureProposal. In general, Autoware expects
52  * this argument to be given the path to the directory containing the two HD
53  * maps, lanelet_map.osm and pointcloud_map.pcd.
54  *
55  * Depending on your map file, you may need to include additional files in
56  * this directory. For example, Autoware.Auto (at the time this comment was
57  * written) should be given the map origin coordinates in a separate yaml
58  * file.
59  *
60  * ------------------------------------------------------------------------ */
62 
64 
66 
68 
69  explicit Configuration(
70  const Pathname & map_path, const Pathname & scenario_path,
71  const std::set<std::uint8_t> & auto_sink_entity_types = {})
77  {
79  }
80 
81  explicit Configuration(
83  const std::set<std::uint8_t> & auto_sink_entity_types = {})
89  {
91  }
92 
93  auto assertMapPath(const Pathname & map_path) const -> const Pathname &
94  {
95  if (map_path.empty()) {
96  throw common::SimulationError("No map path is given");
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()), ")");
100  } else if (not contains(map_path, ".osm")) {
101  throw common::SimulationError("The map_path must contain at least one *.osm file");
102  } else if (not contains(map_path, ".pcd")) {
103  throw common::SimulationError("The map_path must contain at least one *.pcd file");
104  } else {
105  return map_path;
106  }
107  }
108 
109  template <typename... Ts>
110  auto contains(Ts &&... xs) const -> bool
111  {
112  return not findLexicographicallyFirstFilenameOf(std::forward<decltype(xs)>(xs)...).empty();
113  }
114 
116  const Pathname & pathname, const std::string & extension) const -> Filename
117  {
118  Filename result;
119 
120  for (const auto & each :
121  boost::make_iterator_range(boost::filesystem::directory_iterator(pathname), {})) {
122  const auto filename = each.path().filename().string();
123  if (
124  each.path().extension() == extension and
125  std::lexicographical_compare(
126  std::cbegin(result), std::cend(result), std::cbegin(filename), std::cend(filename))) {
127  result = filename;
128  }
129  }
130 
131  return result;
132  }
133 
134  auto getLanelet2MapFile() const -> const auto &
135  {
136  if (not lanelet2_map_file.empty()) {
137  return lanelet2_map_file;
138  } else {
139  throw common::SimulationError("The map_path must contain at least one *.osm file");
140  }
141  }
142 
143  auto getPointCloudMapFile() const -> const auto &
144  {
145  if (not pointcloud_map_file.empty()) {
146  return pointcloud_map_file;
147  } else {
148  throw common::SimulationError("The map_path must contain at least one *.pcd file");
149  }
150  }
151 
152  auto lanelet2_map_path() const -> boost::filesystem::path { return map_path / lanelet2_map_file; }
153 
154  auto pointcloud_map_path() const -> boost::filesystem::path
155  {
156  return map_path / pointcloud_map_file;
157  }
158 };
159 } // namespace traffic_simulator
160 
161 #endif // TRAFFIC_SIMULATOR__API__CONFIGURATION_HPP_
auto activate(Ts &&... xs)
Definition: lanelet_map.hpp:33
Definition: api.hpp:48
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