15 #ifndef RCLCPP__TIME_SOURCE_HPP_ 16 #define RCLCPP__TIME_SOURCE_HPP_ 23 #include "builtin_interfaces/msg/time.hpp" 24 #include "rcl_interfaces/msg/parameter_event.hpp" 39 explicit TimeSource(rclcpp::Node::SharedPtr node);
49 const rclcpp::node_interfaces::NodeBaseInterface::SharedPtr node_base_interface,
50 const rclcpp::node_interfaces::NodeTopicsInterface::SharedPtr node_topics_interface,
51 const rclcpp::node_interfaces::NodeGraphInterface::SharedPtr node_graph_interface,
52 const rclcpp::node_interfaces::NodeServicesInterface::SharedPtr node_services_interface);
72 rclcpp::node_interfaces::NodeBaseInterface::SharedPtr node_base_;
73 rclcpp::node_interfaces::NodeTopicsInterface::SharedPtr node_topics_;
74 rclcpp::node_interfaces::NodeGraphInterface::SharedPtr node_graph_;
75 rclcpp::node_interfaces::NodeServicesInterface::SharedPtr node_services_;
78 using MessageT = builtin_interfaces::msg::Time;
84 void clock_cb(
const builtin_interfaces::msg::Time::SharedPtr msg);
90 using ParamMessageT = rcl_interfaces::msg::ParameterEvent;
95 void on_parameter_event(
const rcl_interfaces::msg::ParameterEvent::SharedPtr event);
98 enum UseSimTimeParameterState {UNSET, SET_TRUE, SET_FALSE};
99 UseSimTimeParameterState parameter_state_;
102 void enable_ros_time();
104 void disable_ros_time();
107 static void enable_ros_time(rclcpp::Clock::SharedPtr clock);
108 static void disable_ros_time(rclcpp::Clock::SharedPtr clock);
109 static void set_clock(
110 const builtin_interfaces::msg::Time::SharedPtr msg,
111 bool set_ros_time_enabled,
112 rclcpp::Clock::SharedPtr clock);
116 bool ros_time_active_;
118 builtin_interfaces::msg::Time::SharedPtr last_msg_set_;
128 #endif // RCLCPP__TIME_SOURCE_HPP_ Definition: time_source.hpp:35
Subscription implementation, templated on the type of message this subscription receives.
Definition: subscription.hpp:123
Definition: allocator_common.hpp:24
void attachNode(rclcpp::Node::SharedPtr node)
void detachClock(rclcpp::Clock::SharedPtr clock)
#define RCLCPP_PUBLIC
Definition: visibility_control.hpp:50
void attachClock(rclcpp::Clock::SharedPtr clock)
Attach a clock to the time source to be updated.