|
| 1 | +// Copyright 2025 TIER IV, 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, WITHOUT WARRANTIES OR |
| 11 | +// CONDITIONS OF ANY KIND, either express or implied. See the License for the specific language |
| 12 | +// governing permissions and limitations under the License. |
| 13 | + |
| 14 | +#include "topic_relay_controller_node.hpp" |
| 15 | + |
| 16 | +#include <memory> |
| 17 | +#include <string> |
| 18 | + |
| 19 | +namespace autoware::topic_relay_controller |
| 20 | +{ |
| 21 | +TopicRelayController::TopicRelayController(const rclcpp::NodeOptions & options) |
| 22 | +: Node("topic_relay_controller", options), is_relaying_(true) |
| 23 | +{ |
| 24 | + // Parameter |
| 25 | + node_param_.topic = declare_parameter<std::string>("topic"); |
| 26 | + node_param_.remap_topic = declare_parameter<std::string>("remap_topic"); |
| 27 | + node_param_.qos_depth = declare_parameter<int>("qos_depth", 1); |
| 28 | + node_param_.transient_local = declare_parameter<bool>("transient_local", false); |
| 29 | + node_param_.best_effort = declare_parameter<bool>("best_effort", false); |
| 30 | + node_param_.is_transform = (node_param_.topic == "/tf" || node_param_.topic == "/tf_static"); |
| 31 | + node_param_.enable_relay_control = declare_parameter<bool>("enable_relay_control"); |
| 32 | + if (node_param_.enable_relay_control) |
| 33 | + node_param_.srv_name = declare_parameter<std::string>("srv_name"); |
| 34 | + node_param_.enable_keep_publishing = declare_parameter<bool>("enable_keep_publishing"); |
| 35 | + if (node_param_.enable_keep_publishing) |
| 36 | + node_param_.update_rate = declare_parameter<int>("update_rate"); |
| 37 | + |
| 38 | + if (node_param_.is_transform) { |
| 39 | + node_param_.frame_id = declare_parameter<std::string>("frame_id"); |
| 40 | + node_param_.child_frame_id = declare_parameter<std::string>("child_frame_id"); |
| 41 | + } else { |
| 42 | + node_param_.topic_type = declare_parameter<std::string>("topic_type"); |
| 43 | + } |
| 44 | + |
| 45 | + // Service |
| 46 | + if (node_param_.enable_relay_control) { |
| 47 | + srv_change_relay_control_ = create_service<tier4_system_msgs::srv::ChangeTopicRelayControl>( |
| 48 | + node_param_.srv_name, |
| 49 | + [this]( |
| 50 | + const tier4_system_msgs::srv::ChangeTopicRelayControl::Request::SharedPtr request, |
| 51 | + tier4_system_msgs::srv::ChangeTopicRelayControl::Response::SharedPtr response) { |
| 52 | + is_relaying_ = request->relay_on; |
| 53 | + RCLCPP_INFO(get_logger(), "relay control: %s", is_relaying_ ? "ON" : "OFF"); |
| 54 | + response->status.success = true; |
| 55 | + }); |
| 56 | + } |
| 57 | + |
| 58 | + // Subscriber |
| 59 | + rclcpp::QoS qos = rclcpp::SystemDefaultsQoS(); |
| 60 | + if (node_param_.qos_depth > 0) { |
| 61 | + size_t qos_depth = static_cast<size_t>(node_param_.qos_depth); |
| 62 | + qos.keep_last(qos_depth); |
| 63 | + } else { |
| 64 | + RCLCPP_ERROR(get_logger(), "qos_depth must be greater than 0"); |
| 65 | + return; |
| 66 | + } |
| 67 | + |
| 68 | + if (node_param_.transient_local) { |
| 69 | + qos.transient_local(); |
| 70 | + } |
| 71 | + if (node_param_.best_effort) { |
| 72 | + qos.best_effort(); |
| 73 | + } |
| 74 | + |
| 75 | + if (node_param_.is_transform) { |
| 76 | + // Publisher |
| 77 | + pub_transform_ = this->create_publisher<tf2_msgs::msg::TFMessage>(node_param_.remap_topic, qos); |
| 78 | + |
| 79 | + sub_transform_ = this->create_subscription<tf2_msgs::msg::TFMessage>( |
| 80 | + node_param_.topic, qos, [this](tf2_msgs::msg::TFMessage::SharedPtr msg) { |
| 81 | + for (const auto & transform : msg->transforms) { |
| 82 | + if ( |
| 83 | + transform.header.frame_id != node_param_.frame_id || |
| 84 | + transform.child_frame_id != node_param_.child_frame_id || !is_relaying_) |
| 85 | + return; |
| 86 | + |
| 87 | + if (node_param_.enable_keep_publishing) { |
| 88 | + last_tf_topic_ = msg; |
| 89 | + } else { |
| 90 | + pub_transform_->publish(*msg); |
| 91 | + } |
| 92 | + } |
| 93 | + }); |
| 94 | + } else { |
| 95 | + // Publisher |
| 96 | + pub_topic_ = |
| 97 | + this->create_generic_publisher(node_param_.remap_topic, node_param_.topic_type, qos); |
| 98 | + |
| 99 | + sub_topic_ = this->create_generic_subscription( |
| 100 | + node_param_.topic, node_param_.topic_type, qos, |
| 101 | + [this]([[maybe_unused]] std::shared_ptr<rclcpp::SerializedMessage> msg) { |
| 102 | + if (!is_relaying_) return; |
| 103 | + |
| 104 | + if (node_param_.enable_keep_publishing) { |
| 105 | + last_topic_ = msg; |
| 106 | + } else { |
| 107 | + pub_topic_->publish(*msg); |
| 108 | + } |
| 109 | + }); |
| 110 | + } |
| 111 | + |
| 112 | + // Timer |
| 113 | + if (node_param_.enable_keep_publishing) { |
| 114 | + const auto update_period_ns = rclcpp::Rate(node_param_.update_rate).period(); |
| 115 | + timer_ = rclcpp::create_timer(this, get_clock(), update_period_ns, [this]() { |
| 116 | + if (!is_relaying_) return; |
| 117 | + |
| 118 | + if (node_param_.is_transform) { |
| 119 | + if (last_tf_topic_) pub_transform_->publish(*last_tf_topic_); |
| 120 | + } else { |
| 121 | + if (last_topic_) pub_topic_->publish(*last_topic_); |
| 122 | + } |
| 123 | + }); |
| 124 | + } |
| 125 | +} |
| 126 | +} // namespace autoware::topic_relay_controller |
| 127 | + |
| 128 | +#include <rclcpp_components/register_node_macro.hpp> |
| 129 | +RCLCPP_COMPONENTS_REGISTER_NODE(autoware::topic_relay_controller::TopicRelayController) |
0 commit comments