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 <string>
25 
26 namespace traffic_simulator
27 {
29 {
31 
32  using Pathname = boost::filesystem::path;
33 
34  bool auto_sink = true;
35 
36  bool verbose = false;
37 
38  bool standalone_mode = false;
39 
40  std::string simulator_host = "localhost";
41 
43 
45 
46  /* ---- NOTE -----------------------------------------------------------------
47  *
48  * This setting comes from the argument of the same name (= `map_path`) in
49  * the launch file of ArchitectureProposal. In general, Autoware expects
50  * this argument to be given the path to the directory containing the two HD
51  * maps, lanelet_map.osm and pointcloud_map.pcd.
52  *
53  * Depending on your map file, you may need to include additional files in
54  * this directory. For example, Autoware.Auto (at the time this comment was
55  * written) should be given the map origin coordinates in a separate yaml
56  * file.
57  *
58  * ------------------------------------------------------------------------ */
60 
62 
64 
66 
67  explicit Configuration(const Pathname & map_path) //
71  {
72  }
73 
74  auto assertMapPath(const Pathname & map_path) const -> const Pathname &
75  {
76  if (map_path.empty()) {
77  throw common::SimulationError("No map path is given");
78  } else if (not boost::filesystem::is_directory(map_path)) {
80  "The map_path must be a directory (given an ", std::quoted(map_path.string()), ")");
81  } else if (not contains(map_path, ".osm")) {
82  throw common::SimulationError("The map_path must contain at least one *.osm file");
83  } else if (not contains(map_path, ".pcd")) {
84  throw common::SimulationError("The map_path must contain at least one *.pcd file");
85  } else {
86  return map_path;
87  }
88  }
89 
90  template <typename... Ts>
91  auto contains(Ts &&... xs) const -> bool
92  {
93  return not findLexicographicallyFirstFilenameOf(std::forward<decltype(xs)>(xs)...).empty();
94  }
95 
97  const Pathname & pathname, const std::string & extension) const -> Filename
98  {
99  Filename result;
100 
101  for (const auto & each :
102  boost::make_iterator_range(boost::filesystem::directory_iterator(pathname), {})) {
103  const auto filename = each.path().filename().string();
104  if (
105  each.path().extension() == extension and
106  std::lexicographical_compare(
107  std::cbegin(result), std::cend(result), std::cbegin(filename), std::cend(filename))) {
108  result = filename;
109  }
110  }
111 
112  return result;
113  }
114 
115  auto getLanelet2MapFile() const -> const auto &
116  {
117  if (not lanelet2_map_file.empty()) {
118  return lanelet2_map_file;
119  } else {
120  throw common::SimulationError("The map_path must contain at least one *.osm file");
121  }
122  }
123 
124  auto getPointCloudMapFile() const -> const auto &
125  {
126  if (not pointcloud_map_file.empty()) {
127  return pointcloud_map_file;
128  } else {
129  throw common::SimulationError("The map_path must contain at least one *.pcd file");
130  }
131  }
132 
133  auto lanelet2_map_path() const { return map_path / lanelet2_map_file; }
134 
136 };
137 } // namespace traffic_simulator
138 
139 #endif // TRAFFIC_SIMULATOR__API__CONFIGURATION_HPP_
Definition: api.hpp:49
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:29
auto lanelet2_map_path() const
Definition: configuration.hpp:133
auto contains(Ts &&... xs) const -> bool
Definition: configuration.hpp:91
const Pathname map_path
Definition: configuration.hpp:59
Configuration(const Pathname &map_path)
Definition: configuration.hpp:67
auto getLanelet2MapFile() const -> const auto &
Definition: configuration.hpp:115
auto assertMapPath(const Pathname &map_path) const -> const Pathname &
Definition: configuration.hpp:74
std::string Filename
Definition: configuration.hpp:30
auto findLexicographicallyFirstFilenameOf(const Pathname &pathname, const std::string &extension) const -> Filename
Definition: configuration.hpp:96
double v2i_traffic_light_publish_rate
Definition: configuration.hpp:44
auto getPointCloudMapFile() const -> const auto &
Definition: configuration.hpp:124
bool standalone_mode
Definition: configuration.hpp:38
Filename pointcloud_map_file
Definition: configuration.hpp:63
bool verbose
Definition: configuration.hpp:36
bool auto_sink
Definition: configuration.hpp:34
std::string simulator_host
Definition: configuration.hpp:40
Pathname scenario_path
Definition: configuration.hpp:65
Filename lanelet2_map_file
Definition: configuration.hpp:61
boost::filesystem::path Pathname
Definition: configuration.hpp:32
double conventional_traffic_light_publish_rate
Definition: configuration.hpp:42
auto pointcloud_map_path() const
Definition: configuration.hpp:135