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"
28 
29 
30 namespace rclcpp
31 {
32 class Clock;
33 
35 {
36 public:
38  explicit TimeSource(rclcpp::Node::SharedPtr node);
39 
41  TimeSource();
42 
44  void attachNode(rclcpp::Node::SharedPtr node);
45 
47  void attachNode(
48  rclcpp::node_interfaces::NodeBaseInterface::SharedPtr node_base_interface,
49  rclcpp::node_interfaces::NodeTopicsInterface::SharedPtr node_topics_interface,
50  rclcpp::node_interfaces::NodeGraphInterface::SharedPtr node_graph_interface,
51  rclcpp::node_interfaces::NodeServicesInterface::SharedPtr node_services_interface,
52  rclcpp::node_interfaces::NodeLoggingInterface::SharedPtr node_logging_interface,
53  rclcpp::node_interfaces::NodeClockInterface::SharedPtr node_clock_interface,
54  rclcpp::node_interfaces::NodeParametersInterface::SharedPtr node_parameters_interface);
55 
57  void detachNode();
58 
60 
64  void attachClock(rclcpp::Clock::SharedPtr clock);
65 
67  void detachClock(rclcpp::Clock::SharedPtr clock);
68 
70  ~TimeSource();
71 
72 private:
73  // Preserve the node reference
74  rclcpp::node_interfaces::NodeBaseInterface::SharedPtr node_base_;
75  rclcpp::node_interfaces::NodeTopicsInterface::SharedPtr node_topics_;
76  rclcpp::node_interfaces::NodeGraphInterface::SharedPtr node_graph_;
77  rclcpp::node_interfaces::NodeServicesInterface::SharedPtr node_services_;
78  rclcpp::node_interfaces::NodeLoggingInterface::SharedPtr node_logging_;
79  rclcpp::node_interfaces::NodeClockInterface::SharedPtr node_clock_;
80  rclcpp::node_interfaces::NodeParametersInterface::SharedPtr node_parameters_;
81 
82  // Store (and update on node attach) logger for logging.
83  Logger logger_;
84 
85  // The subscription for the clock callback
86  using MessageT = rosgraph_msgs::msg::Clock;
89  std::shared_ptr<SubscriptionT> clock_subscription_;
90  std::mutex clock_sub_lock_;
91 
92  // The clock callback itself
93  void clock_cb(const rosgraph_msgs::msg::Clock::SharedPtr msg);
94 
95  // Create the subscription for the clock topic
96  void create_clock_sub();
97 
98  // Destroy the subscription for the clock topic
99  void destroy_clock_sub();
100 
101  // Parameter Event subscription
102  using ParamMessageT = rcl_interfaces::msg::ParameterEvent;
104  std::shared_ptr<ParamSubscriptionT> parameter_subscription_;
105 
106  // Callback for parameter updates
107  void on_parameter_event(const rcl_interfaces::msg::ParameterEvent::SharedPtr event);
108 
109  // An enum to hold the parameter state
110  enum UseSimTimeParameterState {UNSET, SET_TRUE, SET_FALSE};
111  UseSimTimeParameterState parameter_state_;
112 
113  // An internal method to use in the clock callback that iterates and enables all clocks
114  void enable_ros_time();
115  // An internal method to use in the clock callback that iterates and disables all clocks
116  void disable_ros_time();
117 
118  // Internal helper functions used inside iterators
119  static void enable_ros_time(rclcpp::Clock::SharedPtr clock);
120  static void disable_ros_time(rclcpp::Clock::SharedPtr clock);
121  static void set_clock(
122  const builtin_interfaces::msg::Time::SharedPtr msg,
123  bool set_ros_time_enabled,
124  rclcpp::Clock::SharedPtr clock);
125 
126  // Local storage of validity of ROS time
127  // This is needed when new clocks are added.
128  bool ros_time_active_;
129  // Last set message to be passed to newly registered clocks
130  rosgraph_msgs::msg::Clock::SharedPtr last_msg_set_;
131 
132  // A lock to protect iterating the associated_clocks_ field.
133  std::mutex clock_list_lock_;
134  // A vector to store references to associated clocks.
135  std::vector<rclcpp::Clock::SharedPtr> associated_clocks_;
136 };
137 
138 } // namespace rclcpp
139 
140 #endif // RCLCPP__TIME_SOURCE_HPP_
Definition: logger.hpp:77
This header provides the get_node_topics_interface() template function.
Definition: allocator_common.hpp:24
Subscription implementation, templated on the type of message this subscription receives.
Definition: subscription.hpp:59
#define RCLCPP_PUBLIC
Definition: visibility_control.hpp:50
void detachClock(rclcpp::Clock::SharedPtr clock)
Definition: time_source.hpp:34
void attachClock(rclcpp::Clock::SharedPtr clock)
Attach a clock to the time source to be updated.
void attachNode(rclcpp::Node::SharedPtr node)