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