$darkmode
simulation.hpp
Go to the documentation of this file.
1 /*
2  * Copyright 2020 Robert Bosch GmbH
3  *
4  * Licensed under the Apache License, Version 2.0 (the "License");
5  * you may not use this file except in compliance with the License.
6  * You may obtain a copy of the License at
7  *
8  * http://www.apache.org/licenses/LICENSE-2.0
9  *
10  * Unless required by applicable law or agreed to in writing, software
11  * distributed under the License is distributed on an "AS IS" BASIS,
12  * WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.
13  * See the License for the specific language governing permissions and
14  * limitations under the License.
15  *
16  * SPDX-License-Identifier: Apache-2.0
17  */
23 #pragma once
24 
25 #include <functional> // for function<>
26 #include <memory> // for unique_ptr<>
27 
28 #include <boost/filesystem/path.hpp> // for path
29 
30 #include <fable/enum.hpp> // for ENUM_SERIALIZATION
31 
32 #include "simulation_context.hpp"
33 #include "stack.hpp" // for Stack
34 
35 namespace engine {
36 
38  cloe::Stack config;
39 
40  std::string uuid;
41  SimulationSync sync;
42  cloe::Duration elapsed;
43  SimulationOutcome outcome;
44  SimulationStatistics statistics;
45  cloe::Json triggers;
46  boost::optional<boost::filesystem::path> output_dir;
47 
48  public:
62  boost::filesystem::path get_output_filepath(const boost::filesystem::path& filename) const {
63  boost::filesystem::path filepath;
64  if (filename.is_absolute()) {
65  filepath = filename;
66  } else if (output_dir) {
67  filepath = *output_dir / filename;
68  } else {
69  throw cloe::ModelError{"cannot determine output path for '{}'", filename.native()};
70  }
71 
72  return filepath;
73  }
74 
80  void set_output_dir() {
81  if (config.engine.output_path) {
82  // For $registry to be of value, output_path (~= $id) here needs to be set.
83  if (config.engine.output_path->is_absolute()) {
84  // If it's absolute, then registry_path doesn't matter.
85  output_dir = *config.engine.output_path;
86  } else if (config.engine.registry_path) {
87  // Now, since output_dir is relative, we need the registry path.
88  // We don't care here whether the registry is relative or not.
89  output_dir = *config.engine.registry_path / *config.engine.output_path;
90  }
91  }
92  }
93 
94  friend void to_json(cloe::Json& j, const SimulationResult& r) {
95  j = cloe::Json{
96  {"uuid", r.uuid}, {"statistics", r.statistics}, {"simulation", r.sync},
97  {"elapsed", r.elapsed}, {"outcome", r.outcome},
98  };
99  }
100 };
101 
102 class Simulation {
103  public:
104  Simulation(const cloe::Stack& config, const std::string& uuid);
105  ~Simulation() = default;
106 
110  cloe::Logger logger() const { return logger_; }
111 
119 
123  size_t write_output(const SimulationResult&) const;
124 
128  bool write_output_file(const boost::filesystem::path& filepath, const cloe::Json& j) const;
129 
133  bool is_writable(const boost::filesystem::path& filepath) const;
134 
138  void set_report_progress(bool value) { report_progress_ = value; }
139 
145  void signal_abort();
146 
147  private:
148  cloe::Logger logger_;
149  cloe::Stack config_;
150  std::string uuid_;
151  std::function<void()> abort_fn_;
152 
153  // Options:
154  bool report_progress_{false};
155 };
156 
157 } // namespace engine
Definition: model.hpp:62
Definition: stack.hpp:901
Definition: simulation_context.hpp:57
Definition: simulation.hpp:102
void signal_abort()
Definition: simulation.cpp:1387
cloe::Logger logger() const
Definition: simulation.hpp:110
SimulationResult run()
Definition: simulation.cpp:1197
void set_report_progress(bool value)
Definition: simulation.hpp:138
bool is_writable(const boost::filesystem::path &filepath) const
Definition: simulation.cpp:1353
bool write_output_file(const boost::filesystem::path &filepath, const cloe::Json &j) const
Definition: simulation.cpp:1336
size_t write_output(const SimulationResult &) const
Definition: simulation.cpp:1311
std::chrono::nanoseconds Duration
Definition: cloe_fwd.hpp:36
SimulationOutcome
Definition: simulation_context.hpp:287
Definition: simulation.hpp:37
void set_output_dir()
Definition: simulation.hpp:80
boost::filesystem::path get_output_filepath(const boost::filesystem::path &filename) const
Definition: simulation.hpp:62
Definition: simulation_context.hpp:258