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"    49     rclcpp::node_interfaces::NodeBaseInterface::SharedPtr node_base_interface,
    50     rclcpp::node_interfaces::NodeTopicsInterface::SharedPtr node_topics_interface,
    51     rclcpp::node_interfaces::NodeGraphInterface::SharedPtr node_graph_interface,
    52     rclcpp::node_interfaces::NodeServicesInterface::SharedPtr node_services_interface,
    53     rclcpp::node_interfaces::NodeLoggingInterface::SharedPtr node_logging_interface,
    54     rclcpp::node_interfaces::NodeClockInterface::SharedPtr node_clock_interface,
    55     rclcpp::node_interfaces::NodeParametersInterface::SharedPtr node_parameters_interface);
    75   rclcpp::node_interfaces::NodeBaseInterface::SharedPtr node_base_;
    76   rclcpp::node_interfaces::NodeTopicsInterface::SharedPtr node_topics_;
    77   rclcpp::node_interfaces::NodeGraphInterface::SharedPtr node_graph_;
    78   rclcpp::node_interfaces::NodeServicesInterface::SharedPtr node_services_;
    79   rclcpp::node_interfaces::NodeLoggingInterface::SharedPtr node_logging_;
    80   rclcpp::node_interfaces::NodeClockInterface::SharedPtr node_clock_;
    81   rclcpp::node_interfaces::NodeParametersInterface::SharedPtr node_parameters_;
    87   using MessageT = rosgraph_msgs::msg::Clock;
    94   void clock_cb(
const rosgraph_msgs::msg::Clock::SharedPtr msg);
    97   void create_clock_sub();
   100   void destroy_clock_sub();
   103   using ParamMessageT = rcl_interfaces::msg::ParameterEvent;
   108   void on_parameter_event(
const rcl_interfaces::msg::ParameterEvent::SharedPtr event);
   111   enum UseSimTimeParameterState {UNSET, SET_TRUE, SET_FALSE};
   112   UseSimTimeParameterState parameter_state_;
   115   void enable_ros_time();
   117   void disable_ros_time();
   122   static void set_clock(
   123     const builtin_interfaces::msg::Time::SharedPtr msg,
   124     bool set_ros_time_enabled,
   129   bool ros_time_active_;
   131   rosgraph_msgs::msg::Clock::SharedPtr last_msg_set_;
   138   rclcpp::node_interfaces::OnSetParametersCallbackHandle::SharedPtr sim_time_cb_handler_ = 
nullptr;
   143 #endif  // RCLCPP__TIME_SOURCE_HPP_ Definition: logger.hpp:77
 
This header provides the get_node_base_interface() template function. 
Definition: allocator_common.hpp:24
 
Subscription implementation, templated on the type of message this subscription receives. 
Definition: subscription.hpp:67
 
#define RCLCPP_PUBLIC
Definition: visibility_control.hpp:50
 
Set the data type used in the intra-process buffer as std::shared_ptr<MessageT> 
 
void detachClock(rclcpp::Clock::SharedPtr clock)
 
Definition: time_source.hpp:35
 
void attachClock(rclcpp::Clock::SharedPtr clock)
Attach a clock to the time source to be updated. 
 
void attachNode(rclcpp::Node::SharedPtr node)