15 #ifndef RCLCPP__TIME_SOURCE_HPP_
16 #define RCLCPP__TIME_SOURCE_HPP_
23 #include "builtin_interfaces/msg/time.hpp"
24 #include "rosgraph_msgs/msg/clock.hpp"
25 #include "rcl_interfaces/msg/parameter_event.hpp"
45 explicit TimeSource(rclcpp::Node::SharedPtr node);
76 rclcpp::node_interfaces::NodeBaseInterface::SharedPtr node_base_interface,
77 rclcpp::node_interfaces::NodeTopicsInterface::SharedPtr node_topics_interface,
78 rclcpp::node_interfaces::NodeGraphInterface::SharedPtr node_graph_interface,
79 rclcpp::node_interfaces::NodeServicesInterface::SharedPtr node_services_interface,
80 rclcpp::node_interfaces::NodeLoggingInterface::SharedPtr node_logging_interface,
81 rclcpp::node_interfaces::NodeClockInterface::SharedPtr node_clock_interface,
82 rclcpp::node_interfaces::NodeParametersInterface::SharedPtr node_parameters_interface);
106 rclcpp::node_interfaces::NodeBaseInterface::SharedPtr node_base_;
107 rclcpp::node_interfaces::NodeTopicsInterface::SharedPtr node_topics_;
108 rclcpp::node_interfaces::NodeGraphInterface::SharedPtr node_graph_;
109 rclcpp::node_interfaces::NodeServicesInterface::SharedPtr node_services_;
110 rclcpp::node_interfaces::NodeLoggingInterface::SharedPtr node_logging_;
111 rclcpp::node_interfaces::NodeClockInterface::SharedPtr node_clock_;
112 rclcpp::node_interfaces::NodeParametersInterface::SharedPtr node_parameters_;
118 using MessageT = rosgraph_msgs::msg::Clock;
125 void clock_cb(
const rosgraph_msgs::msg::Clock::SharedPtr msg);
128 void create_clock_sub();
131 void destroy_clock_sub();
134 using ParamMessageT = rcl_interfaces::msg::ParameterEvent;
139 void on_parameter_event(
const rcl_interfaces::msg::ParameterEvent::SharedPtr event);
142 enum UseSimTimeParameterState {UNSET, SET_TRUE, SET_FALSE};
143 UseSimTimeParameterState parameter_state_;
146 void enable_ros_time();
148 void disable_ros_time();
151 static void enable_ros_time(rclcpp::Clock::SharedPtr clock);
152 static void disable_ros_time(rclcpp::Clock::SharedPtr clock);
153 static void set_clock(
154 const builtin_interfaces::msg::Time::SharedPtr msg,
155 bool set_ros_time_enabled,
156 rclcpp::Clock::SharedPtr clock);
160 bool ros_time_active_;
162 rosgraph_msgs::msg::Clock::SharedPtr last_msg_set_;
169 rclcpp::node_interfaces::OnSetParametersCallbackHandle::SharedPtr sim_time_cb_handler_ =
nullptr;
174 #endif // RCLCPP__TIME_SOURCE_HPP_