ROS 2 rclcpp + rcl - humble  humble
ROS 2 C++ Client Library with ROS Client Library
time_source.cpp
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 #include <memory>
16 #include <string>
17 #include <utility>
18 #include <vector>
19 
20 #include "builtin_interfaces/msg/time.hpp"
21 
22 #include "rcl/time.h"
23 
24 #include "rclcpp/clock.hpp"
25 #include "rclcpp/exceptions.hpp"
26 #include "rclcpp/logging.hpp"
27 #include "rclcpp/node.hpp"
28 #include "rclcpp/parameter_client.hpp"
29 #include "rclcpp/parameter_events_filter.hpp"
30 #include "rclcpp/time.hpp"
31 #include "rclcpp/time_source.hpp"
32 
33 namespace rclcpp
34 {
35 
36 class ClocksState final
37 {
38 public:
39  ClocksState()
40  : logger_(rclcpp::get_logger("rclcpp"))
41  {
42  }
43 
44  // An internal method to use in the clock callback that iterates and enables all clocks
45  void enable_ros_time()
46  {
47  if (ros_time_active_) {
48  // already enabled no-op
49  return;
50  }
51 
52  // Local storage
53  ros_time_active_ = true;
54 
55  // Update all attached clocks to zero or last recorded time
56  std::lock_guard<std::mutex> guard(clock_list_lock_);
57  auto time_msg = std::make_shared<builtin_interfaces::msg::Time>();
58  if (last_msg_set_) {
59  time_msg = std::make_shared<builtin_interfaces::msg::Time>(last_msg_set_->clock);
60  }
61  for (auto it = associated_clocks_.begin(); it != associated_clocks_.end(); ++it) {
62  set_clock(time_msg, true, *it);
63  }
64  }
65 
66  // An internal method to use in the clock callback that iterates and disables all clocks
67  void disable_ros_time()
68  {
69  if (!ros_time_active_) {
70  // already disabled no-op
71  return;
72  }
73 
74  // Local storage
75  ros_time_active_ = false;
76 
77  // Update all attached clocks
78  std::lock_guard<std::mutex> guard(clock_list_lock_);
79  for (auto it = associated_clocks_.begin(); it != associated_clocks_.end(); ++it) {
80  auto msg = std::make_shared<builtin_interfaces::msg::Time>();
81  set_clock(msg, false, *it);
82  }
83  }
84 
85  // Check if ROS time is active
86  bool is_ros_time_active() const
87  {
88  return ros_time_active_;
89  }
90 
91  // Attach a clock
92  void attachClock(rclcpp::Clock::SharedPtr clock)
93  {
94  if (clock->get_clock_type() != RCL_ROS_TIME) {
95  throw std::invalid_argument("Cannot attach clock to a time source that's not a ROS clock");
96  }
97 
98  std::lock_guard<std::mutex> guard(clock_list_lock_);
99  associated_clocks_.push_back(clock);
100  // Set the clock to zero unless there's a recently received message
101  auto time_msg = std::make_shared<builtin_interfaces::msg::Time>();
102  if (last_msg_set_) {
103  time_msg = std::make_shared<builtin_interfaces::msg::Time>(last_msg_set_->clock);
104  }
105  set_clock(time_msg, ros_time_active_, clock);
106  }
107 
108  // Detach a clock
109  void detachClock(rclcpp::Clock::SharedPtr clock)
110  {
111  std::lock_guard<std::mutex> guard(clock_list_lock_);
112  auto result = std::find(associated_clocks_.begin(), associated_clocks_.end(), clock);
113  if (result != associated_clocks_.end()) {
114  associated_clocks_.erase(result);
115  } else {
116  RCLCPP_ERROR(logger_, "failed to remove clock");
117  }
118  }
119 
120  // Internal helper function used inside iterators
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  std::lock_guard<std::mutex> clock_guard(clock->get_clock_mutex());
127 
128  // Do change
129  if (!set_ros_time_enabled && clock->ros_time_is_active()) {
130  auto ret = rcl_disable_ros_time_override(clock->get_clock_handle());
131  if (ret != RCL_RET_OK) {
132  rclcpp::exceptions::throw_from_rcl_error(
133  ret, "Failed to disable ros_time_override_status");
134  }
135  } else if (set_ros_time_enabled && !clock->ros_time_is_active()) {
136  auto ret = rcl_enable_ros_time_override(clock->get_clock_handle());
137  if (ret != RCL_RET_OK) {
138  rclcpp::exceptions::throw_from_rcl_error(
139  ret, "Failed to enable ros_time_override_status");
140  }
141  }
142 
143  auto ret = rcl_set_ros_time_override(
144  clock->get_clock_handle(),
145  rclcpp::Time(*msg).nanoseconds());
146  if (ret != RCL_RET_OK) {
147  rclcpp::exceptions::throw_from_rcl_error(
148  ret, "Failed to set ros_time_override_status");
149  }
150  }
151 
152  // Internal helper function
153  void set_all_clocks(
154  const builtin_interfaces::msg::Time::SharedPtr msg,
155  bool set_ros_time_enabled)
156  {
157  std::lock_guard<std::mutex> guard(clock_list_lock_);
158  for (auto it = associated_clocks_.begin(); it != associated_clocks_.end(); ++it) {
159  set_clock(msg, set_ros_time_enabled, *it);
160  }
161  }
162 
163  // Cache the last clock message received
164  void cache_last_msg(std::shared_ptr<const rosgraph_msgs::msg::Clock> msg)
165  {
166  last_msg_set_ = msg;
167  }
168 
169 private:
170  // Store (and update on node attach) logger for logging.
171  Logger logger_;
172 
173  // A lock to protect iterating the associated_clocks_ field.
174  std::mutex clock_list_lock_;
175  // A vector to store references to associated clocks.
176  std::vector<rclcpp::Clock::SharedPtr> associated_clocks_;
177 
178  // Local storage of validity of ROS time
179  // This is needed when new clocks are added.
180  bool ros_time_active_{false};
181  // Last set message to be passed to newly registered clocks
182  std::shared_ptr<const rosgraph_msgs::msg::Clock> last_msg_set_;
183 };
184 
186 {
187 public:
188  NodeState(const rclcpp::QoS & qos, bool use_clock_thread)
189  : use_clock_thread_(use_clock_thread),
190  logger_(rclcpp::get_logger("rclcpp")),
191  qos_(qos)
192  {
193  }
194 
195  ~NodeState()
196  {
197  if (
198  node_base_ || node_topics_ || node_graph_ || node_services_ ||
199  node_logging_ || node_clock_ || node_parameters_)
200  {
201  detachNode();
202  }
203  }
204 
205  // Check if a clock thread will be used
206  bool get_use_clock_thread()
207  {
208  return use_clock_thread_;
209  }
210 
211  // Set whether a clock thread will be used
212  void set_use_clock_thread(bool use_clock_thread)
213  {
214  use_clock_thread_ = use_clock_thread;
215  }
216 
217  // Check if the clock thread is joinable
218  bool clock_thread_is_joinable()
219  {
220  return clock_executor_thread_.joinable();
221  }
222 
223  // Attach a node to this time source
224  void attachNode(
225  rclcpp::node_interfaces::NodeBaseInterface::SharedPtr node_base_interface,
226  rclcpp::node_interfaces::NodeTopicsInterface::SharedPtr node_topics_interface,
227  rclcpp::node_interfaces::NodeGraphInterface::SharedPtr node_graph_interface,
228  rclcpp::node_interfaces::NodeServicesInterface::SharedPtr node_services_interface,
229  rclcpp::node_interfaces::NodeLoggingInterface::SharedPtr node_logging_interface,
230  rclcpp::node_interfaces::NodeClockInterface::SharedPtr node_clock_interface,
231  rclcpp::node_interfaces::NodeParametersInterface::SharedPtr node_parameters_interface)
232  {
233  node_base_ = node_base_interface;
234  node_topics_ = node_topics_interface;
235  node_graph_ = node_graph_interface;
236  node_services_ = node_services_interface;
237  node_logging_ = node_logging_interface;
238  node_clock_ = node_clock_interface;
239  node_parameters_ = node_parameters_interface;
240  // TODO(tfoote): Update QOS
241 
242  logger_ = node_logging_->get_logger();
243 
244  // Though this defaults to false, it can be overridden by initial parameter values for the
245  // node, which may be given by the user at the node's construction or even by command-line
246  // arguments.
247  rclcpp::ParameterValue use_sim_time_param;
248  const std::string use_sim_time_name = "use_sim_time";
249  if (!node_parameters_->has_parameter(use_sim_time_name)) {
250  use_sim_time_param = node_parameters_->declare_parameter(
251  use_sim_time_name,
252  rclcpp::ParameterValue(false));
253  } else {
254  use_sim_time_param = node_parameters_->get_parameter(use_sim_time_name).get_parameter_value();
255  }
256  if (use_sim_time_param.get_type() == rclcpp::PARAMETER_BOOL) {
257  if (use_sim_time_param.get<bool>()) {
258  parameter_state_ = SET_TRUE;
259  clocks_state_.enable_ros_time();
260  create_clock_sub();
261  }
262  } else {
263  RCLCPP_ERROR(
264  logger_, "Invalid type '%s' for parameter 'use_sim_time', should be 'bool'",
265  rclcpp::to_string(use_sim_time_param.get_type()).c_str());
266  throw std::invalid_argument("Invalid type for parameter 'use_sim_time', should be 'bool'");
267  }
268 
269  // TODO(tfoote) use parameters interface not subscribe to events via topic ticketed #609
270  parameter_subscription_ = rclcpp::AsyncParametersClient::on_parameter_event(
271  node_topics_,
272  [this](std::shared_ptr<const rcl_interfaces::msg::ParameterEvent> event) {
273  if (node_base_ != nullptr) {
274  this->on_parameter_event(event);
275  }
276  // Do nothing if node_base_ is nullptr because it means the TimeSource is now
277  // without an attached node
278  });
279  }
280 
281  // Detach the attached node
282  void detachNode()
283  {
284  // destroy_clock_sub() *must* be first here, to ensure that the executor
285  // can't possibly call any of the callbacks as we are cleaning up.
286  destroy_clock_sub();
287  clocks_state_.disable_ros_time();
288  parameter_subscription_.reset();
289  node_base_.reset();
290  node_topics_.reset();
291  node_graph_.reset();
292  node_services_.reset();
293  node_logging_.reset();
294  node_clock_.reset();
295  node_parameters_.reset();
296  }
297 
298  void attachClock(std::shared_ptr<rclcpp::Clock> clock)
299  {
300  clocks_state_.attachClock(std::move(clock));
301  }
302 
303  void detachClock(std::shared_ptr<rclcpp::Clock> clock)
304  {
305  clocks_state_.detachClock(std::move(clock));
306  }
307 
308 private:
309  ClocksState clocks_state_;
310 
311  // Dedicated thread for clock subscription.
312  bool use_clock_thread_;
313  std::thread clock_executor_thread_;
314 
315  // Preserve the node reference
316  rclcpp::node_interfaces::NodeBaseInterface::SharedPtr node_base_{nullptr};
317  rclcpp::node_interfaces::NodeTopicsInterface::SharedPtr node_topics_{nullptr};
318  rclcpp::node_interfaces::NodeGraphInterface::SharedPtr node_graph_{nullptr};
319  rclcpp::node_interfaces::NodeServicesInterface::SharedPtr node_services_{nullptr};
320  rclcpp::node_interfaces::NodeLoggingInterface::SharedPtr node_logging_{nullptr};
321  rclcpp::node_interfaces::NodeClockInterface::SharedPtr node_clock_{nullptr};
322  rclcpp::node_interfaces::NodeParametersInterface::SharedPtr node_parameters_{nullptr};
323 
324  // Store (and update on node attach) logger for logging.
325  Logger logger_;
326 
327  // QoS of the clock subscription.
328  rclcpp::QoS qos_;
329 
330  // The subscription for the clock callback
332  std::shared_ptr<SubscriptionT> clock_subscription_{nullptr};
333  std::mutex clock_sub_lock_;
334  rclcpp::CallbackGroup::SharedPtr clock_callback_group_;
335  rclcpp::executors::SingleThreadedExecutor::SharedPtr clock_executor_;
336  std::promise<void> cancel_clock_executor_promise_;
337 
338  // The clock callback itself
339  void clock_cb(std::shared_ptr<const rosgraph_msgs::msg::Clock> msg)
340  {
341  if (!clocks_state_.is_ros_time_active() && SET_TRUE == this->parameter_state_) {
342  clocks_state_.enable_ros_time();
343  }
344  // Cache the last message in case a new clock is attached.
345  clocks_state_.cache_last_msg(msg);
346  auto time_msg = std::make_shared<builtin_interfaces::msg::Time>(msg->clock);
347 
348  if (SET_TRUE == this->parameter_state_) {
349  clocks_state_.set_all_clocks(time_msg, true);
350  }
351  }
352 
353  // Create the subscription for the clock topic
354  void create_clock_sub()
355  {
356  std::lock_guard<std::mutex> guard(clock_sub_lock_);
357  if (clock_subscription_) {
358  // Subscription already created.
359  return;
360  }
361 
363  options.qos_overriding_options = rclcpp::QosOverridingOptions(
364  {
365  rclcpp::QosPolicyKind::Depth,
366  rclcpp::QosPolicyKind::Durability,
367  rclcpp::QosPolicyKind::History,
368  rclcpp::QosPolicyKind::Reliability,
369  });
370 
371  if (use_clock_thread_) {
372  clock_callback_group_ = node_base_->create_callback_group(
373  rclcpp::CallbackGroupType::MutuallyExclusive,
374  false
375  );
376  options.callback_group = clock_callback_group_;
377  rclcpp::ExecutorOptions exec_options;
378  exec_options.context = node_base_->get_context();
379  clock_executor_ =
380  std::make_shared<rclcpp::executors::SingleThreadedExecutor>(exec_options);
381  if (!clock_executor_thread_.joinable()) {
382  cancel_clock_executor_promise_ = std::promise<void>{};
383  clock_executor_thread_ = std::thread(
384  [this]() {
385  auto future = cancel_clock_executor_promise_.get_future();
386  clock_executor_->add_callback_group(clock_callback_group_, node_base_);
387  clock_executor_->spin_until_future_complete(future);
388  }
389  );
390  }
391  }
392 
393  clock_subscription_ = rclcpp::create_subscription<rosgraph_msgs::msg::Clock>(
394  node_parameters_,
395  node_topics_,
396  "/clock",
397  qos_,
398  [this](std::shared_ptr<const rosgraph_msgs::msg::Clock> msg) {
399  // We are using node_base_ as an indication if there is a node attached.
400  // Only call the clock_cb if that is the case.
401  if (node_base_ != nullptr) {
402  clock_cb(msg);
403  }
404  },
405  options
406  );
407  }
408 
409  // Destroy the subscription for the clock topic
410  void destroy_clock_sub()
411  {
412  std::lock_guard<std::mutex> guard(clock_sub_lock_);
413  if (clock_executor_thread_.joinable()) {
414  cancel_clock_executor_promise_.set_value();
415  clock_executor_->cancel();
416  clock_executor_thread_.join();
417  clock_executor_->remove_callback_group(clock_callback_group_);
418  }
419  clock_subscription_.reset();
420  }
421 
422  // Parameter Event subscription
424  std::shared_ptr<ParamSubscriptionT> parameter_subscription_;
425 
426  // Callback for parameter updates
427  void on_parameter_event(std::shared_ptr<const rcl_interfaces::msg::ParameterEvent> event)
428  {
429  // Filter out events on 'use_sim_time' parameter instances in other nodes.
430  if (event->node != node_base_->get_fully_qualified_name()) {
431  return;
432  }
433  // Filter for only 'use_sim_time' being added or changed.
434  rclcpp::ParameterEventsFilter filter(event, {"use_sim_time"},
435  {rclcpp::ParameterEventsFilter::EventType::NEW,
436  rclcpp::ParameterEventsFilter::EventType::CHANGED});
437  for (auto & it : filter.get_events()) {
438  if (it.second->value.type != ParameterType::PARAMETER_BOOL) {
439  RCLCPP_ERROR(logger_, "use_sim_time parameter cannot be set to anything but a bool");
440  continue;
441  }
442  if (it.second->value.bool_value) {
443  parameter_state_ = SET_TRUE;
444  clocks_state_.enable_ros_time();
445  create_clock_sub();
446  } else {
447  parameter_state_ = SET_FALSE;
448  destroy_clock_sub();
449  clocks_state_.disable_ros_time();
450  }
451  }
452  // Handle the case that use_sim_time was deleted.
453  rclcpp::ParameterEventsFilter deleted(event, {"use_sim_time"},
454  {rclcpp::ParameterEventsFilter::EventType::DELETED});
455  for (auto & it : deleted.get_events()) {
456  (void) it; // if there is a match it's already matched, don't bother reading it.
457  // If the parameter is deleted mark it as unset but don't change state.
458  parameter_state_ = UNSET;
459  }
460  }
461 
462  // An enum to hold the parameter state
463  enum UseSimTimeParameterState {UNSET, SET_TRUE, SET_FALSE};
464  UseSimTimeParameterState parameter_state_;
465 };
466 
468  std::shared_ptr<rclcpp::Node> node,
469  const rclcpp::QoS & qos,
470  bool use_clock_thread)
471 : TimeSource(qos, use_clock_thread)
472 {
473  attachNode(node);
474 }
475 
477  const rclcpp::QoS & qos,
478  bool use_clock_thread)
479 : constructed_use_clock_thread_(use_clock_thread),
480  constructed_qos_(qos)
481 {
482  node_state_ = std::make_shared<NodeState>(qos, use_clock_thread);
483 }
484 
485 void TimeSource::attachNode(rclcpp::Node::SharedPtr node)
486 {
487  node_state_->set_use_clock_thread(node->get_node_options().use_clock_thread());
488  attachNode(
489  node->get_node_base_interface(),
490  node->get_node_topics_interface(),
491  node->get_node_graph_interface(),
492  node->get_node_services_interface(),
493  node->get_node_logging_interface(),
494  node->get_node_clock_interface(),
495  node->get_node_parameters_interface());
496 }
497 
499  rclcpp::node_interfaces::NodeBaseInterface::SharedPtr node_base_interface,
500  rclcpp::node_interfaces::NodeTopicsInterface::SharedPtr node_topics_interface,
501  rclcpp::node_interfaces::NodeGraphInterface::SharedPtr node_graph_interface,
502  rclcpp::node_interfaces::NodeServicesInterface::SharedPtr node_services_interface,
503  rclcpp::node_interfaces::NodeLoggingInterface::SharedPtr node_logging_interface,
504  rclcpp::node_interfaces::NodeClockInterface::SharedPtr node_clock_interface,
505  rclcpp::node_interfaces::NodeParametersInterface::SharedPtr node_parameters_interface)
506 {
507  node_state_->attachNode(
508  std::move(node_base_interface),
509  std::move(node_topics_interface),
510  std::move(node_graph_interface),
511  std::move(node_services_interface),
512  std::move(node_logging_interface),
513  std::move(node_clock_interface),
514  std::move(node_parameters_interface));
515 }
516 
518 {
519  node_state_.reset();
520  node_state_ = std::make_shared<NodeState>(
521  constructed_qos_,
522  constructed_use_clock_thread_);
523 }
524 
525 void TimeSource::attachClock(std::shared_ptr<rclcpp::Clock> clock)
526 {
527  node_state_->attachClock(std::move(clock));
528 }
529 
530 void TimeSource::detachClock(std::shared_ptr<rclcpp::Clock> clock)
531 {
532  node_state_->detachClock(std::move(clock));
533 }
534 
536 {
537  return node_state_->get_use_clock_thread();
538 }
539 
540 void TimeSource::set_use_clock_thread(bool use_clock_thread)
541 {
542  node_state_->set_use_clock_thread(use_clock_thread);
543 }
544 
546 {
547  return node_state_->clock_thread_is_joinable();
548 }
549 
551 {
552 }
553 
554 } // namespace rclcpp
Store the type and value of a parameter.
RCLCPP_PUBLIC ParameterType get_type() const
Return an enum indicating the type of the set value.
Encapsulation of Quality of Service settings.
Definition: qos.hpp:111
Options that are passed in subscription/publisher constructor to specify QoSConfigurability.
Subscription implementation, templated on the type of message this subscription receives.
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.
RCLCPP_PUBLIC rcl_time_point_value_t nanoseconds() const
Get the nanoseconds since epoch.
Definition: time.cpp:219
Versions of rosidl_typesupport_cpp::get_message_type_support_handle that handle adapted types.
RCLCPP_PUBLIC std::string to_string(const FutureReturnCode &future_return_code)
String conversion function for FutureReturnCode.
RCLCPP_PUBLIC Logger get_logger(const std::string &name)
Return a named logger.
Definition: logger.cpp:27
Options to be passed to the executor constructor.
rclcpp::CallbackGroup::SharedPtr callback_group
The callback group for this subscription. NULL to use the default callback group.
RCL_PUBLIC RCL_WARN_UNUSED rcl_ret_t rcl_enable_ros_time_override(rcl_clock_t *clock)
Enable the ROS time abstraction override.
Definition: time.c:299
RCL_PUBLIC RCL_WARN_UNUSED rcl_ret_t rcl_disable_ros_time_override(rcl_clock_t *clock)
Disable the ROS time abstraction override.
Definition: time.c:321
@ RCL_ROS_TIME
Use ROS time.
Definition: time.h:66
RCL_PUBLIC RCL_WARN_UNUSED rcl_ret_t rcl_set_ros_time_override(rcl_clock_t *clock, rcl_time_point_value_t time_value)
Set the current time for this RCL_ROS_TIME time source.
Definition: time.c:361
#define RCL_RET_OK
Success return code.
Definition: types.h:26