scenario_simulator_v2 C++ API
simulation_clock.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__SIMULATION_CLOCK__SIMULATION_CLOCK_HPP_
16 #define TRAFFIC_SIMULATOR__SIMULATION_CLOCK__SIMULATION_CLOCK_HPP_
17 
18 #include <rclcpp/rclcpp.hpp>
19 #include <rosgraph_msgs/msg/clock.hpp>
20 
21 namespace traffic_simulator
22 {
23 class SimulationClock : rclcpp::Clock
24 {
25 public:
26  explicit SimulationClock(bool use_sim_time, double realtime_factor, double frame_rate);
27 
28  auto getCurrentRosTime() -> rclcpp::Time;
29 
30  auto getCurrentRosTimeAsMsg() -> rosgraph_msgs::msg::Clock;
31 
33  {
34  return seconds_since_the_simulator_started_ - seconds_at_the_start_of_the_scenario_;
35  }
36 
37  auto getCurrentSimulationTime() const { return seconds_since_the_simulator_started_; }
38 
39  auto getStepTime() const { return realtime_factor / frame_rate_; }
40 
41  auto start() -> void;
42 
43  auto started() const { return not std::isnan(seconds_at_the_start_of_the_scenario_); }
44 
45  auto update() -> void;
46 
47  const bool use_sim_time;
48 
50 
51 private:
52  double frame_rate_;
53 
54  const rclcpp::Time time_at_the_start_of_the_simulator_;
55 
56  double seconds_since_the_simulator_started_ = 0.0;
57 
58  double seconds_at_the_start_of_the_scenario_ = std::numeric_limits<double>::quiet_NaN();
59 };
60 } // namespace traffic_simulator
61 
62 #endif // TRAFFIC_SIMULATOR__SIMULATION_CLOCK__SIMULATION_CLOCK_HPP_
Definition: simulation_clock.hpp:24
auto getCurrentRosTime() -> rclcpp::Time
Definition: simulation_clock.cpp:41
const bool use_sim_time
Definition: simulation_clock.hpp:47
double realtime_factor
Definition: simulation_clock.hpp:49
auto started() const
Definition: simulation_clock.hpp:43
auto getCurrentScenarioTime() const
Definition: simulation_clock.hpp:32
auto update() -> void
Definition: simulation_clock.cpp:29
SimulationClock(bool use_sim_time, double realtime_factor, double frame_rate)
Definition: simulation_clock.cpp:20
auto getCurrentSimulationTime() const
Definition: simulation_clock.hpp:37
auto getStepTime() const
Definition: simulation_clock.hpp:39
auto getCurrentRosTimeAsMsg() -> rosgraph_msgs::msg::Clock
Definition: simulation_clock.cpp:34
auto start() -> void
Definition: simulation_clock.cpp:51
Definition: api.hpp:48