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" 40 explicit TimeSource(rclcpp::Node::SharedPtr node);
50 const rclcpp::node_interfaces::NodeBaseInterface::SharedPtr node_base_interface,
51 const rclcpp::node_interfaces::NodeTopicsInterface::SharedPtr node_topics_interface,
52 const rclcpp::node_interfaces::NodeGraphInterface::SharedPtr node_graph_interface,
53 const rclcpp::node_interfaces::NodeServicesInterface::SharedPtr node_services_interface);
73 rclcpp::node_interfaces::NodeBaseInterface::SharedPtr node_base_;
74 rclcpp::node_interfaces::NodeTopicsInterface::SharedPtr node_topics_;
75 rclcpp::node_interfaces::NodeGraphInterface::SharedPtr node_graph_;
76 rclcpp::node_interfaces::NodeServicesInterface::SharedPtr node_services_;
79 using MessageT = rosgraph_msgs::msg::Clock;
85 void clock_cb(
const rosgraph_msgs::msg::Clock::SharedPtr msg);
91 using ParamMessageT = rcl_interfaces::msg::ParameterEvent;
96 void on_parameter_event(
const rcl_interfaces::msg::ParameterEvent::SharedPtr event);
99 enum UseSimTimeParameterState {UNSET, SET_TRUE, SET_FALSE};
100 UseSimTimeParameterState parameter_state_;
103 void enable_ros_time();
105 void disable_ros_time();
108 static void enable_ros_time(rclcpp::Clock::SharedPtr clock);
109 static void disable_ros_time(rclcpp::Clock::SharedPtr clock);
110 static void set_clock(
111 const builtin_interfaces::msg::Time::SharedPtr msg,
112 bool set_ros_time_enabled,
113 rclcpp::Clock::SharedPtr clock);
117 bool ros_time_active_;
119 rosgraph_msgs::msg::Clock::SharedPtr last_msg_set_;
129 #endif // RCLCPP__TIME_SOURCE_HPP_ Definition: time_source.hpp:36
Subscription implementation, templated on the type of message this subscription receives.
Definition: subscription.hpp:147
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.