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 "rcl_interfaces/msg/parameter_event.hpp"
25 
26 #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 
45  void attachNode(rclcpp::Node::SharedPtr node);
46 
48  void attachNode(
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);
53 
55  void detachNode();
56 
58 
62  void attachClock(rclcpp::Clock::SharedPtr clock);
63 
65  void detachClock(rclcpp::Clock::SharedPtr clock);
66 
68  ~TimeSource();
69 
70 private:
71  // Preserve the node reference
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_;
76 
77  // The subscription for the clock callback
78  using MessageT = builtin_interfaces::msg::Time;
81  std::shared_ptr<SubscriptionT> clock_subscription_;
82 
83  // The clock callback itself
84  void clock_cb(const builtin_interfaces::msg::Time::SharedPtr msg);
85 
86  // Parameter Client pointer
88 
89  // Parameter Event subscription
90  using ParamMessageT = rcl_interfaces::msg::ParameterEvent;
92  std::shared_ptr<ParamSubscriptionT> parameter_subscription_;
93 
94  // Callback for parameter updates
95  void on_parameter_event(const rcl_interfaces::msg::ParameterEvent::SharedPtr event);
96 
97  // An enum to hold the parameter state
98  enum UseSimTimeParameterState {UNSET, SET_TRUE, SET_FALSE};
99  UseSimTimeParameterState parameter_state_;
100 
101  // An internal method to use in the clock callback that iterates and enables all clocks
102  void enable_ros_time();
103  // An internal method to use in the clock callback that iterates and disables all clocks
104  void disable_ros_time();
105 
106  // Internal helper functions used inside iterators
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);
113 
114  // Local storage of validity of ROS time
115  // This is needed when new clocks are added.
116  bool ros_time_active_;
117  // Last set message to be passed to newly registered clocks
118  builtin_interfaces::msg::Time::SharedPtr last_msg_set_;
119 
120  // A lock to protect iterating the associated_clocks_ field.
121  std::mutex clock_list_lock_;
122  // A vector to store references to associated clocks.
123  std::vector<rclcpp::Clock::SharedPtr> associated_clocks_;
124 };
125 
126 } // namespace rclcpp
127 
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.