20 #include "builtin_interfaces/msg/time.hpp"
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"
45 void enable_ros_time()
47 if (ros_time_active_) {
53 ros_time_active_ =
true;
56 std::lock_guard<std::mutex> guard(clock_list_lock_);
57 auto time_msg = std::make_shared<builtin_interfaces::msg::Time>();
59 time_msg = std::make_shared<builtin_interfaces::msg::Time>(last_msg_set_->clock);
61 for (
auto it = associated_clocks_.begin(); it != associated_clocks_.end(); ++it) {
62 set_clock(time_msg,
true, *it);
67 void disable_ros_time()
69 if (!ros_time_active_) {
75 ros_time_active_ =
false;
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);
86 bool is_ros_time_active()
const
88 return ros_time_active_;
92 void attachClock(rclcpp::Clock::SharedPtr clock)
95 throw std::invalid_argument(
"Cannot attach clock to a time source that's not a ROS clock");
98 std::lock_guard<std::mutex> guard(clock_list_lock_);
99 associated_clocks_.push_back(clock);
101 auto time_msg = std::make_shared<builtin_interfaces::msg::Time>();
103 time_msg = std::make_shared<builtin_interfaces::msg::Time>(last_msg_set_->clock);
105 set_clock(time_msg, ros_time_active_, clock);
109 void detachClock(rclcpp::Clock::SharedPtr clock)
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);
116 RCLCPP_ERROR(logger_,
"failed to remove 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)
126 std::lock_guard<std::mutex> clock_guard(clock->get_clock_mutex());
129 if (!set_ros_time_enabled && clock->ros_time_is_active()) {
132 rclcpp::exceptions::throw_from_rcl_error(
133 ret,
"Failed to disable ros_time_override_status");
135 }
else if (set_ros_time_enabled && !clock->ros_time_is_active()) {
138 rclcpp::exceptions::throw_from_rcl_error(
139 ret,
"Failed to enable ros_time_override_status");
144 clock->get_clock_handle(),
147 rclcpp::exceptions::throw_from_rcl_error(
148 ret,
"Failed to set ros_time_override_status");
154 const builtin_interfaces::msg::Time::SharedPtr msg,
155 bool set_ros_time_enabled)
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);
164 void cache_last_msg(std::shared_ptr<const rosgraph_msgs::msg::Clock> msg)
174 std::mutex clock_list_lock_;
176 std::vector<rclcpp::Clock::SharedPtr> associated_clocks_;
180 bool ros_time_active_{
false};
182 std::shared_ptr<const rosgraph_msgs::msg::Clock> last_msg_set_;
189 : use_clock_thread_(use_clock_thread),
198 node_base_ || node_topics_ || node_graph_ || node_services_ ||
199 node_logging_ || node_clock_ || node_parameters_)
206 bool get_use_clock_thread()
208 return use_clock_thread_;
212 void set_use_clock_thread(
bool use_clock_thread)
214 use_clock_thread_ = use_clock_thread;
218 bool clock_thread_is_joinable()
220 return clock_executor_thread_.joinable();
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)
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;
242 logger_ = node_logging_->get_logger();
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(
254 use_sim_time_param = node_parameters_->get_parameter(use_sim_time_name).get_parameter_value();
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();
264 logger_,
"Invalid type '%s' for parameter 'use_sim_time', should be 'bool'",
266 throw std::invalid_argument(
"Invalid type for parameter 'use_sim_time', should be 'bool'");
270 parameter_subscription_ = rclcpp::AsyncParametersClient::on_parameter_event(
272 [
this](std::shared_ptr<const rcl_interfaces::msg::ParameterEvent> event) {
273 if (node_base_ !=
nullptr) {
274 this->on_parameter_event(event);
287 clocks_state_.disable_ros_time();
288 parameter_subscription_.reset();
290 node_topics_.reset();
292 node_services_.reset();
293 node_logging_.reset();
295 node_parameters_.reset();
298 void attachClock(std::shared_ptr<rclcpp::Clock> clock)
300 clocks_state_.attachClock(std::move(clock));
303 void detachClock(std::shared_ptr<rclcpp::Clock> clock)
305 clocks_state_.detachClock(std::move(clock));
312 bool use_clock_thread_;
313 std::thread clock_executor_thread_;
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};
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_;
339 void clock_cb(std::shared_ptr<const rosgraph_msgs::msg::Clock> msg)
341 if (!clocks_state_.is_ros_time_active() && SET_TRUE == this->parameter_state_) {
342 clocks_state_.enable_ros_time();
345 clocks_state_.cache_last_msg(msg);
346 auto time_msg = std::make_shared<builtin_interfaces::msg::Time>(msg->clock);
348 if (SET_TRUE == this->parameter_state_) {
349 clocks_state_.set_all_clocks(time_msg,
true);
354 void create_clock_sub()
356 std::lock_guard<std::mutex> guard(clock_sub_lock_);
357 if (clock_subscription_) {
365 rclcpp::QosPolicyKind::Depth,
366 rclcpp::QosPolicyKind::Durability,
367 rclcpp::QosPolicyKind::History,
368 rclcpp::QosPolicyKind::Reliability,
371 if (use_clock_thread_) {
372 clock_callback_group_ = node_base_->create_callback_group(
373 rclcpp::CallbackGroupType::MutuallyExclusive,
378 exec_options.context = node_base_->get_context();
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(
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);
393 clock_subscription_ = rclcpp::create_subscription<rosgraph_msgs::msg::Clock>(
398 [
this](std::shared_ptr<const rosgraph_msgs::msg::Clock> msg) {
401 if (node_base_ !=
nullptr) {
410 void destroy_clock_sub()
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_);
419 clock_subscription_.reset();
424 std::shared_ptr<ParamSubscriptionT> parameter_subscription_;
427 void on_parameter_event(std::shared_ptr<const rcl_interfaces::msg::ParameterEvent> event)
430 if (event->node != node_base_->get_fully_qualified_name()) {
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");
442 if (it.second->value.bool_value) {
443 parameter_state_ = SET_TRUE;
444 clocks_state_.enable_ros_time();
447 parameter_state_ = SET_FALSE;
449 clocks_state_.disable_ros_time();
454 {rclcpp::ParameterEventsFilter::EventType::DELETED});
455 for (
auto & it : deleted.get_events()) {
458 parameter_state_ = UNSET;
463 enum UseSimTimeParameterState {UNSET, SET_TRUE, SET_FALSE};
464 UseSimTimeParameterState parameter_state_;
468 std::shared_ptr<rclcpp::Node> node,
470 bool use_clock_thread)
478 bool use_clock_thread)
479 : constructed_use_clock_thread_(use_clock_thread),
480 constructed_qos_(qos)
482 node_state_ = std::make_shared<NodeState>(qos, use_clock_thread);
487 node_state_->set_use_clock_thread(node->get_node_options().use_clock_thread());
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());
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)
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));
520 node_state_ = std::make_shared<NodeState>(
522 constructed_use_clock_thread_);
527 node_state_->attachClock(std::move(clock));
532 node_state_->detachClock(std::move(clock));
537 return node_state_->get_use_clock_thread();
542 node_state_->set_use_clock_thread(use_clock_thread);
547 return node_state_->clock_thread_is_joinable();
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.
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.
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.
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.
RCL_PUBLIC RCL_WARN_UNUSED rcl_ret_t rcl_disable_ros_time_override(rcl_clock_t *clock)
Disable the ROS time abstraction override.
@ RCL_ROS_TIME
Use ROS time.
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.
#define RCL_RET_OK
Success return code.