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 <ament_index_cpp/get_package_share_directory.hpp>
20 #include <boost/filesystem.hpp>
21 #include <boost/filesystem/operations.hpp>
22 #include <boost/range/iterator_range.hpp>
23 #include <iomanip>
25 #include <string>
26 
27 namespace traffic_simulator
28 {
30 {
32 
33  using Pathname = boost::filesystem::path;
34 
35  bool auto_sink = true;
36 
37  bool verbose = false;
38 
39  bool standalone_mode = false;
40 
41  std::string simulator_host = "localhost";
42 
44 
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 
69  ament_index_cpp::get_package_share_directory("traffic_simulator") +
70  "/config/scenario_simulator_v2.rviz";
71 
72  explicit Configuration(const Pathname & map_path) //
76  {
77  }
78 
79  auto assertMapPath(const Pathname & map_path) const -> const Pathname &
80  {
81  if (map_path.empty()) {
82  throw common::SimulationError("No map path is given");
83  } else if (not boost::filesystem::is_directory(map_path)) {
85  "The map_path must be a directory (given an ", std::quoted(map_path.string()), ")");
86  } else if (not contains(map_path, ".osm")) {
87  throw common::SimulationError("The map_path must contain at least one *.osm file");
88  } else if (not contains(map_path, ".pcd")) {
89  throw common::SimulationError("The map_path must contain at least one *.pcd file");
90  } else {
91  return map_path;
92  }
93  }
94 
95  template <typename... Ts>
96  auto contains(Ts &&... xs) const -> bool
97  {
98  return not findLexicographicallyFirstFilenameOf(std::forward<decltype(xs)>(xs)...).empty();
99  }
100 
102  const Pathname & pathname, const std::string & extension) const -> Filename
103  {
104  Filename result;
105 
106  for (const auto & each :
107  boost::make_iterator_range(boost::filesystem::directory_iterator(pathname), {})) {
108  const auto filename = each.path().filename().string();
109  if (
110  each.path().extension() == extension and
111  std::lexicographical_compare(
112  std::cbegin(result), std::cend(result), std::cbegin(filename), std::cend(filename))) {
113  result = filename;
114  }
115  }
116 
117  return result;
118  }
119 
120  auto getLanelet2MapFile() const -> const auto &
121  {
122  if (not lanelet2_map_file.empty()) {
123  return lanelet2_map_file;
124  } else {
125  throw common::SimulationError("The map_path must contain at least one *.osm file");
126  }
127  }
128 
129  auto getPointCloudMapFile() const -> const auto &
130  {
131  if (not pointcloud_map_file.empty()) {
132  return pointcloud_map_file;
133  } else {
134  throw common::SimulationError("The map_path must contain at least one *.pcd file");
135  }
136  }
137 
138  auto lanelet2_map_path() const { return map_path / lanelet2_map_file; }
139 
141 };
142 } // namespace traffic_simulator
143 
144 #endif // TRAFFIC_SIMULATOR__API__CONFIGURATION_HPP_
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:30
auto lanelet2_map_path() const
Definition: configuration.hpp:138
auto contains(Ts &&... xs) const -> bool
Definition: configuration.hpp:96
const Pathname map_path
Definition: configuration.hpp:60
Configuration(const Pathname &map_path)
Definition: configuration.hpp:72
auto getLanelet2MapFile() const -> const auto &
Definition: configuration.hpp:120
auto assertMapPath(const Pathname &map_path) const -> const Pathname &
Definition: configuration.hpp:79
std::string Filename
Definition: configuration.hpp:31
auto findLexicographicallyFirstFilenameOf(const Pathname &pathname, const std::string &extension) const -> Filename
Definition: configuration.hpp:101
double v2i_traffic_light_publish_rate
Definition: configuration.hpp:45
auto getPointCloudMapFile() const -> const auto &
Definition: configuration.hpp:129
bool standalone_mode
Definition: configuration.hpp:39
Filename pointcloud_map_file
Definition: configuration.hpp:64
bool verbose
Definition: configuration.hpp:37
bool auto_sink
Definition: configuration.hpp:35
std::string simulator_host
Definition: configuration.hpp:41
Pathname scenario_path
Definition: configuration.hpp:66
Filename lanelet2_map_file
Definition: configuration.hpp:62
Pathname rviz_config_path
Definition: configuration.hpp:68
boost::filesystem::path Pathname
Definition: configuration.hpp:33
double conventional_traffic_light_publish_rate
Definition: configuration.hpp:43
auto pointcloud_map_path() const
Definition: configuration.hpp:140