17 #include <unordered_set>
21 #include "builtin_interfaces/msg/time.hpp"
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"
42 last_time_msg_(std::make_shared<builtin_interfaces::msg::Time>())
47 void enable_ros_time()
49 if (ros_time_active_) {
55 ros_time_active_ =
true;
58 set_all_clocks(last_time_msg_,
true);
62 void disable_ros_time()
64 if (!ros_time_active_) {
70 ros_time_active_ =
false;
73 auto msg = std::make_shared<builtin_interfaces::msg::Time>();
74 set_all_clocks(msg,
false);
78 bool is_ros_time_active()
const
80 return ros_time_active_;
84 void attachClock(rclcpp::Clock::SharedPtr clock)
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");
93 std::lock_guard<std::mutex> guard(clock_list_lock_);
94 associated_clocks_.insert(clock);
96 set_clock(last_time_msg_, ros_time_active_, clock);
100 void detachClock(rclcpp::Clock::SharedPtr clock)
102 std::lock_guard<std::mutex> guard(clock_list_lock_);
103 auto removed = associated_clocks_.erase(clock);
105 RCLCPP_ERROR(logger_,
"failed to remove clock");
110 static void set_clock(
111 const builtin_interfaces::msg::Time::SharedPtr msg,
112 bool set_ros_time_enabled,
113 rclcpp::Clock::SharedPtr clock)
115 std::lock_guard<std::mutex> clock_guard(clock->get_clock_mutex());
119 if (!set_ros_time_enabled && clock->ros_time_is_active()) {
122 rclcpp::exceptions::throw_from_rcl_error(
123 ret,
"Failed to disable ros_time_override_status");
125 }
else if (set_ros_time_enabled && !clock->ros_time_is_active()) {
128 rclcpp::exceptions::throw_from_rcl_error(
129 ret,
"Failed to enable ros_time_override_status");
134 clock->get_clock_handle(),
137 rclcpp::exceptions::throw_from_rcl_error(
138 ret,
"Failed to set ros_time_override_status");
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");
148 const builtin_interfaces::msg::Time::SharedPtr msg,
149 bool set_ros_time_enabled)
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);
158 void cache_last_msg(std::shared_ptr<const rosgraph_msgs::msg::Clock> msg)
160 last_time_msg_ = std::make_shared<builtin_interfaces::msg::Time>(msg->clock);
163 bool are_all_clocks_rcl_ros_time()
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());
180 std::mutex clock_list_lock_;
182 std::unordered_set<rclcpp::Clock::SharedPtr> associated_clocks_;
186 bool ros_time_active_{
false};
188 std::shared_ptr<builtin_interfaces::msg::Time> last_time_msg_{
nullptr};
195 : use_clock_thread_(use_clock_thread),
204 node_base_ || node_topics_ || node_graph_ || node_services_ ||
205 node_logging_ || node_clock_ || node_parameters_)
212 bool get_use_clock_thread()
214 return use_clock_thread_;
218 void set_use_clock_thread(
bool use_clock_thread)
220 use_clock_thread_ = use_clock_thread;
224 bool clock_thread_is_joinable()
226 return clock_executor_thread_.joinable();
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)
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;
249 logger_ = node_logging_->get_logger();
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(
261 use_sim_time_param = node_parameters_->get_parameter(use_sim_time_name).get_parameter_value();
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();
271 logger_,
"Invalid type '%s' for parameter 'use_sim_time', should be 'bool'",
273 throw std::invalid_argument(
"Invalid type for parameter 'use_sim_time', should be 'bool'");
276 on_set_parameters_callback_ = node_parameters_->add_on_set_parameters_callback(
277 std::bind(&TimeSource::NodeState::on_set_parameters,
this, std::placeholders::_1));
279 post_set_parameters_callback_ = node_parameters_->add_post_set_parameters_callback(
280 std::bind(&TimeSource::NodeState::post_set_parameters,
this, std::placeholders::_1));
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());
294 if (post_set_parameters_callback_) {
295 node_parameters_->remove_post_set_parameters_callback(post_set_parameters_callback_.get());
297 on_set_parameters_callback_.reset();
298 post_set_parameters_callback_.reset();
300 node_topics_.reset();
302 node_services_.reset();
303 node_logging_.reset();
305 node_parameters_.reset();
308 void attachClock(std::shared_ptr<rclcpp::Clock> clock)
310 clocks_state_.attachClock(std::move(clock));
313 void detachClock(std::shared_ptr<rclcpp::Clock> clock)
315 clocks_state_.detachClock(std::move(clock));
322 bool use_clock_thread_;
323 std::thread clock_executor_thread_;
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};
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_;
349 void clock_cb(std::shared_ptr<const rosgraph_msgs::msg::Clock> msg)
351 if (!clocks_state_.is_ros_time_active() && SET_TRUE == this->parameter_state_) {
352 clocks_state_.enable_ros_time();
355 clocks_state_.cache_last_msg(msg);
356 auto time_msg = std::make_shared<builtin_interfaces::msg::Time>(msg->clock);
358 if (SET_TRUE == this->parameter_state_) {
359 clocks_state_.set_all_clocks(time_msg,
true);
364 void create_clock_sub()
366 std::lock_guard<std::mutex> guard(clock_sub_lock_);
367 if (clock_subscription_) {
375 rclcpp::QosPolicyKind::Depth,
376 rclcpp::QosPolicyKind::Durability,
377 rclcpp::QosPolicyKind::History,
378 rclcpp::QosPolicyKind::Reliability,
381 if (use_clock_thread_) {
382 clock_callback_group_ = node_base_->create_callback_group(
383 rclcpp::CallbackGroupType::MutuallyExclusive,
388 exec_options.context = node_base_->get_context();
390 std::make_shared<rclcpp::executors::SingleThreadedExecutor>(exec_options);
391 if (!clock_executor_thread_.joinable()) {
392 clock_executor_thread_ = std::thread(
394 clock_executor_->add_callback_group(clock_callback_group_, node_base_);
395 clock_executor_->spin();
401 clock_subscription_ = rclcpp::create_subscription<rosgraph_msgs::msg::Clock>(
406 [
this](std::shared_ptr<const rosgraph_msgs::msg::Clock> msg) {
407 bool execute_cb =
false;
409 std::lock_guard<std::mutex> guard(node_base_lock_);
412 execute_cb = node_base_ !=
nullptr;
423 void destroy_clock_sub()
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_);
431 clock_subscription_.reset();
435 node_interfaces::OnSetParametersCallbackHandle::SharedPtr on_set_parameters_callback_{
nullptr};
438 node_interfaces::PostSetParametersCallbackHandle::SharedPtr
439 post_set_parameters_callback_{
nullptr};
442 rcl_interfaces::msg::SetParametersResult on_set_parameters(
443 const std::vector<rclcpp::Parameter> & parameters)
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;
452 "use_sim_time parameter can't be true while clocks are not all of RCL_ROS_TIME type";
455 "use_sim_time parameter can't be true while clocks are not all of RCL_ROS_TIME type");
463 void post_set_parameters(
const std::vector<rclcpp::Parameter> & parameters)
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();
473 parameter_state_ = SET_FALSE;
475 clocks_state_.disable_ros_time();
482 enum UseSimTimeParameterState {SET_TRUE, SET_FALSE};
483 UseSimTimeParameterState parameter_state_;
487 std::shared_ptr<rclcpp::Node> node,
489 bool use_clock_thread)
497 bool use_clock_thread)
498 : constructed_use_clock_thread_(use_clock_thread),
499 constructed_qos_(qos)
501 node_state_ = std::make_shared<NodeState>(qos, use_clock_thread);
506 node_state_->set_use_clock_thread(node->get_node_options().use_clock_thread());
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());
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)
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));
539 node_state_ = std::make_shared<NodeState>(
541 constructed_use_clock_thread_);
546 node_state_->attachClock(std::move(clock));
551 node_state_->detachClock(std::move(clock));
556 return node_state_->get_use_clock_thread();
561 node_state_->set_use_clock_thread(use_clock_thread);
566 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.