rclcpp  master
C++ ROS Client Library API
time_source.hpp
Go to the documentation of this file.
1 // Copyright 2017 Open Source Robotics Foundation, Inc.
2 //
3 // Licensed under the Apache License, Version 2.0 (the "License");
4 // you may not use this file except in compliance with the License.
5 // You may obtain a copy of the License at
6 //
7 // http://www.apache.org/licenses/LICENSE-2.0
8 //
9 // Unless required by applicable law or agreed to in writing, software
10 // distributed under the License is distributed on an "AS IS" BASIS,
11 // WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.
12 // See the License for the specific language governing permissions and
13 // limitations under the License.
14 
15 #ifndef RCLCPP__TIME_SOURCE_HPP_
16 #define RCLCPP__TIME_SOURCE_HPP_
17 
18 #include <memory>
19 #include <vector>
20 
21 #include "rcl/time.h"
22 
23 #include "builtin_interfaces/msg/time.hpp"
24 #include "rosgraph_msgs/msg/clock.hpp"
25 #include "rcl_interfaces/msg/parameter_event.hpp"
26 
27 #include "rclcpp/node.hpp"
29 
30 
31 namespace rclcpp
32 {
33 class Clock;
34 
36 {
37 public:
39  explicit TimeSource(rclcpp::Node::SharedPtr node);
40 
42  TimeSource();
43 
46 
48  void attachNode(
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);
56 
58  void detachNode();
59 
61 
66 
69 
71  ~TimeSource();
72 
73 private:
74  // Preserve the node reference
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_;
82 
83  // Store (and update on node attach) logger for logging.
84  Logger logger_;
85 
86  // The subscription for the clock callback
87  using MessageT = rosgraph_msgs::msg::Clock;
90  std::shared_ptr<SubscriptionT> clock_subscription_;
91  std::mutex clock_sub_lock_;
92 
93  // The clock callback itself
94  void clock_cb(const rosgraph_msgs::msg::Clock::SharedPtr msg);
95 
96  // Create the subscription for the clock topic
97  void create_clock_sub();
98 
99  // Destroy the subscription for the clock topic
100  void destroy_clock_sub();
101 
102  // Parameter Event subscription
103  using ParamMessageT = rcl_interfaces::msg::ParameterEvent;
105  std::shared_ptr<ParamSubscriptionT> parameter_subscription_;
106 
107  // Callback for parameter updates
108  void on_parameter_event(const rcl_interfaces::msg::ParameterEvent::SharedPtr event);
109 
110  // An enum to hold the parameter state
111  enum UseSimTimeParameterState {UNSET, SET_TRUE, SET_FALSE};
112  UseSimTimeParameterState parameter_state_;
113 
114  // An internal method to use in the clock callback that iterates and enables all clocks
115  void enable_ros_time();
116  // An internal method to use in the clock callback that iterates and disables all clocks
117  void disable_ros_time();
118 
119  // Internal helper functions used inside iterators
120  static void enable_ros_time(rclcpp::Clock::SharedPtr clock);
121  static void disable_ros_time(rclcpp::Clock::SharedPtr clock);
122  static void set_clock(
123  const builtin_interfaces::msg::Time::SharedPtr msg,
124  bool set_ros_time_enabled,
126 
127  // Local storage of validity of ROS time
128  // This is needed when new clocks are added.
129  bool ros_time_active_;
130  // Last set message to be passed to newly registered clocks
131  rosgraph_msgs::msg::Clock::SharedPtr last_msg_set_;
132 
133  // A lock to protect iterating the associated_clocks_ field.
134  std::mutex clock_list_lock_;
135  // A vector to store references to associated clocks.
136  std::vector<rclcpp::Clock::SharedPtr> associated_clocks_;
137  // A handler for the use_sim_time parameter callback.
138  rclcpp::node_interfaces::OnSetParametersCallbackHandle::SharedPtr sim_time_cb_handler_ = nullptr;
139 };
140 
141 } // namespace rclcpp
142 
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)