From 39c652a2eb4c0de094ac69c3871ab8a31cf99eca Mon Sep 17 00:00:00 2001 From: y-okumura Date: Thu, 24 Feb 2022 17:41:55 +0900 Subject: [PATCH] Purge old names such as "sub timing", "timing advertise" --- src/tilde/include/tilde/tilde_node.hpp | 18 +++++++----------- 1 file changed, 7 insertions(+), 11 deletions(-) diff --git a/src/tilde/include/tilde/tilde_node.hpp b/src/tilde/include/tilde/tilde_node.hpp index a49edf46e94..222d7700823 100644 --- a/src/tilde/include/tilde/tilde_node.hpp +++ b/src/tilde/include/tilde/tilde_node.hpp @@ -39,7 +39,6 @@ namespace tilde template inline constexpr bool always_false_v = false; -/// PoC of `every sub talks sub timing` class TildeNode : public rclcpp::Node { public: @@ -61,9 +60,6 @@ class TildeNode : public rclcpp::Node virtual ~TildeNode(); /// create custom subscription - /** - * This is the implementation of `first node only send path_info` strategy. - */ template< typename MessageT, typename CallbackT, @@ -160,10 +156,10 @@ class TildeNode : public rclcpp::Node // TODO(y-okumura-isp): consider race condition in multi threaded executor. // i.e. subA comes when subB callback which uses topicA is running - for (auto &[topic, tap] : timing_advertise_pubs_) { - tap->set_input_info(resolved_topic_name, input_info); + for (auto &[topic, tp] : tilde_pubs_) { + tp->set_input_info(resolved_topic_name, input_info); if (input_info->has_header_stamp) { - tap->set_explicit_subtime(resolved_topic_name, input_info); + tp->set_explicit_subtime(resolved_topic_name, input_info); } } } @@ -198,12 +194,12 @@ class TildeNode : public rclcpp::Node auto info_pub = create_publisher( info_topic, rclcpp::QoS(1), options); - auto ta_pub = std::make_shared( + auto tilde_pub = std::make_shared( info_pub, pub, get_fully_qualified_name(), this->get_clock(), steady_clock_, this->enable_tilde); - timing_advertise_pubs_[info_topic] = ta_pub; + tilde_pubs_[info_topic] = tilde_pub; tracepoint( TRACEPOINT_PROVIDER, @@ -216,8 +212,8 @@ class TildeNode : public rclcpp::Node } private: - /// topic info name vs TildePublisher (pub side) - std::map> timing_advertise_pubs_; + /// topic vs publishers + std::map> tilde_pubs_; /// node clock may be simulation time std::shared_ptr steady_clock_;