15 #ifndef TRAFFIC_SIMULATOR__SIMULATION_CLOCK__SIMULATION_CLOCK_HPP_
16 #define TRAFFIC_SIMULATOR__SIMULATION_CLOCK__SIMULATION_CLOCK_HPP_
18 #include <rclcpp/rclcpp.hpp>
19 #include <rosgraph_msgs/msg/clock.hpp>
34 return seconds_since_the_simulator_started_ - seconds_at_the_start_of_the_scenario_;
43 auto started()
const {
return not std::isnan(seconds_at_the_start_of_the_scenario_); }
54 const rclcpp::Time time_at_the_start_of_the_simulator_;
56 double seconds_since_the_simulator_started_ = 0.0;
58 double seconds_at_the_start_of_the_scenario_ = std::numeric_limits<double>::quiet_NaN();
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