ROS 2 rclcpp + rcl - jazzy  jazzy
ROS 2 C++ Client Library with ROS Client Library
time_source.hpp
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 #include "rclcpp/executors.hpp"
29 #include "rclcpp/node_interfaces/node_parameters_interface.hpp"
30 
31 
32 namespace rclcpp
33 {
34 class Clock;
35 
51 {
52 public:
54 
61  RCLCPP_PUBLIC
62  explicit TimeSource(
63  rclcpp::Node::SharedPtr node,
64  const rclcpp::QoS & qos = rclcpp::ClockQoS(),
65  bool use_clock_thread = true);
66 
68 
74  RCLCPP_PUBLIC
75  explicit TimeSource(
76  const rclcpp::QoS & qos = rclcpp::ClockQoS(),
77  bool use_clock_thread = true);
78 
79  // The TimeSource is uncopyable
80  TimeSource(const TimeSource &) = delete;
81  TimeSource & operator=(const TimeSource &) = delete;
82 
83  // The TimeSource is moveable
84  TimeSource(TimeSource &&) = default;
85  TimeSource & operator=(TimeSource &&) = default;
86 
88 
91  RCLCPP_PUBLIC
92  void attachNode(rclcpp::Node::SharedPtr node);
93 
95 
107  RCLCPP_PUBLIC
108  void attachNode(
109  rclcpp::node_interfaces::NodeBaseInterface::SharedPtr node_base_interface,
110  rclcpp::node_interfaces::NodeTopicsInterface::SharedPtr node_topics_interface,
111  rclcpp::node_interfaces::NodeGraphInterface::SharedPtr node_graph_interface,
112  rclcpp::node_interfaces::NodeServicesInterface::SharedPtr node_services_interface,
113  rclcpp::node_interfaces::NodeLoggingInterface::SharedPtr node_logging_interface,
114  rclcpp::node_interfaces::NodeClockInterface::SharedPtr node_clock_interface,
115  rclcpp::node_interfaces::NodeParametersInterface::SharedPtr node_parameters_interface);
116 
118  RCLCPP_PUBLIC
119  void detachNode();
120 
122 
126  RCLCPP_PUBLIC
127  void attachClock(rclcpp::Clock::SharedPtr clock);
128 
130  RCLCPP_PUBLIC
131  void detachClock(rclcpp::Clock::SharedPtr clock);
132 
134  RCLCPP_PUBLIC
135  bool get_use_clock_thread();
136 
138  RCLCPP_PUBLIC
139  void set_use_clock_thread(bool use_clock_thread);
140 
142  RCLCPP_PUBLIC
144 
146  RCLCPP_PUBLIC
147  ~TimeSource();
148 
149 private:
150  class NodeState;
151  std::shared_ptr<NodeState> node_state_;
152 
153  // Preserve the arguments received by the constructor for reuse at runtime
154  bool constructed_use_clock_thread_;
155  rclcpp::QoS constructed_qos_;
156 };
157 
158 } // namespace rclcpp
159 
160 #endif // RCLCPP__TIME_SOURCE_HPP_
Encapsulation of Quality of Service settings.
Definition: qos.hpp:116
RCLCPP_PUBLIC bool get_use_clock_thread()
Get whether a separate clock thread is used or not.
RCLCPP_PUBLIC void attachClock(rclcpp::Clock::SharedPtr clock)
Attach a clock to the time source to be updated.
RCLCPP_PUBLIC void detachClock(rclcpp::Clock::SharedPtr clock)
Detach a clock from the time source.
RCLCPP_PUBLIC void set_use_clock_thread(bool use_clock_thread)
Set whether to use a separate clock thread or not.
RCLCPP_PUBLIC TimeSource(rclcpp::Node::SharedPtr node, const rclcpp::QoS &qos=rclcpp::ClockQoS(), bool use_clock_thread=true)
Constructor.
RCLCPP_PUBLIC bool clock_thread_is_joinable()
Check if the clock thread is joinable.
RCLCPP_PUBLIC ~TimeSource()
TimeSource Destructor.
RCLCPP_PUBLIC void detachNode()
Detach the node from the time source.
RCLCPP_PUBLIC void attachNode(rclcpp::Node::SharedPtr node)
Attach node to the time source.
Versions of rosidl_typesupport_cpp::get_message_type_support_handle that handle adapted types.